diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index c57c562d..fed55e82 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -13,6 +13,16 @@ _Select the appropriate type(s) that describe this PR_ - [ ] Maintenance update - [ ] Other (please describe) +TODO Items General: +- [ ] Add example/test for new feature +- [ ] Update registry +- [ ] Run testing + +TODO Items API Change: +- [ ] Update docs with API change +- [ ] Run update_discons.py +- [ ] Update DISCON schema + ## Github issues addressed, if one exists ## Examples/Testing, if applicable diff --git a/Examples/example_01.py b/Examples/example_01.py index 6c4c3e39..14cf3bbd 100644 --- a/Examples/example_01.py +++ b/Examples/example_01.py @@ -34,7 +34,7 @@ path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), dev_branch=True, - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) # Print some basic turbine info diff --git a/Examples/example_04.py b/Examples/example_04.py index 229c176b..69da8392 100644 --- a/Examples/example_04.py +++ b/Examples/example_04.py @@ -34,11 +34,12 @@ controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file +cp_filename = os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), dev_branch=True, - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + rot_source='txt',txt_filename= cp_filename ) # Tune controller @@ -46,7 +47,10 @@ # Write parameter input file param_file = os.path.join(this_dir,'DISCON.IN') -write_DISCON(turbine,controller,param_file=param_file, txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename'])) +write_DISCON(turbine,controller, +param_file=param_file, +txt_filename=cp_filename +) # Plot gain schedule fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) diff --git a/Examples/example_05.py b/Examples/example_05.py index deb50bd0..9555aeb3 100644 --- a/Examples/example_05.py +++ b/Examples/example_05.py @@ -55,11 +55,12 @@ # controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file +cp_filename = os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), dev_branch=True, - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + rot_source='txt',txt_filename=cp_filename ) # Tune controller @@ -68,7 +69,11 @@ # Write parameter input file param_filename = os.path.join(this_dir,'DISCON.IN') -write_DISCON(turbine,controller,param_file=param_filename, txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename'])) +write_DISCON( + turbine,controller, + param_file=param_filename, + txt_filename=cp_filename + ) # Load controller library diff --git a/Examples/example_07.py b/Examples/example_07.py index 4626e794..3fc16f85 100644 --- a/Examples/example_07.py +++ b/Examples/example_07.py @@ -45,7 +45,7 @@ path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), dev_branch=True, - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) # Tune controller controller.tune_controller(turbine) diff --git a/Examples/example_10.py b/Examples/example_10.py index c710711f..7a7b0693 100644 --- a/Examples/example_10.py +++ b/Examples/example_10.py @@ -34,7 +34,6 @@ # Load turbine data from openfast model turbine = ROSCO_turbine.Turbine(turbine_params) -# turbine.load_from_fast(path_params['FAST_InputFile'],path_params['FAST_directory'],dev_branch=True,rot_source='txt',txt_filename=path_params['rotor_performance_filename']) turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(this_dir,path_params['FAST_directory']),dev_branch=True) diff --git a/Examples/example_11.py b/Examples/example_11.py index f8a9b199..6b1e9680 100644 --- a/Examples/example_11.py +++ b/Examples/example_11.py @@ -46,7 +46,7 @@ os.path.join(this_dir,path_params['FAST_directory']), dev_branch=True, rot_source='txt', - txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) # Tune controller diff --git a/Examples/example_15.py b/Examples/example_15.py new file mode 100644 index 00000000..eb53752a --- /dev/null +++ b/Examples/example_15.py @@ -0,0 +1,47 @@ +''' +----------- Example_15 -------------- +Use the runFAST scripts to set up an example, use pass through in yaml +------------------------------------- + +In this example: + - use run_FAST_ROSCO class to set up a test case + +''' + +import os +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + + +def main(): + # Simulation config + sim_config = 7 + + r = run_FAST_ROSCO() + + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL5MW_PassThrough.yaml') + run_dir = os.path.join(example_out_dir,'15_PassThrough') + os.makedirs(run_dir,exist_ok=True) + + # RAAW FAD set up + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step + r.wind_case_opts = { + 'U_start': [10], + 'U_end': [15], + 'wind_dir': run_dir + } + r.save_dir = run_dir + + r.run_FAST() + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/run_examples.py b/Examples/run_examples.py index 181f4239..a0b8a30a 100644 --- a/Examples/run_examples.py +++ b/Examples/run_examples.py @@ -18,7 +18,8 @@ 'example_11', 'example_12', 'example_13', - 'example_14' + 'example_14', + 'example_15', ] def execute_script(fscript): diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index cff72dd0..ba723bc4 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -436,7 +436,389 @@ properties: default: 0.707 minimum: 0 - + DISCON: + type: object + description: These are pass-through parameters for the DISCON.IN file. Use with caution. + default: {} + properties: + LoggingLevel: + type: number + description: (0- write no debug files, 1- write standard output .dbg-file, 2- write standard output .dbg-file and complete avrSWAP-array .dbg2-file) + F_LPFType: + type: number + description: 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals + F_NotchType: + type: number + description: Notch on the measured generator speed and/or tower fore-aft motion (for floating) (0- disable, 1- generator speed, 2- tower-top fore-aft motion, 3- generator speed and tower-top fore-aft motion) + IPC_ControlMode: + type: number + description: Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) (0- off, 1- 1P reductions, 2- 1P+2P reductions) + VS_ControlMode: + type: number + description: Generator torque control mode in above rated conditions (0- constant torque, 1- constant power, 2- TSR tracking PI control with constant torque, 3- TSR tracking PI control with constant power) + PC_ControlMode: + type: number + description: Blade pitch control mode (0- No pitch, fix to fine pitch, 1- active PI blade pitch control) + Y_ControlMode: + type: number + description: Yaw control mode (0- no yaw control, 1- yaw rate control, 2- yaw-by-IPC) + SS_Mode: + type: number + description: Setpoint Smoother mode (0- no setpoint smoothing, 1- introduce setpoint smoothing) + WE_Mode: + type: number + description: Wind speed estimator mode (0- One-second low pass filtered hub height wind speed, 1- Immersion and Invariance Estimator, 2- Extended Kalman Filter) + PS_Mode: + type: number + description: Pitch saturation mode (0- no pitch saturation, 1- implement pitch saturation) + SD_Mode: + type: number + description: Shutdown mode (0- no shutdown procedure, 1- pitch to max pitch at shutdown) + Fl_Mode: + type: number + description: Floating specific feedback mode (0- no nacelle velocity feedback, 1- feed back translational velocity, 2- feed back rotational veloicty) + Flp_Mode: + type: number + description: Flap control mode (0- no flap control, 1- steady state flap angle, 2- Proportional flap control) + F_LPFCornerFreq: + type: number + description: Corner frequency (-3dB point) in the low-pass filters, + units: rad/s + F_LPFDamping: + type: number + description: Damping coefficient (used only when F_FilterType = 2 [-] + F_NotchCornerFreq: + type: number + description: Natural frequency of the notch filter, + units: rad/s + F_NotchBetaNumDen: + type: array + items: + type: number + description: Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] + F_SSCornerFreq: + type: number + description: Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, + units: rad/s. + F_WECornerFreq: + type: number + description: Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate + units: rad/s. + F_FlCornerFreq: + type: array + items: + type: number + description: Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control + units: rad/s + F_FlHighPassFreq: + type: number + description: Natural frequency of first-order high-pass filter for nacelle fore-aft motion + units: rad/s + F_FlpCornerFreq: + type: array + items: + 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 + PC_GS_n: + type: number + description: Amount of gain-scheduling table entries + PC_GS_angles: + type: array + items: + type: number + description: Gain-schedule table- pitch angles + units: rad + PC_GS_KP: + type: array + items: + type: number + description: Gain-schedule table- pitch controller kp gains + units: s + PC_GS_KI: + type: array + items: + type: number + description: Gain-schedule table- pitch controller ki gains + PC_GS_KD: + type: array + items: + type: number + description: Gain-schedule table- pitch controller kd gains + PC_GS_TF: + type: array + items: + type: number + description: Gain-schedule table- pitch controller tf gains (derivative filter) + PC_MaxPit: + type: number + description: Maximum physical pitch limit, + units: rad + PC_MinPit: + type: number + description: Minimum physical pitch limit, + units: rad + PC_MaxRat: + type: number + description: Maximum pitch rate (in absolute value) in pitch controller + units: rad/s. + PC_MinRat: + type: number + description: Minimum pitch rate (in absolute value) in pitch controller + units: rad/s. + PC_RefSpd: + type: number + description: Desired (reference) HSS speed for pitch controller + units: rad/s. + PC_FinePit: + type: number + description: Record 5- Below-rated pitch angle set-point + units: rad + PC_Switch: + type: number + description: Angle above lowest minimum pitch angle for switch + units: rad + IPC_IntSat: + type: number + description: Integrator saturation (maximum signal amplitude contribution to pitch from IPC) + units: rad + IPC_KP: + type: array + items: + type: number + description: Proportional gain for the individual pitch controller- first parameter for 1P reductions, second for 2P reductions, [-] + IPC_KI: + type: array + items: + type: number + description: Integral gain for the individual pitch controller- first parameter for 1P reductions, second for 2P reductions, [-] + IPC_aziOffset: + type: array + items: + type: number + description: Phase offset added to the azimuth angle for the individual pitch controller + units: rad + IPC_CornerFreqAct: + type: number + description: Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal (0- Disable) + units: rad/s + VS_GenEff: + type: number + description: Generator efficiency mechanical power -> electrical power, should match the efficiency defined in the generator properties + units: percent + VS_ArSatTq: + type: number + description: Above rated generator torque PI control saturation + units: Nm + VS_MaxRat: + type: number + description: Maximum torque rate (in absolute value) in torque controller + units: Nm/s + VS_MaxTq: + type: number + description: Maximum generator torque in Region 3 (HSS side) + units: Nm + VS_MinTq: + type: number + description: Minimum generator torque (HSS side) + units: Nm + VS_MinOMSpd: + type: number + description: Minimum generator speed + units: rad/s + VS_Rgn2K: + type: number + description: Generator torque constant in Region 2 (HSS side) + units: Nm/(rad/s)^2 + VS_RtPwr: + type: number + description: Wind turbine rated power + units: W + VS_RtTq: + type: number + description: Rated torque + units: Nm + VS_RefSpd: + type: number + description: Rated generator speed + units: rad/s + VS_n: + type: number + description: Number of generator PI torque controller gains + VS_KP: + type: number + description: Proportional gain for generator PI torque controller. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) + VS_KI: + type: number + description: Integral gain for generator PI torque controller (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) + units: s + VS_TSRopt: + type: number + description: Power-maximizing region 2 tip-speed-ratio + units: rad + SS_VSGain: + type: number + description: Variable speed torque controller setpoint smoother gain + SS_PCGain: + type: number + description: Collective pitch controller setpoint smoother gain + WE_BladeRadius: + type: number + description: Blade length (distance from hub center to blade tip) + units: m + WE_CP_n: + type: number + description: Amount of parameters in the Cp array + WE_CP: + type: array + items: + type: number + description: Parameters that define the parameterized CP(lambda) function + WE_Gamma: + type: number + description: Adaption gain of the wind speed estimator algorithm + units: m/rad + WE_GearboxRatio: + type: number + description: Gearbox ratio, >=1 + WE_Jtot: + type: number + description: Total drivetrain inertia, including blades, hub and casted generator inertia to LSS + units: kg m^2 + WE_RhoAir: + type: number + description: Air density + units: kg m^-3 + PerfFileName: + type: string + description: File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) + PerfTableSize: + type: number + description: Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios + WE_FOPoles_N: + type: number + description: Number of first-order system poles used in EKF + WE_FOPoles_v: + type: array + items: + type: number + description: Wind speeds corresponding to first-order system poles + units: m/s + WE_FOPoles: + type: array + items: + type: number + description: First order system poles + units: 1/s + Y_ErrThresh: + type: number + description: Yaw error threshold. Turbine begins to yaw when it passes this + units: rad^2 s + Y_IPC_IntSat: + type: number + description: Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC) + units: rad + Y_IPC_n: + type: number + description: Number of controller gains (yaw-by-IPC) + Y_IPC_KP: + type: number + description: Yaw-by-IPC proportional controller gain Kp + Y_IPC_KI: + type: number + description: Yaw-by-IPC integral controller gain Ki + Y_IPC_omegaLP: + type: number + description: Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error + units: rad/s. + Y_IPC_zetaLP: + type: number + description: Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error. + Y_MErrSet: + type: number + description: Yaw alignment error, set point + units: rad + Y_omegaLPFast: + type: number + description: Corner frequency fast low pass filter, 1.0 + units: rad/s + Y_omegaLPSlow: + type: number + description: Corner frequency slow low pass filter, 1/60 + units: rad/s + Y_Rate: + type: number + description: Yaw rate + units: rad/s + FA_KI: + type: number + description: Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on + units: rad s/m + FA_HPFCornerFreq: + type: number + description: Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal + units: rad/s + FA_IntSat: + type: number + description: Integrator saturation (maximum signal amplitude contribution to pitch from FA damper) + units: rad + PS_BldPitchMin_N: + type: number + description: Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + PS_WindSpeeds: + type: array + items: + type: number + description: Wind speeds corresponding to minimum blade pitch angles + units: m/s + PS_BldPitchMin: + type: array + items: + type: number + description: Minimum blade pitch angles + units: rad + SD_MaxPit: + type: number + description: Maximum blade pitch angle to initiate shutdown + units: rad + SD_CornerFreq: + type: number + description: Cutoff Frequency for first order low-pass filter for blade pitch angle + units: rad/s + Fl_Kp: + type: number + description: Nacelle velocity proportional feedback gain + units: s + Flp_Angle: + type: number + description: Initial or steady state flap angle + units: rad + Flp_Kp: + type: number + description: Blade root bending moment proportional gain for flap control + units: s + Flp_Ki: + type: number + description: Flap displacement integral gain for flap control + Flp_MaxPit: + type: number + description: Maximum (and minimum) flap pitch angle + units: rad + OL_Filename: + type: string + description: Input file with open loop timeseries (absolute path or relative to this file) + Ind_Breakpoint: + type: number + description: The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) + Ind_BldPitch: + type: number + description: The column in OL_Filename that contains the blade pitch input in rad + Ind_GenTq: + type: number + description: The column in OL_Filename that contains the generator torque in Nm + Ind_YawRate: + type: number + description: The column in OL_Filename that contains the generator torque in Nm linmodel_tuning: type: object diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index abcec83a..64ccf8dd 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -149,26 +149,22 @@ def simp_step(**wind_case_opts): if 'T_Max' in wind_case_opts: T_max = wind_case_opts['T_Max'] - else: - # Default Runtime + else: #default T_max = 300. if 'U_start' in wind_case_opts: U_start = wind_case_opts['U_start'] - else: - # Default Runtime + else: #default U_start = [16] if 'U_end' in wind_case_opts: U_end = wind_case_opts['U_end'] - else: - # Default Runtime + else: #default U_end = [17] if 'T_step' in wind_case_opts: T_step = wind_case_opts['T_step'] - else: - # Default Runtime + else: #default T_step = 150 # Step Wind Setup diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index 71a73e78..26c9e36c 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -62,8 +62,12 @@ def run_FAST(self): controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file - cp_filename = os.path.join(path_params['FAST_directory'],path_params['rotor_performance_filename']) tune_yaml_dir = os.path.split(self.tuning_yaml)[0] + cp_filename = os.path.join( + tune_yaml_dir, + path_params['FAST_directory'], + path_params['rotor_performance_filename'] + ) turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(tune_yaml_dir,path_params['FAST_directory']), \ dev_branch=True,rot_source='txt',\ diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 031e2e11..b084a904 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -495,6 +495,11 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PA_CornerFreq'] = controller.PA_CornerFreq DISCON_dict['PA_Damping'] = controller.PA_Damping + # Add pass through here + for param, value in controller.controller_params['DISCON'].items(): + DISCON_dict[param] = value + + return DISCON_dict diff --git a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_ServoDyn.dat b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_ServoDyn.dat index a7f094dd..86351f2d 100644 --- a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_ServoDyn.dat +++ b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_ServoDyn.dat @@ -81,7 +81,7 @@ True GenTiStp - Method to stop the generator {T: timed using TimGen false DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] 9999.9 BPCutoff - Cutoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] 0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] - 0 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] + 1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] 0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] 0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] 0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] diff --git a/Tune_Cases/IEA15MW.yaml b/Tune_Cases/IEA15MW.yaml index 7eaf1d8d..fa2aeb57 100644 --- a/Tune_Cases/IEA15MW.yaml +++ b/Tune_Cases/IEA15MW.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/NREL5MW.yaml b/Tune_Cases/NREL5MW.yaml index 21f5acab..9ad252dc 100644 --- a/Tune_Cases/NREL5MW.yaml +++ b/Tune_Cases/NREL5MW.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'NREL-5MW.fst' # Name of *.fst file FAST_directory: '../Test_Cases/NREL-5MW' # Main OpenFAST model directory, where the *.fst lives # Optional - rotor_performance_filename: '../Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: 'Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/NREL5MW_PassThrough.yaml b/Tune_Cases/NREL5MW_PassThrough.yaml new file mode 100644 index 00000000..2ad3be80 --- /dev/null +++ b/Tune_Cases/NREL5MW_PassThrough.yaml @@ -0,0 +1,64 @@ +--- # ---------------------NREL Generic controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: NREL 5MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'NREL-5MW.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/NREL-5MW' # Main OpenFAST model directory, where the *.fst lives + # Optional + rotor_performance_filename: 'Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 38677040.613 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 1.26711 # Rated rotor speed [rad/s] + v_min: 3.0 # Cut-in wind speed [m/s] + v_rated: 11.4 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] + max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 5000000. # Rated Power [W] + bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] + # Optional + # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 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: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 1 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 0 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + # Controller parameters + zeta_pc: 0.7 # Pitch controller desired damping ratio [-] + omega_pc: 0.6 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.7 # Torque controller desired damping ratio [-] + omega_vs: 0.15 # Torque controller desired natural frequency [rad/s] + twr_freq: 0.4499 # Tower natural frequency [rad/s] + ptfm_freq: 0.2325 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) + # Optional + ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} + sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} + + DISCON: + IPC_ControlMode: 2 + IPC_Vramp: [10,14] + IPC_IntSat: 0.2 + IPC_KI: [1.e-8, 0] + IPC_aziOffset: [0.5236,0] + VS_MaxTq: 44170.325 + PC_GS_n: 2 + PC_GS_angles: [0, 0.4] + PC_GS_KP: [-.02, -0.003] + PC_GS_KI: [-.008, -.002] + PC_GS_KD: [0, 0] + PC_GS_TF: [0, 0] \ No newline at end of file diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index d041f0e3..59eccc7d 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -201,6 +201,15 @@ controller_params *Minimum* = 0 *Maximum* = 1 +:code:`TD_Mode` : Float + Tower damper mode (0- no tower damper, 1- feed back translational + nacelle accelleration to pitch angle + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 1 + + :code:`Fl_Mode` : Float Floating specific feedback mode (0- no nacelle velocity feedback, 1 - nacelle velocity feedback, 2 - nacelle pitching acceleration @@ -230,6 +239,15 @@ controller_params *Minimum* = 0 *Maximum* = 2 +:code:`PA_Mode` : Float + Pitch actuator mode {0 - not used, 1 - first order filter, 2 - + second order filter} + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 2 + + :code:`U_pc` : Array of Floats List of wind speeds to schedule pitch control zeta and omega @@ -363,6 +381,13 @@ controller_params *Minimum* = 0 +:code:`max_torque_factor` : Float + Maximum torque = rated torque * max_torque_factor + + *Default* = 1.1 + + *Minimum* = 0 + :code:`IPC_Kp1p` : Float, s Proportional gain for IPC, 1P [s] @@ -391,6 +416,13 @@ controller_params *Minimum* = 0 +:code:`IPC_Vramp` : Array of Floats + wind speeds for IPC cut-in sigma function [m/s] + + *Default* = [0.0, 0.0] + + *Minimum* = 0.0 + filter_params @@ -475,6 +507,368 @@ open_loop *Default* = 0 +:code:`PA_CornerFreq` : Float, rad/s + Pitch actuator natural frequency [rad/s] + + *Default* = 3.14 + + *Minimum* = 0 + +:code:`PA_Damping` : Float + Pitch actuator damping ratio [-] + + *Default* = 0.707 + + *Minimum* = 0 + + + +DISCON +######################################## + + +These are pass-through parameters for the DISCON.IN file. Use with caution. + +:code:`LoggingLevel` : Float + (0- write no debug files, 1- write standard output .dbg-file, 2- + write standard output .dbg-file and complete avrSWAP-array + .dbg2-file) + +:code:`F_LPFType` : Float + 1- first-order low-pass filter, 2- second-order low-pass filter + (currently filters generator speed and pitch control signals + +:code:`F_NotchType` : Float + Notch on the measured generator speed and/or tower fore-aft motion + (for floating) (0- disable, 1- generator speed, 2- tower-top fore- + aft motion, 3- generator speed and tower-top fore-aft motion) + +:code:`IPC_ControlMode` : Float + Turn Individual Pitch Control (IPC) for fatigue load reductions + (pitch contribution) (0- off, 1- 1P reductions, 2- 1P+2P + reductions) + +:code:`VS_ControlMode` : Float + Generator torque control mode in above rated conditions (0- + constant torque, 1- constant power, 2- TSR tracking PI control + with constant torque, 3- TSR tracking PI control with constant + power) + +:code:`PC_ControlMode` : Float + Blade pitch control mode (0- No pitch, fix to fine pitch, 1- + active PI blade pitch control) + +:code:`Y_ControlMode` : Float + Yaw control mode (0- no yaw control, 1- yaw rate control, 2- yaw- + by-IPC) + +:code:`SS_Mode` : Float + Setpoint Smoother mode (0- no setpoint smoothing, 1- introduce + setpoint smoothing) + +:code:`WE_Mode` : Float + Wind speed estimator mode (0- One-second low pass filtered hub + height wind speed, 1- Immersion and Invariance Estimator, 2- + Extended Kalman Filter) + +:code:`PS_Mode` : Float + Pitch saturation mode (0- no pitch saturation, 1- implement pitch + saturation) + +:code:`SD_Mode` : Float + Shutdown mode (0- no shutdown procedure, 1- pitch to max pitch at + shutdown) + +:code:`Fl_Mode` : Float + Floating specific feedback mode (0- no nacelle velocity feedback, + 1- feed back translational velocity, 2- feed back rotational + veloicty) + +:code:`Flp_Mode` : Float + Flap control mode (0- no flap control, 1- steady state flap angle, + 2- Proportional flap control) + +:code:`F_LPFCornerFreq` : Float, rad/s + Corner frequency (-3dB point) in the low-pass filters, + +:code:`F_LPFDamping` : Float + Damping coefficient (used only when F_FilterType = 2 [-] + +:code:`F_NotchCornerFreq` : Float, rad/s + Natural frequency of the notch filter, + +:code:`F_NotchBetaNumDen` : Array of Floats + Two notch damping values (numerator and denominator, resp) - + determines the width and depth of the notch, [-] + +:code:`F_SSCornerFreq` : Float, rad/s. + Corner frequency (-3dB point) in the first order low pass filter + for the setpoint smoother, + +:code:`F_WECornerFreq` : Float, rad/s. + Corner frequency (-3dB point) in the first order low pass filter + for the wind speed estimate + +:code:`F_FlCornerFreq` : Array of Floats + Natural frequency and damping in the second order low pass filter + of the tower-top fore-aft motion for floating feedback control + +:code:`F_FlHighPassFreq` : Float, rad/s + Natural frequency of first-order high-pass filter for nacelle + fore-aft motion + +:code:`F_FlpCornerFreq` : Array of Floats + Corner frequency and damping in the second order low pass filter + of the blade root bending moment for flap control + +:code:`PC_GS_n` : Float + Amount of gain-scheduling table entries + +:code:`PC_GS_angles` : Array of Floats + Gain-schedule table- pitch angles + +:code:`PC_GS_KP` : Array of Floats + Gain-schedule table- pitch controller kp gains + +:code:`PC_GS_KI` : Array of Floats + Gain-schedule table- pitch controller ki gains + +:code:`PC_GS_KD` : Array of Floats + Gain-schedule table- pitch controller kd gains + +:code:`PC_GS_TF` : Array of Floats + Gain-schedule table- pitch controller tf gains (derivative filter) + +:code:`PC_MaxPit` : Float, rad + Maximum physical pitch limit, + +:code:`PC_MinPit` : Float, rad + Minimum physical pitch limit, + +:code:`PC_MaxRat` : Float, rad/s. + Maximum pitch rate (in absolute value) in pitch controller + +:code:`PC_MinRat` : Float, rad/s. + Minimum pitch rate (in absolute value) in pitch controller + +:code:`PC_RefSpd` : Float, rad/s. + Desired (reference) HSS speed for pitch controller + +:code:`PC_FinePit` : Float, rad + Record 5- Below-rated pitch angle set-point + +:code:`PC_Switch` : Float, rad + Angle above lowest minimum pitch angle for switch + +:code:`IPC_IntSat` : Float, rad + Integrator saturation (maximum signal amplitude contribution to + pitch from IPC) + +:code:`IPC_KP` : Array of Floats + Proportional gain for the individual pitch controller- first + parameter for 1P reductions, second for 2P reductions, [-] + +:code:`IPC_KI` : Array of Floats + Integral gain for the individual pitch controller- first parameter + for 1P reductions, second for 2P reductions, [-] + +:code:`IPC_aziOffset` : Array of Floats + Phase offset added to the azimuth angle for the individual pitch + controller + +:code:`IPC_CornerFreqAct` : Float, rad/s + Corner frequency of the first-order actuators model, to induce a + phase lag in the IPC signal (0- Disable) + +:code:`VS_GenEff` : Float, percent + Generator efficiency mechanical power -> electrical power, should + match the efficiency defined in the generator properties + +:code:`VS_ArSatTq` : Float, Nm + Above rated generator torque PI control saturation + +:code:`VS_MaxRat` : Float, Nm/s + Maximum torque rate (in absolute value) in torque controller + +:code:`VS_MaxTq` : Float, Nm + Maximum generator torque in Region 3 (HSS side) + +:code:`VS_MinTq` : Float, Nm + Minimum generator torque (HSS side) + +:code:`VS_MinOMSpd` : Float, rad/s + Minimum generator speed + +:code:`VS_Rgn2K` : Float, Nm/(rad/s)^2 + Generator torque constant in Region 2 (HSS side) + +:code:`VS_RtPwr` : Float, W + Wind turbine rated power + +:code:`VS_RtTq` : Float, Nm + Rated torque + +:code:`VS_RefSpd` : Float, rad/s + Rated generator speed + +:code:`VS_n` : Float + Number of generator PI torque controller gains + +:code:`VS_KP` : Float + Proportional gain for generator PI torque controller. (Only used + in the transitional 2.5 region if VS_ControlMode =/ 2) + +:code:`VS_KI` : Float, s + Integral gain for generator PI torque controller (Only used in + the transitional 2.5 region if VS_ControlMode =/ 2) + +:code:`VS_TSRopt` : Float, rad + Power-maximizing region 2 tip-speed-ratio + +:code:`SS_VSGain` : Float + Variable speed torque controller setpoint smoother gain + +:code:`SS_PCGain` : Float + Collective pitch controller setpoint smoother gain + +:code:`WE_BladeRadius` : Float, m + Blade length (distance from hub center to blade tip) + +:code:`WE_CP_n` : Float + Amount of parameters in the Cp array + +:code:`WE_CP` : Array of Floats + Parameters that define the parameterized CP(lambda) function + +:code:`WE_Gamma` : Float, m/rad + Adaption gain of the wind speed estimator algorithm + +:code:`WE_GearboxRatio` : Float + Gearbox ratio, >=1 + +:code:`WE_Jtot` : Float, kg m^2 + Total drivetrain inertia, including blades, hub and casted + generator inertia to LSS + +:code:`WE_RhoAir` : Float, kg m^-3 + Air density + +:code:`PerfFileName` : String + File containing rotor performance tables (Cp,Ct,Cq) (absolute path + or relative to this file) + +:code:`PerfTableSize` : Float + Size of rotor performance tables, first number refers to number of + blade pitch angles, second number referse to number of tip-speed + ratios + +:code:`WE_FOPoles_N` : Float + Number of first-order system poles used in EKF + +:code:`WE_FOPoles_v` : Array of Floats + Wind speeds corresponding to first-order system poles + +:code:`WE_FOPoles` : Array of Floats + First order system poles + +:code:`Y_ErrThresh` : Float, rad^2 s + Yaw error threshold. Turbine begins to yaw when it passes this + +:code:`Y_IPC_IntSat` : Float, rad + Integrator saturation (maximum signal amplitude contribution to + pitch from yaw-by-IPC) + +:code:`Y_IPC_n` : Float + Number of controller gains (yaw-by-IPC) + +:code:`Y_IPC_KP` : Float + Yaw-by-IPC proportional controller gain Kp + +:code:`Y_IPC_KI` : Float + Yaw-by-IPC integral controller gain Ki + +:code:`Y_IPC_omegaLP` : Float, rad/s. + Low-pass filter corner frequency for the Yaw-by-IPC controller to + filtering the yaw alignment error + +:code:`Y_IPC_zetaLP` : Float + Low-pass filter damping factor for the Yaw-by-IPC controller to + filtering the yaw alignment error. + +:code:`Y_MErrSet` : Float, rad + Yaw alignment error, set point + +:code:`Y_omegaLPFast` : Float, rad/s + Corner frequency fast low pass filter, 1.0 + +:code:`Y_omegaLPSlow` : Float, rad/s + Corner frequency slow low pass filter, 1/60 + +:code:`Y_Rate` : Float, rad/s + Yaw rate + +:code:`FA_KI` : Float, rad s/m + Integral gain for the fore-aft tower damper controller, -1 = off / + >0 = on + +:code:`FA_HPFCornerFreq` : Float, rad/s + Corner frequency (-3dB point) in the high-pass filter on the fore- + aft acceleration signal + +:code:`FA_IntSat` : Float, rad + Integrator saturation (maximum signal amplitude contribution to + pitch from FA damper) + +:code:`PS_BldPitchMin_N` : Float + Number of values in minimum blade pitch lookup table (should equal + number of values in PS_WindSpeeds and PS_BldPitchMin) + +:code:`PS_WindSpeeds` : Array of Floats + Wind speeds corresponding to minimum blade pitch angles + +:code:`PS_BldPitchMin` : Array of Floats + Minimum blade pitch angles + +:code:`SD_MaxPit` : Float, rad + Maximum blade pitch angle to initiate shutdown + +:code:`SD_CornerFreq` : Float, rad/s + Cutoff Frequency for first order low-pass filter for blade pitch + angle + +:code:`Fl_Kp` : Float, s + Nacelle velocity proportional feedback gain + +:code:`Flp_Angle` : Float, rad + Initial or steady state flap angle + +:code:`Flp_Kp` : Float, s + Blade root bending moment proportional gain for flap control + +:code:`Flp_Ki` : Float + Flap displacement integral gain for flap control + +:code:`Flp_MaxPit` : Float, rad + Maximum (and minimum) flap pitch angle + +:code:`OL_Filename` : String + Input file with open loop timeseries (absolute path or relative to + this file) + +:code:`Ind_Breakpoint` : Float + The column in OL_Filename that contains the breakpoint (time if + OL_Mode = 1) + +:code:`Ind_BldPitch` : Float + The column in OL_Filename that contains the blade pitch input in + rad + +:code:`Ind_GenTq` : Float + The column in OL_Filename that contains the generator torque in Nm + +:code:`Ind_YawRate` : Float + The column in OL_Filename that contains the generator torque in Nm + linmodel_tuning