From 911922f29a10c91f4afd853e4648d709d4a4024b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 9 Jul 2021 13:47:29 -0600 Subject: [PATCH] Squashed 'ROSCO/' changes from 81b34264..f4fa4fd0 f4fa4fd0 Pass Through Kp_float (#57) fc585199 Merge pull request #56 from dzalkind/mult_omega c8836797 Merge branch 'oneROSCO2' into mult_omega bd78d4ab Fix tests: 5MW U_pc and 06 example dir ed054d9a Add omega vs. windspeed functionality git-subtree-dir: ROSCO git-subtree-split: f4fa4fd0972767ad5117f8293490357b81bcf7aa --- Examples/example_04.py | 21 +++-- Examples/example_06.py | 34 +++++++ ROSCO_toolbox/controller.py | 111 ++++++++++++++++++++--- ROSCO_toolbox/inputs/toolbox_schema.yaml | 32 +++++-- ROSCO_toolbox/turbine.py | 2 +- Tune_Cases/BAR.yaml | 5 +- Tune_Cases/DTU10MW.yaml | 5 +- Tune_Cases/IEA15MW.yaml | 5 +- Tune_Cases/NREL5MW.yaml | 5 +- 9 files changed, 182 insertions(+), 38 deletions(-) diff --git a/Examples/example_04.py b/Examples/example_04.py index c0a22c7d6..94e2d83b2 100644 --- a/Examples/example_04.py +++ b/Examples/example_04.py @@ -50,14 +50,21 @@ write_DISCON(turbine,controller,param_file=param_file, txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename'])) # Plot gain schedule -fig, ax = plt.subplots(1,2,constrained_layout=True) -ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) -ax[0].set_xlabel('Wind Speed') -ax[0].set_ylabel('Proportional Gain') +fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) +ax = ax.flatten() +ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) +ax[0].set_ylabel('omega_pc') -ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) -ax[1].set_xlabel('Wind Speed') -ax[1].set_ylabel('Integral Gain') +ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) +ax[1].set_ylabel('zeta_pc') + +ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) +ax[2].set_xlabel('Wind Speed') +ax[2].set_ylabel('Proportional Gain') + +ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) +ax[3].set_xlabel('Wind Speed') +ax[3].set_ylabel('Integral Gain') plt.suptitle('Pitch Controller Gains') diff --git a/Examples/example_06.py b/Examples/example_06.py index b9d41d5ed..ea9c47636 100644 --- a/Examples/example_06.py +++ b/Examples/example_06.py @@ -13,6 +13,8 @@ # Python Modules import yaml import os +import numpy as np +import matplotlib.pyplot as plt # ROSCO toolbox modules from ROSCO_toolbox import controller as ROSCO_controller from ROSCO_toolbox import turbine as ROSCO_turbine @@ -22,6 +24,7 @@ this_dir = os.path.dirname(os.path.abspath(__file__)) +example_out_dir = os.path.join(this_dir,'examples_out') # Load yaml file parameter_filename = os.path.join(os.path.dirname(this_dir), 'Tune_Cases', 'IEA15MW.yaml') @@ -43,10 +46,41 @@ # Tune controller controller.tune_controller(turbine) +# Now double Kp_float and check that it's passed through +Kp_float = -18 +controller_params['Kp_float'] = Kp_float +controller = ROSCO_controller.Controller(controller_params) +controller.tune_controller(turbine) +np.testing.assert_almost_equal(Kp_float,controller.Kp_float) + # Write parameter input file param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) +# Plot gain schedule +fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) +ax = ax.flatten() +ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) +ax[0].set_ylabel('omega_pc') + +ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) +ax[1].set_ylabel('zeta_pc') + +ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) +ax[2].set_xlabel('Wind Speed') +ax[2].set_ylabel('Proportional Gain') + +ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) +ax[3].set_xlabel('Wind Speed') +ax[3].set_ylabel('Integral Gain') + +plt.suptitle('Pitch Controller Gains') + +if False: + plt.show() +else: + plt.savefig(os.path.join(example_out_dir,'06_GainSched.png')) + # Run OpenFAST # --- May need to change fastcall if you use a non-standard command to call openfast fastcall = 'openfast' diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index c8ce15b0e..69ddc61fb 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -63,6 +63,7 @@ def __init__(self, controller_params): self.Flp_Mode = controller_params['Flp_Mode'] # Necessary parameters + self.U_pc = controller_params['U_pc'] self.zeta_pc = controller_params['zeta_pc'] self.omega_pc = controller_params['omega_pc'] self.zeta_vs = controller_params['zeta_vs'] @@ -96,6 +97,13 @@ def __init__(self, controller_params): self.ptfm_freq = controller_params['ptfm_freq'] except: raise Exception('ROSCO_toolbox:controller: twr_freq and ptfm_freq must be set if Fl_Mode > 0') + + # Kp_float direct setting + if 'Kp_float' in controller_params: + self.Kp_float = controller_params['Kp_float'] + else: + # Set to 0 to compute based on sensitivities later + self.Kp_float = 0 else: self.twr_freq = 0 self.ptfm_freq = 0 @@ -225,9 +233,16 @@ def tune_controller(self, turbine): A_pc = A[-len(v_above_rated)+1:] # above rated B_tau = B_tau * np.ones(len(v)) + # Resample omega_ and zeta_pc at above rated wind speeds + if len(self.U_pc) == len(self.omega_pc) == len(self.zeta_pc): + self.omega_pc_U = multi_sigma(v_above_rated[1:],self.U_pc,self.omega_pc) + self.zeta_pc_U = multi_sigma(v_above_rated[1:],self.U_pc,self.zeta_pc) + else: + raise Exception('ROSCO_toolbox: The lengths of U_pc, omega_pc, and zeta_pc must be equal') + # -- Find gain schedule -- self.pc_gain_schedule = ControllerTypes() - self.pc_gain_schedule.second_order_PI(self.zeta_pc, self.omega_pc,A_pc,B_beta[-len(v_above_rated)+1:],linearize=True,v=v_above_rated[1:]) + 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) @@ -282,15 +297,17 @@ def tune_controller(self, turbine): # --- Floating feedback term --- if self.Fl_Mode == 1: # Floating feedback - Kp_float = (dtau_dv/dtau_dbeta) * turbine.TowerHt * Ng - f_kp = interpolate.interp1d(v,Kp_float) - self.Kp_float = f_kp(turbine.v_rated * (1.05)) # get Kp at v_rated + 0.5 m/s - # Turn on the notch filter if floating - self.F_NotchType = 2 - - # And check for .yaml input inconsistencies - if self.twr_freq == 0.0 or self.ptfm_freq == 0.0: - print('WARNING: twr_freq and ptfm_freq should be defined for floating turbine control!!') + # If we haven't set Kp_float as a control parameter + if self.Kp_float == 0: + Kp_float = (dtau_dv/dtau_dbeta) * turbine.TowerHt * Ng + f_kp = interpolate.interp1d(v,Kp_float) + self.Kp_float = f_kp(turbine.v_rated * (1.05)) # get Kp at v_rated + 0.5 m/s + # Turn on the notch filter if floating + self.F_NotchType = 2 + + # And check for .yaml input inconsistencies + if self.twr_freq == 0.0 or self.ptfm_freq == 0.0: + print('WARNING: twr_freq and ptfm_freq should be defined for floating turbine control!!') else: self.Kp_float = 0.0 @@ -517,10 +534,10 @@ def second_order_PI(self,zeta,om_n,A,B,linearize=False,v=None): Parameters: ----------- - zeta : int (-) - Desired damping ratio - om_n : int (rad/s) - Desired natural frequency + zeta : list of floats (-) + Desired damping ratio with breakpoints at v + om_n : list of floats (rad/s) + Desired natural frequency with breakpoints at v A : array_like (1/s) Plant poles (state transition matrix) B : array_like (varies) @@ -540,3 +557,69 @@ def second_order_PI(self,zeta,om_n,A,B,linearize=False,v=None): # Calculate gain schedule self.Kp = 1/B * (2*zeta*om_n + A) self.Ki = om_n**2/B + + +# helper functions + +def sigma(tt,t0,t1,y0=0,y1=1): + ''' + generates timeseries for a smooth transition from y0 to y1 from x0 to x1 + + inputs: tt - time indices + t0 - start time + t1 - end time + y0 - start output + y1 - end output + + outputs: yy - output timeseries corresponding to tt + ''' + + a3 = 2/(t0-t1)**3 + a2 = -3*(t0+t1)/(t0-t1)**3 + a1 = 6*t1*t0/(t0-t1)**3 + a0 = (t0-3*t1)*t0**2/(t0-t1)**3 + + a = np.array([a3,a2,a1,a0]) + + T = np.vander(tt,N=4) # vandermonde matrix + + ss = T @ a.T # base sigma + + yy = (y1-y0) * ss + y0 # scale and offset + + return yy + + +def multi_sigma(xx,x_bp,y_bp): + ''' + Make a sigma interpolation with multiple breakpoints + + Parameters: + ----------- + xx : list of floats (-) + new sample points + x_bp : list of floats (-) + breakpoints + y_bp : list of floats (-) + function value at breakpoints + + ''' + yy = np.zeros_like(xx) + + # interpolate sigma functions between all breakpoints + for i_sigma in range(0,len(x_bp)-1): + ind_i = (xx >= x_bp[i_sigma]) & (xx < x_bp[i_sigma+1]) + xx_i = xx[ind_i] + yy_i = sigma(xx_i,x_bp[i_sigma],x_bp[i_sigma+1],y0=y_bp[i_sigma],y1=y_bp[i_sigma+1]) + yy[ind_i] = yy_i + + # add first and last values to beginning and end + yy[xxx_bp[-1]] = y_bp[-1] + + if False: # debug plot + import matplotlib.pyplot as plt + plt.plot(xx,yy) + plt.show() + + return yy diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 0a833553c..e04b423df 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -118,9 +118,9 @@ properties: F_NotchType: type: number minimum: 0 - maximum: 1 + maximum: 3 default: 0 - description: Notch on the measured generator speed (0- disable, 1- enabled) + 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 minimum: 0 @@ -187,16 +187,28 @@ properties: maximum: 2 default: 0 description: Active Power Control Mode (0- no active power control 1- constant active power control, 2- open loop power vs time, 3- open loop power vs. wind speed) + U_pc: + type: array + description: List of wind speeds to schedule pitch control zeta and omega + unit: m/s + items: + type: number + minimum: 0 + uniqueItems: True zeta_pc: - type: number - minimum: 0 - description: Pitch controller desired damping ratio [-] + type: array + description: List of pitch controller desired damping ratio at U_pc [-] unit: none + items: + type: number + minimum: 0 omega_pc: - type: number - minimum: 0 - description: Pitch controller desired natural frequency [rad/s] + type: array + description: List of pitch controller desired natural frequency at U_pc [rad/s] unit: rad/s + items: + type: number + minimum: 0 zeta_vs: type: number minimum: 0 @@ -279,6 +291,10 @@ properties: description: Number of pitch angle gain scheduling breakpoints minimum: 0 default: 30 + Kp_float: + type: number + description: Gain of floating feedback control + unit: s filter_params: type: object diff --git a/ROSCO_toolbox/turbine.py b/ROSCO_toolbox/turbine.py index 5ac3a6b74..fd30a7369 100644 --- a/ROSCO_toolbox/turbine.py +++ b/ROSCO_toolbox/turbine.py @@ -158,7 +158,7 @@ def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_ print('Loading FAST model: %s ' % FAST_InputFile) self.TurbineName = FAST_InputFile.strip('.fst') - fast = self.fast = InputReader_OpenFAST(FAST_ver=FAST_ver,dev_branch=dev_branch) + fast = self.fast = InputReader_OpenFAST() fast.FAST_InputFile = FAST_InputFile fast.FAST_directory = FAST_directory fast.execute() diff --git a/Tune_Cases/BAR.yaml b/Tune_Cases/BAR.yaml index f8d0c5220..914990a17 100644 --- a/Tune_Cases/BAR.yaml +++ b/Tune_Cases/BAR.yaml @@ -42,8 +42,9 @@ controller_params: Fl_Mode: 0 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} Flp_Mode: 2 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} # Controller parameters - zeta_pc: 1.2 # Pitch controller desired damping ratio [-] - omega_pc: 0.1 # Pitch controller desired natural frequency [rad/s] + U_pc: [12] + zeta_pc: [1.2] # Pitch controller desired damping ratio [-] + omega_pc: [0.1] # Pitch controller desired natural frequency [rad/s] zeta_vs: 0.5 # Torque controller desired damping ratio [-] omega_vs: 0.1 # Torque controller desired natural frequency [rad/s] # Only needed if Flp_Mode > 0 diff --git a/Tune_Cases/DTU10MW.yaml b/Tune_Cases/DTU10MW.yaml index aa4ef17df..beae4ed7d 100644 --- a/Tune_Cases/DTU10MW.yaml +++ b/Tune_Cases/DTU10MW.yaml @@ -45,8 +45,9 @@ controller_params: # twr_freq: # None # Tower natural frequency [rad/s] # ptfm_freq: # None # Platform natural frequency [rad/s] # Controller parameters - zeta_pc: 0.8 # Pitch controller desired damping ratio [-] - omega_pc: 0.3 # Pitch controller desired natural frequency [rad/s] + U_pc: [12] + zeta_pc: [0.8] # Pitch controller desired damping ratio [-] + omega_pc: [0.3] # Pitch controller desired natural frequency [rad/s] zeta_vs: 0.7 # Torque controller desired damping ratio [-] omega_vs: 0.2 # Torque controller desired natural frequency [rad/s] # Optional - these can be defined, but do not need to be diff --git a/Tune_Cases/IEA15MW.yaml b/Tune_Cases/IEA15MW.yaml index 23d6962bc..feb2d9cbd 100644 --- a/Tune_Cases/IEA15MW.yaml +++ b/Tune_Cases/IEA15MW.yaml @@ -39,8 +39,9 @@ controller_params: 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 - zeta_pc: 1.0 # Pitch controller desired damping ratio [-] - omega_pc: 0.25 # Pitch controller desired natural frequency [rad/s] + U_pc: [14,20] + zeta_pc: [2.0,1.0] # Pitch controller desired damping ratio [-] + omega_pc: [0.15,0.3] # Pitch controller desired natural frequency [rad/s] zeta_vs: 0.85 # Torque controller desired damping ratio [-] omega_vs: 0.12 # Torque controller desired natural frequency [rad/s] # Optional - these can be defined, but do not need to be diff --git a/Tune_Cases/NREL5MW.yaml b/Tune_Cases/NREL5MW.yaml index 5a6519eea..549c44ced 100644 --- a/Tune_Cases/NREL5MW.yaml +++ b/Tune_Cases/NREL5MW.yaml @@ -42,8 +42,9 @@ controller_params: 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.5 # Pitch controller desired natural frequency [rad/s] + U_pc: [12] + zeta_pc: [0.7] # Pitch controller desired damping ratio [-] + omega_pc: [0.5] # Pitch controller desired natural frequency [rad/s] zeta_vs: 0.7 # Torque controller desired damping ratio [-] omega_vs: 0.2 # Torque controller desired natural frequency [rad/s] # Only needed if Flp_Mode > 0