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/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__)) diff --git a/Examples/31_fixed_pitch_mhk.py b/Examples/31_fixed_pitch_mhk.py new file mode 100644 index 00000000..61cb5da4 --- /dev/null +++ b/Examples/31_fixed_pitch_mhk.py @@ -0,0 +1,234 @@ +''' +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_sim.png + + + +''' + +# 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 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 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 +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(): + + 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) + + 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(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 + # Constant power underspeed (should be the default) + 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) + + # Constant power overspeed + 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) + + # 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) + + # Linear increasing power, leveling out + 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'] = 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'] = 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) + 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=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=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=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', 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, '30_fixed_pitch_mhk_sched.png') + print('Saving figure ' + fig_fname) + plt.savefig(fig_fname,bbox_inches='tight',) + + # Write parameter input file for constant power underspeed controller + 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: + 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': TMax, + } + r.case_inputs = {} + 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]',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]',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]',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]',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, '30_fixed_pitch_mhk_sim.png') + print('Saving figure ' + fig_fname) + plt.savefig(fig_fname, bbox_inches='tight') + + +if __name__=="__main__": + main() diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index a1de2b31..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 12/11/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)} @@ -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,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]. 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.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 -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 ----------------------------------------- @@ -80,16 +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] -11.43674000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +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. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +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]. +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, [-]. @@ -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.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] @@ -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.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] @@ -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.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 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] @@ -168,8 +175,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 82138a4e..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 12/11/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)} @@ -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.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 @@ -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] -33850461.49341 ! 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_Cp_Ct_Cq.txt b/Examples/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt index da7445bf..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 @@ -1,99 +1,168 @@ # ----- 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, 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 # 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 +-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 -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 +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 -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 +-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/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 8b6e8b25..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 12/11/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)} @@ -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.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 -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.210670000000 ! 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 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] @@ -163,7 +170,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/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/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 5a03d7b6..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 12/11/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)} @@ -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.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 -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.185750000000 ! 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 ! SD_TimeActivate - Time to acitvate shutdown modes, [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 c7808254..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 12/11/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)} @@ -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.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 @@ -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.761280000000 ! 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] diff --git a/Examples/Tune_Cases/RM1_MHK_FBP.yaml b/Examples/Tune_Cases/RM1_MHK_FBP.yaml new file mode 100644 index 00000000..9ac1d933 --- /dev/null +++ b/Examples/Tune_Cases/RM1_MHK_FBP.yaml @@ -0,0 +1,74 @@ +--- # ---------------------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: 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} + 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 + VS_FBP: 3 + 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 + 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 + F_VSRefSpdCornerFreq: 0.05 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/Examples/example_inputs/minimal_DISCON.IN b/Examples/example_inputs/minimal_DISCON.IN index 1b972078..0cc91456 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 diff --git a/docs/source/examples.rst b/docs/source/examples.rst index 37d5891e..95016606 100644 --- a/docs/source/examples.rst +++ b/docs/source/examples.rst @@ -133,3 +133,4 @@ A complete list of examples is given below: .. automodule:: 28_tower_resonance .. automodule:: 29_power_control .. automodule:: 30_shutdown +.. automodule:: 31_fixed_pitch_mhk diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 1142bdba..bdc69eed 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: @@ -267,25 +270,28 @@ 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 - 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 [-] 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] @@ -315,10 +321,22 @@ ControlParameters: VS_TSRopt: <<: *real description: Power-maximizing region 2 tip-speed ratio [rad] - VS_PwrFiltF: + VS_FBP_n: + <<: *integer + description: Number of operating schedule entries for fixed blade pitch control + VS_FBP_U: <<: *real - description: Cut-off frequency of filter on generator power for power-based tsr tracking control - + 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 @@ -1039,9 +1057,6 @@ LocalVariables: VS_GenPwr: <<: *real description: Generator power [W] - VS_GenPwrF: - <<: *real - description: Generator power [W] GenSpeed: <<: *real description: Generator speed (HSS) [rad/s] @@ -1121,7 +1136,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] @@ -1139,7 +1154,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]. @@ -1155,6 +1170,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/rosco_registry/write_registry.py b/rosco/controller/rosco_registry/write_registry.py index acaf63cb..487b0bdd 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/Constants.f90 b/rosco/controller/src/Constants.f90 index 3a1ee0c2..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 @@ -37,6 +37,39 @@ 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_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 + ! PRC Mode constants INTEGER(IntKi), PARAMETER :: PRC_Comm_Constant = 0 ! Constant based on discon input INTEGER(IntKi), PARAMETER :: PRC_Comm_OpenLoop = 1 ! Based on open loop input diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 3f11dc99..962de672 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -91,7 +91,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa 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) ENDIF - + ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN LocalVar%PC_RefSpd_SS = LocalVar%PC_RefSpd_PRC - LocalVar%SS_DelOmegaF @@ -103,34 +103,58 @@ 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 == 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) - ELSE + IF (CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) THEN + ! 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 = (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 = (MAX(LocalVar%GenTq, 0.0)/CntrPar%VS_Rgn2K)**(1./2.) + + ELSE ! Generate constant speed reference if K*Omega^2 in use or torque control disabled 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 + ! Change VS Ref speed based on R_Speed LocalVar%VS_RefSpd = LocalVar%VS_RefSpd_TSR * LocalVar%PRC_R_Speed + + ! Filter reference signal + 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 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 * LocalVar%PRC_R_Speed) + ! 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 * LocalVar%PRC_R_Speed) + END IF ! 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 LocalVar%VS_RefSpd = LocalVar%VS_RefSpd - LocalVar%SS_DelOmegaF @@ -139,10 +163,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Force minimum rotor speed LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) - ! Reference error - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN - LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF - ENDIF + ! Compute speed error from reference + 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) @@ -161,16 +183,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 @@ -182,46 +205,48 @@ 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 + 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 ELSE ! Constant torque tracking - LocalVar%VS_State = 4 - LocalVar%PC_State = 1 + LocalVar%VS_State = VS_State_Region_3_ConstTrq 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 0be00e62..717b3b11 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 @@ -59,6 +59,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! 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 CALL IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) @@ -195,13 +196,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. @@ -213,21 +214,31 @@ 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 - LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque - ELSE - 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 * LocalVar%PRC_R_Torque /(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) + + ! 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 + ! PI controller LocalVar%GenTq = PIController( & @@ -236,29 +247,40 @@ 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) - + + ! 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 + LocalVar%GenTq = MIN(LocalVar%VS_ConstPwr_GenTq, LocalVar%GenTq) + ENDIF + ! 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) - - ! 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 - 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) THEN ! Region 2 + 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 == 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 - LocalVar%GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF + ELSEIF (LocalVar%VS_State == VS_State_Region_3_ConstPwr) THEN ! Region 3, constant power + 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 + ! 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 + ENDIF END IF - - ! Saturate - LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, CntrPar%VS_MaxTq) + ELSE ! VS_ControlMode of 0 LocalVar%GenTq = 0 ENDIF @@ -274,14 +296,12 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) LocalVar%GenTq = LocalVar%GenTq_SD 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/DISCON.F90 b/rosco/controller/src/DISCON.F90 index ae4fd324..62796db4 100644 --- a/rosco/controller/src/DISCON.F90 +++ b/rosco/controller/src/DISCON.F90 @@ -110,7 +110,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) diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index de2fc994..ae18b27b 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -45,7 +45,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 @@ -91,6 +90,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) @@ -370,7 +371,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 @@ -416,6 +416,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) @@ -738,7 +740,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 = 146 + nLocalVars = 147 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -749,174 +751,175 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(6) = LocalVar%n_DT LocalVarOutData(7) = LocalVar%Time_Last LocalVarOutData(8) = LocalVar%VS_GenPwr - LocalVarOutData(9) = LocalVar%VS_GenPwrF - LocalVarOutData(10) = LocalVar%GenSpeed - LocalVarOutData(11) = LocalVar%RotSpeed - LocalVarOutData(12) = LocalVar%NacHeading - LocalVarOutData(13) = LocalVar%NacVane - LocalVarOutData(14) = LocalVar%NacVaneF - LocalVarOutData(15) = LocalVar%HorWindV - LocalVarOutData(16) = LocalVar%HorWindV_F - LocalVarOutData(17) = LocalVar%rootMOOP(1) - LocalVarOutData(18) = LocalVar%rootMOOPF(1) - LocalVarOutData(19) = LocalVar%BlPitch(1) - LocalVarOutData(20) = LocalVar%BlPitchCMeas - LocalVarOutData(21) = LocalVar%Azimuth - LocalVarOutData(22) = LocalVar%OL_Azimuth - LocalVarOutData(23) = LocalVar%AzUnwrapped - LocalVarOutData(24) = LocalVar%AzError - LocalVarOutData(25) = LocalVar%GenTqAz - LocalVarOutData(26) = LocalVar%AzBuffer(1) - LocalVarOutData(27) = LocalVar%NumBl - LocalVarOutData(28) = LocalVar%FA_Acc - LocalVarOutData(29) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(30) = LocalVar%FA_AccHPF - LocalVarOutData(31) = LocalVar%FA_AccHPFI - LocalVarOutData(32) = LocalVar%FA_PitCom(1) - LocalVarOutData(33) = LocalVar%VS_RefSpd - LocalVarOutData(34) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(35) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(36) = LocalVar%VS_RefSpd_RL - LocalVarOutData(37) = LocalVar%PC_RefSpd - LocalVarOutData(38) = LocalVar%PC_RefSpd_SS - LocalVarOutData(39) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(40) = LocalVar%RotSpeedF - LocalVarOutData(41) = LocalVar%GenSpeedF - LocalVarOutData(42) = LocalVar%GenTq - LocalVarOutData(43) = LocalVar%GenTqMeas - LocalVarOutData(44) = LocalVar%GenArTq - LocalVarOutData(45) = LocalVar%GenBrTq - 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%PitCom_SD(1) - LocalVarOutData(75) = LocalVar%PitComAct(1) - LocalVarOutData(76) = LocalVar%SS_DelOmegaF - LocalVarOutData(77) = LocalVar%TestType - LocalVarOutData(78) = LocalVar%Kp_Float - LocalVarOutData(79) = LocalVar%VS_MaxTq - LocalVarOutData(80) = LocalVar%VS_LastGenTrq - LocalVarOutData(81) = LocalVar%VS_LastGenPwr - LocalVarOutData(82) = LocalVar%VS_MechGenPwr - LocalVarOutData(83) = LocalVar%VS_SpdErrAr - LocalVarOutData(84) = LocalVar%VS_SpdErrBr - LocalVarOutData(85) = LocalVar%VS_SpdErr - LocalVarOutData(86) = LocalVar%VS_State - LocalVarOutData(87) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(88) = LocalVar%WE_Vw - LocalVarOutData(89) = LocalVar%WE_Vw_F - LocalVarOutData(90) = LocalVar%WE_VwI - LocalVarOutData(91) = LocalVar%WE_VwIdot - LocalVarOutData(92) = LocalVar%WE_Op - LocalVarOutData(93) = LocalVar%WE_Op_Last - LocalVarOutData(94) = LocalVar%VS_LastGenTrqF - LocalVarOutData(95) = LocalVar%PRC_WSE_F - LocalVarOutData(96) = LocalVar%PRC_R_Speed - LocalVarOutData(97) = LocalVar%PRC_R_Torque - LocalVarOutData(98) = LocalVar%PRC_R_Pitch - LocalVarOutData(99) = LocalVar%PRC_R_Total - LocalVarOutData(100) = LocalVar%PRC_Min_Pitch - LocalVarOutData(101) = LocalVar%PS_Min_Pitch - LocalVarOutData(102) = LocalVar%OL_Index - LocalVarOutData(103) = LocalVar%SD_Trigger - LocalVarOutData(104) = LocalVar%SD_BlPitchF - LocalVarOutData(105) = LocalVar%SD_NacVaneF - LocalVarOutData(106) = LocalVar%SD_GenSpeedF - LocalVarOutData(107) = LocalVar%GenTq_SD - LocalVarOutData(108) = LocalVar%Fl_PitCom - LocalVarOutData(109) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(110) = LocalVar%FA_AccF - LocalVarOutData(111) = LocalVar%FA_Hist - LocalVarOutData(112) = LocalVar%TRA_LastRefSpd - LocalVarOutData(113) = LocalVar%VS_RefSpeed - LocalVarOutData(114) = LocalVar%PtfmTDX - LocalVarOutData(115) = LocalVar%PtfmTDY - LocalVarOutData(116) = LocalVar%PtfmTDZ - LocalVarOutData(117) = LocalVar%PtfmRDX - LocalVarOutData(118) = LocalVar%PtfmRDY - LocalVarOutData(119) = LocalVar%PtfmRDZ - LocalVarOutData(120) = LocalVar%PtfmTVX - LocalVarOutData(121) = LocalVar%PtfmTVY - LocalVarOutData(122) = LocalVar%PtfmTVZ - LocalVarOutData(123) = LocalVar%PtfmRVX - LocalVarOutData(124) = LocalVar%PtfmRVY - LocalVarOutData(125) = LocalVar%PtfmRVZ - LocalVarOutData(126) = LocalVar%PtfmTAX - LocalVarOutData(127) = LocalVar%PtfmTAY - LocalVarOutData(128) = LocalVar%PtfmTAZ - LocalVarOutData(129) = LocalVar%PtfmRAX - LocalVarOutData(130) = LocalVar%PtfmRAY - LocalVarOutData(131) = LocalVar%PtfmRAZ - LocalVarOutData(132) = LocalVar%CC_DesiredL(1) - LocalVarOutData(133) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(134) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(135) = LocalVar%StC_Input(1) - LocalVarOutData(136) = LocalVar%Flp_Angle(1) - LocalVarOutData(137) = LocalVar%RootMyb_Last(1) - LocalVarOutData(138) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(139) = LocalVar%AWC_complexangle(1) - LocalVarOutData(140) = LocalVar%ZMQ_ID - LocalVarOutData(141) = LocalVar%ZMQ_YawOffset - LocalVarOutData(142) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(143) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutData(144) = LocalVar%ZMQ_R_Speed - LocalVarOutData(145) = LocalVar%ZMQ_R_Torque - LocalVarOutData(146) = LocalVar%ZMQ_R_Pitch + 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', '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', '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'] + '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 @@ -931,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, '(147(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(147(a20,TR5:))') + WRITE(UnDb2, '(148(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(148(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -995,7 +998,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,146(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 @@ -1018,4 +1021,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 c4fe19c1..df688bfd 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, [-]. @@ -284,7 +289,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] @@ -309,18 +313,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) [-]. @@ -497,4 +503,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 ab1ec866..46e2a932 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -234,13 +234,18 @@ 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_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 + 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%VS_FBP_U, CntrPar%VS_FBP_Tau, LocalVar%HorWindV, ErrVar) + ENDIF + LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed * CntrPar%VS_GenEff/100.0 @@ -249,7 +254,7 @@ 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 LocalVar%ZMQ_ID = CntrPar%ZMQ_ID @@ -371,7 +376,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) @@ -408,7 +414,8 @@ 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 CALL ParseAry(FileLines, 'F_GenSpdNotch_Ind', CntrPar%F_GenSpdNotch_Ind, CntrPar%F_GenSpdNotch_N, accINFILE(1), ErrVar, CntrPar%F_GenSpdNotch_N == 0, UnEc) @@ -460,7 +467,13 @@ 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) + IF (ErrVar%aviFAIL < 0) RETURN + + !------------ Fixed-Pitch Region 3 Control ------------ + 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 -------------------------------- @@ -975,9 +988,9 @@ 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.' + ErrVar%ErrMsg = 'VS_ControlMode must be between 0 and 4.' ENDIF ! VS_ConstPower @@ -986,6 +999,26 @@ 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 + + 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 @@ -1131,7 +1164,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 @@ -1390,7 +1423,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 diff --git a/rosco/test/test_examples.py b/rosco/test/test_examples.py index e7994007..31eeee75 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', ] diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index c954791e..18281ae0 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'] @@ -83,7 +84,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'] @@ -99,20 +99,37 @@ def __init__(self, controller_params): self.IPC_Vramp = controller_params['IPC_Vramp'] self.ZMQ_UpdatePeriod = controller_params['ZMQ_UpdatePeriod'] - # Optional parameters without defaults + # 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 '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) + if self.PC_ControlMode != 0: + raise Exception( + 'rosco.toolbox:controller: PC_ControlMode must be 0 if VS_FBP > 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 @@ -139,6 +156,7 @@ def __init__(self, controller_params): self.f_fl_highpassfreq = controller_params['filter_params']['f_fl_highpassfreq'] self.f_ss_cornerfreq = controller_params['filter_params']['f_ss_cornerfreq'] self.f_yawerr = controller_params['filter_params']['f_yawerr'] + self.f_vs_refspd_cornerfreq = controller_params['filter_params']['f_vs_refspd_cornerfreq'] self.f_sd_pitchcornerfreq = controller_params['filter_params']['f_sd_pitchcornerfreq'] self.f_sd_yawerrorcornerfreq = controller_params['filter_params']['f_sd_yawerrorcornerfreq'] self.f_sd_genspdcornerfreq = controller_params['filter_params']['f_sd_genspdcornerfreq'] @@ -213,7 +231,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): """ @@ -235,6 +253,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 @@ -245,20 +266,65 @@ 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 + # Construct power schedule differently based on pitch control configuration + 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_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) + P_user_defined = f_P_user_defined(v) + 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) + 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 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) * 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(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 + # 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) + # 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 + + # 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(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 - # 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)) @@ -269,41 +335,63 @@ 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_FBP > 0: # Fixed blade pitch control in Region 3 + + # 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) + + # 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: # Below rated, keep lowest pitch + pitch_op[i] = min(self.min_pitch, f_cp_pitch(Cp_op[i])) + else: # above rated, keep highest pitch + pitch_op[i] = max(self.min_pitch, 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]) 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 + # 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 + 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) + omega_gen_op = omega_op * Ng + + 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: 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: + # 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 to 2.") - # 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] # 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) @@ -352,7 +440,12 @@ 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_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 -- # Careful handling of different efficiencies @@ -362,7 +455,6 @@ def tune_controller(self, turbine): # 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 -- @@ -391,7 +483,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 1c61105b..cd6e305d 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -128,15 +128,21 @@ 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) + 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 @@ -306,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} @@ -469,6 +474,35 @@ 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_power_mode: + type: number + description: Interpretation mode for VS_FBP_P (0- scale relative to rated power, 1- absolute power) + default: 0 + minimum: 0 + maximum: 1 + VS_FBP_speed_mode: + type: number + description: Overspeed or underspeed operating schedule (0- underspeed, 1- overspeed) + default: 0 + minimum: 0 + maximum: 1 + 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 + items: + type: number + minimum: 0 + uniqueItems: True + 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 VS_FBP_power_mode + unit: none + items: + type: number + minimum: 0 + default: [1.0, 1.0] filter_params: type: object @@ -525,6 +559,12 @@ properties: type: number default: 0.41888 unit: rad/s + 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.209440 open_loop: type: object default: {} @@ -636,13 +676,18 @@ 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) 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) @@ -742,6 +787,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 @@ -853,7 +902,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 @@ -881,11 +930,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/ofTools/case_gen/run_FAST.py b/rosco/toolbox/ofTools/case_gen/run_FAST.py index 160a4d40..98305d7a 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 @@ -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 @@ -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 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 diff --git a/rosco/toolbox/turbine.py b/rosco/toolbox/turbine.py index 5b3e18b1..01e2f0af 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.') @@ -302,8 +302,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, 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 omega_array = (TSR_initial * ws_array / self.rotor_radius) * RadSec2rpm @@ -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): ''' diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 435de1e4..1178e96e 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -94,10 +94,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']))) @@ -136,6 +137,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('{:<13.5f} ! F_VSRefSpdCornerFreq - {}\n'.format(float(rosco_vt['F_VSRefSpdCornerFreq']),input_descriptions['F_VSRefSpdCornerFreq'])) file.write('\n') file.write('!------- BLADE PITCH CONTROL ----------------------------------------------\n') @@ -177,7 +179,12 @@ 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} ! 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'])) @@ -496,6 +503,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) @@ -536,6 +544,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 @@ -575,6 +584,11 @@ 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['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