Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Catch divide-by-zero error in wind speed estimator #410

Merged
merged 3 commits into from
Dec 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Examples/28_tower_resonance.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def main():
# Ramp: good demo of functionality, short for CI
r.wind_case_fcn = cl.ramp
r.wind_case_opts = {
'U_start': 4, # from 10 to 15 m/s
'U_start': 0, # from 10 to 15 m/s
'U_end': 10,
't_start': 100,
't_end': 300
Expand Down
1 change: 1 addition & 0 deletions rosco/controller/src/ControllerBlocks.f90
Original file line number Diff line number Diff line change
Expand Up @@ -282,6 +282,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er
LocalVar%WE%v_t = 0.0
LocalVar%WE%v_m = max(LocalVar%HorWindV, 3.0_DbKi) ! avoid divide by 0 below if HorWindV is 0, which some AMRWind setups create
LocalVar%WE%v_h = max(LocalVar%HorWindV, 3.0_DbKi) ! avoid divide by 0 below if HorWindV is 0, which some AMRWind setups create
LocalVar%WE_Vw = LocalVar%WE%v_m + LocalVar%WE%v_t ! Initialize WE_Vw to aviod divide by zero
lambda = WE_Inp_Speed * CntrPar%WE_BladeRadius/LocalVar%WE%v_h
LocalVar%WE%xh = RESHAPE((/LocalVar%WE%om_r, LocalVar%WE%v_t, LocalVar%WE%v_m/),(/3,1/))
LocalVar%WE%P = RESHAPE((/0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 1.0/),(/3,3/))
Expand Down
4 changes: 3 additions & 1 deletion rosco/controller/src/Functions.f90
Original file line number Diff line number Diff line change
Expand Up @@ -575,12 +575,14 @@ REAL(DbKi) FUNCTION AeroDynTorque(RotSpeed, BldPitch, LocalVar, CntrPar, PerfDat
REAL(DbKi) :: RotorArea
REAL(DbKi) :: Cp
REAL(DbKi) :: Lambda
REAL(DbKi) :: WindSpeed

CHARACTER(*), PARAMETER :: RoutineName = 'AeroDynTorque'

! Find Torque
RotorArea = PI*CntrPar%WE_BladeRadius**2
Lambda = RotSpeed*CntrPar%WE_BladeRadius/LocalVar%WE_Vw
WindSpeed = MAX(LocalVar%WE_Vw,EPSILON(1.0_DbKi))
Lambda = RotSpeed*CntrPar%WE_BladeRadius/WindSpeed

! Compute Cp
Cp = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, BldPitch*R2D, Lambda, ErrVar)
Expand Down
Loading