diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 56c0090a..3a60d250 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -330,6 +330,7 @@ def tune_controller(self, turbine): # Store some variables self.v = v # Wind speed (m/s) + self.v_above_rated = v_above_rated self.v_below_rated = v_below_rated self.pitch_op = pitch_op self.pitch_op_pc = pitch_op[-len(v_above_rated)+1:] diff --git a/ROSCO_toolbox/linear/lin_util.py b/ROSCO_toolbox/linear/lin_util.py index 29203da0..74b2e537 100644 --- a/ROSCO_toolbox/linear/lin_util.py +++ b/ROSCO_toolbox/linear/lin_util.py @@ -66,7 +66,7 @@ def pc_closedloop(linturb, controller, u): Cs = interp_pitch_controller(controller, u) # Combine controller and plant - sys_cl = feedback(1, Cs*P) + sys_cl = feedback(Cs*P, 1) return sys_cl @@ -107,7 +107,7 @@ def smargin(linturb, controller, u_eval): # except: sens_sys = pc_sensitivity(linturb, controller, u_eval) ol_sys = pc_openloop(linturb, controller, u_eval) - + cl_sys = pc_closedloop(linturb, controller, u_eval) sp_plant = sp.signal.StateSpace(ol_sys.A, ol_sys.B, ol_sys.C, ol_sys.D) sp_sens = sp.signal.StateSpace(sens_sys.A, sens_sys.B, sens_sys.C, sens_sys.D) @@ -137,7 +137,11 @@ def sens_min(om): return -sp.signal.bode(sp_sens, w=om)[1] if nearest_nyquist < sm: res = sp.optimize.minimize(nyquist_min, nearest_nyquist_freq, method='SLSQP', options={ 'finite_diff_rel_step': 1e-8}) - sm2 = min(abs(res.fun), abs(nearest_nyquist)) + # Make sure this didn't fail + if res.status != 0: + sm2 = nearest_nyquist + else: + sm2 = min(abs(res.fun), abs(nearest_nyquist)) sm_list = [sm, sm2] mag_list = [np.abs(sm_mag), np.abs(mag_at_min)] @@ -146,7 +150,10 @@ def sens_min(om): return -sp.signal.bode(sp_sens, w=om)[1] else: res = sp.optimize.minimize(nyquist_min, nearest_nyquist_freq, method='SLSQP', options={'finite_diff_rel_step': 1e-6}) - sm = min(res.fun, nearest_nyquist) + if res.status != 0: + sm = nearest_nyquist + else: + sm = min(res.fun, nearest_nyquist) @@ -172,10 +179,16 @@ def interp_plant(linturb, v, return_scipy=True): ''' # Find interpolated plant on v - Ap = interp_matrix(linturb.u_h, linturb.A_ops, v) - Bp = interp_matrix(linturb.u_h, linturb.B_ops, v) - Cp = interp_matrix(linturb.u_h, linturb.C_ops, v) - Dp = interp_matrix(linturb.u_h, linturb.D_ops, v) + if np.shape(linturb.A_ops)[2] > 1: + Ap = interp_matrix(linturb.u_h, linturb.A_ops, v) + Bp = interp_matrix(linturb.u_h, linturb.B_ops, v) + Cp = interp_matrix(linturb.u_h, linturb.C_ops, v) + Dp = interp_matrix(linturb.u_h, linturb.D_ops, v) + else: + Ap = np.squeeze(linturb.A_ops, axis=2) + Bp = np.squeeze(linturb.B_ops, axis=2) + Cp = np.squeeze(linturb.C_ops, axis=2) + Dp = np.squeeze(linturb.D_ops, axis=2) if return_scipy: P = sp.signal.StateSpace(Ap, Bp, Cp, Dp) diff --git a/ROSCO_toolbox/linear/linear_models.py b/ROSCO_toolbox/linear/linear_models.py index 9b46548a..5a4d6969 100644 --- a/ROSCO_toolbox/linear/linear_models.py +++ b/ROSCO_toolbox/linear/linear_models.py @@ -23,7 +23,7 @@ class LinearTurbineModel(object): - def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fromMat=False, lin_file=None, rm_hydro=False, load_parallel=False): + def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fromMat=False, fromPkl=False, mat_file=None, rm_hydro=False, load_parallel=False): ''' inputs: lin_file_dir (string) - directory of linear file outputs from OpenFAST @@ -35,7 +35,7 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr rm_hydro (bool) - remove hydrodynamic states load_parallel (bool) - run mbc3 usying multiprocessing ''' - if not fromMat: + if not fromMat and not fromPkl: # Number of linearization cases or OpenFAST sims, different from nlin/NLinTimes in OpenFAST n_lin_cases = len(lin_file_names) @@ -187,9 +187,56 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr # Trim the system self.trim_system(rm_azimuth=True, rm_hydro=rm_hydro) + elif fromPkl: + import pickle + if isinstance(lin_file_names, list): + print('list') + if len(lin_file_names) != 1: + raise TypeError( + 'lin_file_names must be a string or list of length 1 to import matrices from a pickle.') + else: + linfile = lin_file_names[0] + elif isinstance(lin_file_names, str): + linfile = lin_file_names + else: + raise TypeError( + 'lin_file_names must be a string or list of length 1 to import matrices from a pickle.') + + fname = os.path.join(lin_file_dir, linfile) + lin_mats = pickle.load(open(fname, 'rb'))[0] + print('Loading ABCD from ',fname) + self.A_ops = lin_mats['A'] + self.B_ops = lin_mats['B'] + self.C_ops = lin_mats['C'] + self.D_ops = lin_mats['D'] + self.x_ops = lin_mats['x_ops'] + self.u_ops = lin_mats['u_ops'] + self.y_ops = lin_mats['y_ops'] + self.u_h = lin_mats['u_h'] + self.omega_rpm = lin_mats['omega_rpm'] + self.DescCntrlInpt = lin_mats['DescCntrlInpt'] + self.DescStates = lin_mats['DescStates'] + self.DescOutput = lin_mats['DescOutput'] + self.StateDerivOrder = lin_mats['StateDerivOrder'] + self.ind_fast_inps = lin_mats['ind_fast_inps'] + self.ind_fast_outs = lin_mats['ind_fast_outs'] + + # Convert output RPM to rad/s + rpm_idx = np.flatnonzero(np.core.defchararray.find(self.DescOutput, 'rpm') > -1).tolist() + self.C_ops[rpm_idx, :, :] = rpm2radps(self.C_ops[rpm_idx, :, :]) + self.DescOutput = [desc.replace('rpm', 'rad/s') for desc in self.DescOutput] + # Convert output deg to rad + deg_idx = np.flatnonzero(np.core.defchararray.find(self.DescOutput, 'deg') > -1).tolist() + self.C_ops[deg_idx, :, :] = deg2rad(self.C_ops[deg_idx, :, :]) + self.DescOutput = [desc.replace('deg', 'rad') for desc in self.DescOutput] + + # Other important things + self.n_lin_cases = lin_mats['A'].shape[2] + # Trim the system + self.trim_system(rm_azimuth=True, rm_hydro=rm_hydro) else: # from matlab .mat file m - matDict = loadmat(lin_file) + matDict = loadmat(mat_file) # operating points # u_ops \in real(n_inps,n_ops) diff --git a/ROSCO_toolbox/linear/robust_scheduling.py b/ROSCO_toolbox/linear/robust_scheduling.py index dae86c5b..bb347bab 100644 --- a/ROSCO_toolbox/linear/robust_scheduling.py +++ b/ROSCO_toolbox/linear/robust_scheduling.py @@ -16,6 +16,7 @@ from ROSCO_toolbox.inputs.validation import load_rosco_yaml from ROSCO_toolbox.utilities import list_check + class RobustScheduling(om.ExplicitComponent): 'Finding Robust gain schedules for pitch controllers in FOWTs' @@ -110,6 +111,7 @@ def compute(self, inputs, outputs): self.controller.tune_controller(self.turbine) sm = smargin(linturb, self.controller, inputs['u_eval'][0]) + print('omega = {}, sm = {}'.format(inputs['omega'][0], sm)) omega = inputs['omega'] # Outputs @@ -151,9 +153,15 @@ def setup(self): Setup the OpenMDAO problem ''' # Initialize problem - self.om_problem = om.Problem() + from openmdao.utils.mpi import MPI, FakeComm + if MPI: + self.om_problem = om.Problem(comm=FakeComm()) + self.om_problem._run_root_only = True + self.om_problem.comm.allgather = MPI.COMM_WORLD.allgather + self.om_problem.comm.Bcast = MPI.COMM_WORLD.Bcast + else: + self.om_problem = om.Problem() - # Add subsystem self.om_problem.model.add_subsystem('r_sched', RobustScheduling(linturb_options=self.linturb_options, ROSCO_options=self.ROSCO_options)) @@ -166,7 +174,7 @@ def setup(self): ValueError( 'Can only run design of experiments for a single opt_options["windspeed"]') elif self.opt_options['driver'] == 'optimization': - self.om_problem = self.init_doe(self.om_problem, levels=self.opt_options['levels']) + self.om_problem = self.init_optimization(self.om_problem) else: ValueError( "self.opt_options['driver'] must be either 'design_of_experiments' or 'optimization'.") @@ -180,7 +188,6 @@ def setup(self): # Setup OM Problem self.om_problem.setup() - # Set constant values if not list_check(self.opt_options['omega']): self.om_problem.set_val('r_sched.omega', self.opt_options['omega']) @@ -197,7 +204,7 @@ def setup(self): self.om_opt = self.om_problem self.om_opt = self.add_dv(self.om_opt, ['omega', 'k_float']) - self.om_opt = self.init_optimization(self.om_opt) + # self.om_opt = self.init_optimization(self.om_opt) def execute(self): ''' @@ -217,18 +224,26 @@ def execute(self): self.sms = [] for u in self.opt_options['windspeed']: om0 = 0.1 - # Setup optimization - self.om_opt.set_val('r_sched.u_eval', u) - self.om_opt.set_val('r_sched.omega', om0) - - # Run optimization - print('Finding ROSCO tuning parameters for u = {}, sm = {}'.format( - u, self.linturb_options['stability_margin'])) - opt_logfile = os.path.join( - self.output_dir, self.output_name + '.' + str(u) + ".opt.sql") - self.om_opt = self.setup_recorder(self.om_opt, opt_logfile) - self.om_opt.run_driver() - self.om_opt.cleanup() + try_count = 0 + while try_count < 3: + # Setup optimization + self.om_opt.set_val('r_sched.u_eval', u) + self.om_opt.set_val('r_sched.omega', om0) + + # Run optimization + print('Finding ROSCO tuning parameters for u = {}, sm = {}, omega_pc = {}, k_float = {}'.format( + u, self.opt_options['stability_margin'], self.opt_options['omega'], self.opt_options['k_float'])) + opt_logfile = os.path.join( + self.output_dir, self.output_name + '.' + str(u) + ".opt.sql") + self.om_opt = self.setup_recorder(self.om_opt, opt_logfile) + self.om_opt.run_driver() + self.om_opt.cleanup() + + if self.om_opt.driver.fail: + try_count += 1 + om0 = np.random.random_sample(1)*self.opt_options['omega'][-1] + else: + try_count = 4 # save values self.omegas.append(self.om_opt.get_val('r_sched.omega')[0]) @@ -279,6 +294,7 @@ def init_optimization(self, om_problem): def init_doe(self, om_problem, levels=20): '''Initialize DOE driver''' om_problem.driver = om.DOEDriver(om.FullFactorialGenerator(levels=levels)) + # om_problem.driver = om.DOEDriver(om.LatinHypercubeGenerator(samples=levels)) # om_problem.driver = om.DOEDriver(om.UniformGenerator(num_samples=20)) os.makedirs(self.output_dir, exist_ok=True) # om_problem.driver.options['run_parallel'] = True @@ -386,6 +402,7 @@ def load_linturb(linfile_path, load_parallel=False): return linturb + def load_ROSCO(path_params, turbine_params, controller_params): turbine = ROSCO_turbine.Turbine(turbine_params) controller = ROSCO_controller.Controller(controller_params) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 0a854e6b..7c823946 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 04/29/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 05/25/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,7 +49,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 6.618848 8.273560 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] -0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 2.050e-08 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 1.450e-09 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 5f30d82d..9b54f745 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 04/29/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 05/25/22 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,7 +49,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 8.592000 10.740000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] -0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index b469e830..94c969b4 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 04/29/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 05/25/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,7 +49,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] -0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. diff --git a/Test_Cases/Wind/NoShr_3-15_50s.wnd b/Test_Cases/Wind/NoShr_3-15_50s.wnd new file mode 100644 index 00000000..42b8a2d2 --- /dev/null +++ b/Test_Cases/Wind/NoShr_3-15_50s.wnd @@ -0,0 +1,17 @@ +!Wind file for input to OpenFAST. +!Time Wind Wind Vert. Horiz. Vert. LinV Gust +! Speed Dir Speed Shear Shear Shear Speed +0.00 5.00 0.00 0.00 0.00 0.00 0.00 0.00 +50.0 5.00 0.00 0.00 0.00 0.00 0.00 0.00 +50.1 6.00 0.00 0.00 0.00 0.00 0.00 0.00 +100.0 6.00 0.00 0.00 0.00 0.00 0.00 0.00 +100.1 7.00 0.00 0.00 0.00 0.00 0.00 0.00 +150.0 7.00 0.00 0.00 0.00 0.00 0.00 0.00 +150.1 8.00 0.00 0.00 0.00 0.00 0.00 0.00 +200.0 8.00 0.00 0.00 0.00 0.00 0.00 0.00 +200.1 9.00 0.00 0.00 0.00 0.00 0.00 0.00 +250.0 9.00 0.00 0.00 0.00 0.00 0.00 0.00 +250.1 10.00 0.00 0.00 0.00 0.00 0.00 0.00 +300.0 10.00 0.00 0.00 0.00 0.00 0.00 0.00 +300.1 11.00 0.00 0.00 0.00 0.00 0.00 0.00 + diff --git a/Tune_Cases/BAR.yaml b/Tune_Cases/BAR.yaml index bb21281d..e1d7c463 100644 --- a/Tune_Cases/BAR.yaml +++ b/Tune_Cases/BAR.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'BAR_10.fst' # Name of *.fst file FAST_directory: '../Test_Cases/BAR_10' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: '../Test_Cases/BAR_10/Cp_Ct_Cq.BAR_10.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: 'Cp_Ct_Cq.BAR_10.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: