Skip to content

Commit

Permalink
Some housekeeping, hard-code NREL 15MW for now
Browse files Browse the repository at this point in the history
  • Loading branch information
nikhar-abbas committed Oct 8, 2019
1 parent 503c710 commit dfcc576
Show file tree
Hide file tree
Showing 7 changed files with 125 additions and 126 deletions.
19 changes: 11 additions & 8 deletions WTC_toolbox/controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,11 @@ def controller_params(self,turbine):

# Torque Controller Parameters
self.zeta_vs = 0.7 # Torque controller damping ratio (-)
self.omega_vs = 0.3 # Torque controller natural frequency (rad/s)
self.omega_vs = 0.2 # Torque controller natural frequency (rad/s)

# Other basic parameters
# self.v_rated = turbine.RRspeed * turbine.RotorRad / turbine.TSR_initial[turbine.Cp.max_ind[0]] # Rated wind speed (m/s)
# self.v_rated = 10.75
self.v_rated = 11.4

def tune_controller(self, turbine):
Expand Down Expand Up @@ -77,8 +78,8 @@ def tune_controller(self, turbine):
TSR_rated = RRspeed*R/v_rated # TSR at rated

# separate wind speeds by operation regions
v_below_rated = np.arange(v_min,v_rated,0.1) # below rated
v_above_rated = np.arange(v_rated,v_max,0.1) # above rated
v_below_rated = np.arange(v_min,v_rated,0.5) # below rated
v_above_rated = np.arange(v_rated+0.5,v_max,0.5) # above rated
v = np.concatenate((v_below_rated, v_above_rated))

# separate TSRs by operations regions
Expand Down Expand Up @@ -152,6 +153,7 @@ def tune_controller(self, turbine):
self.TSR_op = TSR_op
self.A = A
self.B_beta = B_beta
self.B_tau = B_tau

# Peak Shaving
self.ps = ControllerBlocks()
Expand Down Expand Up @@ -295,11 +297,11 @@ class containing
file.write('1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control}\n')
file.write('0 ! Y_ControlMode - Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}\n')
file.write('1 ! SS_Mode - Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing}\n')
file.write('2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)}\n')
file.write('0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)}\n')
file.write('1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving}\n')
file.write('\n')
file.write('!------- FILTERS ----------------------------------------------------------\n')
file.write('{} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz]\n'.format(str(turbine.omega_dt))) # this needs to be included as an input file
file.write('{} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz]\n'.format(str(turbine.omega_dt * 1/3))) # this needs to be included as an input file
file.write('0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2]\n')
file.write('0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s]\n')
file.write('0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-]\n')
Expand Down Expand Up @@ -330,9 +332,9 @@ class containing
file.write('0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s]\n')
file.write('\n')
file.write('!------- VS TORQUE CONTROL ------------------------------------------------\n')
file.write('{} ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-]\n'.format(str(turbine.GenEff)))
file.write('{} ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm]\n'.format(str(turbine.RatedTorque)))
file.write('150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s].\n')
file.write('{} ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-]\n'.format(turbine.GenEff))
file.write('{} ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm]\n'.format(turbine.RatedTorque))
file.write('1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s].\n')
file.write('{} ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm].\n'.format(str(turbine.RatedTorque*1.1)))
file.write('0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm].\n')
file.write('0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s]\n')
Expand All @@ -343,6 +345,7 @@ class containing
file.write('1 ! VS_n - Number of generator PI torque controller gains\n')
file.write('{} ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(str(controller.vs_gain_schedule.Kp[-1])))
file.write('{} ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(str(controller.vs_gain_schedule.Ki[-1])))
file.write('{} ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad].\n'.format(str(turbine.Cp.TSR_opt).strip('[]')))
file.write('\n')
file.write('!------- SETPOINT SMOOTHER ---------------------------------------------\n')
file.write('30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad].\n')
Expand Down
2 changes: 1 addition & 1 deletion WTC_toolbox/sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ def sim_ws_series(self,t_array,ws_array,rotor_rpm_init=10,init_pitch=0.0, make_p
gen_speed[i] = rot_speed[i] * self.turbine.Ng

# Call the controller
gen_torque[i], bld_pitch[i] = self.controller_int.call_controller(t,dt,bld_pitch[i-1],gen_speed[i],rot_speed[i],ws)
gen_torque[i], bld_pitch[i] = self.controller_int.call_controller(t,dt,bld_pitch[i-1],gen_torque[i-1],gen_speed[i],rot_speed[i],ws)

# Calculate the power
gen_power[i] = gen_speed[i] * np.pi/30.0 * gen_torque[i] * self.gen_eff
Expand Down
21 changes: 8 additions & 13 deletions WTC_toolbox/turbine.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
deg2rad = np.deg2rad(1)
rad2deg = np.rad2deg(1)
rpm2RadSec = 2.0*(np.pi)/60.0
RadSec2rpm = 60/(2.0 * np.pi)

class Turbine():
"""
Expand All @@ -34,20 +35,14 @@ def __init__(self):
"""

# ------ Turbine Parameters------
# Some of this should be loaded from a dictionary and cleaned up...
# self.J = None # Total rotor inertial (kg-m^2)
# self.rho = None # Air density (kg/m^3)
# self.RotorRad = None # Rotor radius (m)
# self.Ng = None # Gearbox ratio (-)
# self.RRspeed = 7.49*rpm2RadSec # Rated rotor speed (rad/s)
self.RRspeed = 12.1*rpm2RadSec # Rated rotor speed (rad/s)
# self.RRspeed = 7.5*rpm2RadSec # Rated rotor speed (rad/s)

self.v_min = 4. # Cut-in wind speed (m/s) (JUST ASSUME FOR NOW)
self.v_rated = None # Rated wind speed (m/s)
self.v_max = 25. # Cut-out wind speed (m/s), -- Does not need to be exact (JUST ASSUME FOR NOW)
# self.GenEff = None
# self.RatedPower = 15000000
self.RatedPower = 5000000
# self.RatedPower = 15000000

# Pitch controller
self.PC_MaxPit = 1.5707 # Maximum pitch angle (rad)
Expand Down Expand Up @@ -126,9 +121,9 @@ def load_from_fast(self, FAST_InputFile,FAST_directory,drivetrain_inertia, FAST_
self.rho = fast.fst_vt['AeroDyn15']['AirDens']
self.mu = fast.fst_vt['AeroDyn15']['KinVisc']
self.Ng = fast.fst_vt['ElastoDyn']['GBRatio']
self.GenEff = fast.fst_vt['ElastoDyn']['GBoxEff']
self.GenEff = fast.fst_vt['ServoDyn']['GenEff']
self.DTTorSpr = fast.fst_vt['ElastoDyn']['DTTorSpr']
self.RatedTorque = self.RatedPower/(self.RRspeed*self.Ng)
self.RatedTorque = self.RatedPower/(self.GenEff/100*self.RRspeed*self.Ng)


# Some additional parameters to save
Expand Down Expand Up @@ -196,17 +191,17 @@ def load_from_ccblade(self,fast):
print('CCBlade run succesfully')
# Generate the look-up tables
# Mesh the grid and flatten the arrays
fixed_rpm = 10 # RPM
fixed_rpm = self.RRspeed*RadSec2rpm # RPM

TSR_initial = np.arange(0.5,15,0.5)
pitch_initial = np.arange(-1,25,0.5)
pitch_initial_rad = pitch_initial * deg2rad
ws_array = (fixed_rpm * (np.pi / 30.) * self.TipRad) / TSR_initial
ws_array = (fixed_rpm * rpm2RadSec * self.TipRad) / TSR_initial
ws_mesh, pitch_mesh = np.meshgrid(ws_array, pitch_initial)
ws_flat = ws_mesh.flatten()
pitch_flat = pitch_mesh.flatten()
omega_flat = np.ones_like(pitch_flat) * fixed_rpm
tsr_flat = (fixed_rpm * (np.pi / 30.) * self.TipRad) / ws_flat
tsr_flat = (fixed_rpm * rpm2RadSec * self.TipRad) / ws_flat

# Get values from cc-blade
print('Running cc_rotor aerodynamic analysis, this may take a second...')
Expand Down
Loading

0 comments on commit dfcc576

Please sign in to comment.