diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ea486fd1..81ad0953 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -136,6 +136,9 @@ ControlParameters: IPC_IntSat: <<: *real description: Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) + IPC_SatMode: + <<: *integer + description: IPC Saturation method IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) IPC_KP: <<: *real description: Integral gain for the individual pitch controller, [-]. @@ -723,6 +726,9 @@ LocalVariables: <<: *real description: Blade pitch [rad] size: 3 + BlPitchCMeas: + <<: *real + description: Mean (collective) blade pitch [rad] Azimuth: <<: *real description: Rotor aziumuth angle [rad] @@ -824,6 +830,9 @@ LocalVariables: <<: *real description: Proportional gain for IPC, after ramp [-] size: 2 + IPC_IntSat: + <<: *real + description: Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) PC_State: <<: *integer description: State of the pitch control system diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index a62c5366..3e453052 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -206,10 +206,10 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er WE_Inp_Speed = LocalVar%RotSpeedF END IF - IF (LocalVar%BlPitch(1) < CntrPar%PC_MinPit) THEN + IF (LocalVar%BlPitchCMeas < CntrPar%PC_MinPit) THEN WE_Inp_Pitch = CntrPar%PC_MinPit ELSE - WE_Inp_Pitch = LocalVar%BlPitch(1) + WE_Inp_Pitch = LocalVar%BlPitchCMeas END IF IF (LocalVar%VS_LastGenTrqF < 0.0001 * CntrPar%VS_RtTq) THEN @@ -228,7 +228,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! Inversion and Invariance Filter implementation IF (CntrPar%WE_Mode == 1) THEN ! Compute AeroDynTorque - Tau_r = AeroDynTorque(LocalVar%RotSpeedF, LocalVar%BlPitch(1), LocalVar, CntrPar, PerfData, ErrVar) + Tau_r = AeroDynTorque(LocalVar%RotSpeedF, LocalVar%BlPitchCMeas, LocalVar, CntrPar, PerfData, ErrVar) LocalVar%WE_VwIdot = CntrPar%WE_Gamma/CntrPar%WE_Jtot*(LocalVar%VS_LastGenTrq*CntrPar%WE_GearboxRatio - Tau_r) LocalVar%WE_VwI = LocalVar%WE_VwI + LocalVar%WE_VwIdot*LocalVar%DT @@ -413,7 +413,7 @@ REAL(DbKi) FUNCTION Shutdown(LocalVar, CntrPar, objInst) ! Pitch Blades to 90 degrees at max pitch rate if in shutdown mode IF (LocalVar%SD) THEN - Shutdown = LocalVar%BlPitch(1) + CntrPar%PC_MaxRat*LocalVar%DT + Shutdown = LocalVar%BlPitchCMeas + CntrPar%PC_MaxRat*LocalVar%DT IF (MODULO(LocalVar%Time, 10.0_DbKi) == 0) THEN print *, ' ** SHUTDOWN MODE **' ENDIF diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 29eda914..fd7a15f4 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -96,7 +96,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Saturate collective pitch commands: LocalVar%PC_PitComT = saturate(LocalVar%PC_PitComT, LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command using the pitch angle limits - LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitchCMeas) ! Saturate the overall command of blade K using the pitch rate limit LocalVar%PC_PitComT_Last = LocalVar%PC_PitComT ! Combine and saturate all individual pitch commands in software @@ -104,9 +104,15 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%FA_PitCom(K) LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch satauration limits LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%IPC_PitComF(K) ! Add IPC - LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the absolute pitch angle limits - LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit - END DO + + ! Hard IPC saturation by peak shaving limit + IF (CntrPar%IPC_SatMode == 1) THEN + LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) + END IF + + ! Rate limit + LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitch(K)) ! Saturate the overall command of blade K using the pitch rate limit + END DO ! Open Loop control, use if ! Open loop mode active Using OL blade pitch control @@ -134,9 +140,9 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Hardware saturation: using CntrPar%PC_MinPit DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate ! Saturate the pitch command using the overall (hardware) limit - LocalVar%PitComAct(K) = saturate(LocalVar%PitComAct(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) + LocalVar%PitComAct(K) = saturate(LocalVar%PitComAct(K), CntrPar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command of blade K using the pitch rate limit - LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitch(K)) ! Saturate the overall command of blade K using the pitch rate limit END DO ! Add pitch actuator fault for blade K @@ -413,15 +419,26 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_KP(i) = sigma(LocalVar%WE_Vw, CntrPar%IPC_Vramp(1), CntrPar%IPC_Vramp(2), 0.0_DbKi, CntrPar%IPC_KP(i), ErrVar) LocalVar%IPC_KI(i) = sigma(LocalVar%WE_Vw, CntrPar%IPC_Vramp(1), CntrPar%IPC_Vramp(2), 0.0_DbKi, CntrPar%IPC_KI(i), ErrVar) END DO + + ! Handle saturation limit, depends on IPC_SatMode + IF (CntrPar%IPC_SatMode == 2) THEN + ! Saturate to min allowed pitch angle, softly using IPC_IntSat + LocalVar%IPC_IntSat = min(CntrPar%IPC_IntSat,LocalVar%BlPitchCMeas - CntrPar%PC_MinPit) + ELSEIF (CntrPar%IPC_SatMode == 3) THEN + ! Saturate to peak shaving, softly using IPC_IntSat + LocalVar%IPC_IntSat = min(CntrPar%IPC_IntSat,LocalVar%BlPitchCMeas - LocalVar%PC_MinPit) + ELSE + LocalVar%IPC_IntSat = CntrPar%IPC_IntSat + ENDIF ! Integrate the signal and multiply with the IPC gain IF ((CntrPar%IPC_ControlMode >= 1) .AND. (CntrPar%Y_ControlMode /= 2)) THEN - LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) IF (CntrPar%IPC_ControlMode >= 2) THEN - LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF ELSE LocalVar%IPC_axisTilt_1P = 0.0 diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index eca51839..3e0e225e 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -48,7 +48,7 @@ REAL(DbKi) FUNCTION saturate(inputValue, minValue, maxValue) END FUNCTION saturate !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, inst) + REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, inst, ResetValue) ! Saturates inputValue. Makes sure it is not smaller than minValue and not larger than maxValue USE ROSCO_Types, ONLY : rlParams @@ -62,13 +62,18 @@ REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, ins LOGICAL, INTENT(IN) :: reset TYPE(rlParams), INTENT(INOUT) :: rlP INTEGER(IntKi), INTENT(INOUT) :: inst + REAL(DbKi), OPTIONAL, INTENT(IN) :: ResetValue ! Value to base rate limit off if restarting ! Local variables REAL(DbKi) :: rate + REAL(DbKi) :: ResetValue_ + + ResetValue_ = inputSignal + IF (PRESENT(ResetValue)) ResetValue_ = ResetValue IF (reset) THEN - rlP%LastSignal(inst) = inputSignal - ratelimit = inputSignal + rlP%LastSignal(inst) = ResetValue_ + ratelimit = ResetValue_ ELSE rate = (inputSignal - rlP%LastSignal(inst))/DT ! Signal rate (unsaturated) @@ -594,6 +599,7 @@ REAL(DbKi) FUNCTION sigma(x, x0, x1, y0, y1, ErrVar) END FUNCTION sigma + !------------------------------------------------------------------------------------------------------------------------------- ! Copied from NWTC_IO.f90 !> This function returns a character string encoded with today's date in the form dd-mmm-ccyy. diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 6e97878d..e852105a 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -53,6 +53,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas WRITE( Un, IOSTAT=ErrStat) LocalVar%Azimuth WRITE( Un, IOSTAT=ErrStat) LocalVar%NumBl WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_Acc @@ -93,6 +94,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_IntSat WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_State WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -234,6 +236,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(1) READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(2) READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) + READ( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas READ( Un, IOSTAT=ErrStat) LocalVar%Azimuth READ( Un, IOSTAT=ErrStat) LocalVar%NumBl READ( Un, IOSTAT=ErrStat) LocalVar%FA_Acc @@ -274,6 +277,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(2) + READ( Un, IOSTAT=ErrStat) LocalVar%IPC_IntSat READ( Un, IOSTAT=ErrStat) LocalVar%PC_State READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -438,7 +442,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 69 + nLocalVars = 71 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -453,77 +457,80 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(10) = LocalVar%rootMOOP(1) LocalVarOutData(11) = LocalVar%rootMOOPF(1) LocalVarOutData(12) = LocalVar%BlPitch(1) - LocalVarOutData(13) = LocalVar%Azimuth - LocalVarOutData(14) = LocalVar%NumBl - LocalVarOutData(15) = LocalVar%FA_Acc - LocalVarOutData(16) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(17) = LocalVar%FA_AccHPF - LocalVarOutData(18) = LocalVar%FA_AccHPFI - LocalVarOutData(19) = LocalVar%FA_PitCom(1) - LocalVarOutData(20) = LocalVar%RotSpeedF - LocalVarOutData(21) = LocalVar%GenSpeedF - LocalVarOutData(22) = LocalVar%GenTq - LocalVarOutData(23) = LocalVar%GenTqMeas - LocalVarOutData(24) = LocalVar%GenArTq - LocalVarOutData(25) = LocalVar%GenBrTq - LocalVarOutData(26) = LocalVar%IPC_PitComF(1) - LocalVarOutData(27) = LocalVar%PC_KP - LocalVarOutData(28) = LocalVar%PC_KI - LocalVarOutData(29) = LocalVar%PC_KD - LocalVarOutData(30) = LocalVar%PC_TF - LocalVarOutData(31) = LocalVar%PC_MaxPit - LocalVarOutData(32) = LocalVar%PC_MinPit - LocalVarOutData(33) = LocalVar%PC_PitComT - LocalVarOutData(34) = LocalVar%PC_PitComT_Last - LocalVarOutData(35) = LocalVar%PC_PitComTF - LocalVarOutData(36) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(37) = LocalVar%PC_PwrErr - LocalVarOutData(38) = LocalVar%PC_SpdErr - LocalVarOutData(39) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(40) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(41) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(42) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(43) = LocalVar%IPC_KI(1) - LocalVarOutData(44) = LocalVar%IPC_KP(1) - LocalVarOutData(45) = LocalVar%PC_State - LocalVarOutData(46) = LocalVar%PitCom(1) - LocalVarOutData(47) = LocalVar%PitComAct(1) - LocalVarOutData(48) = LocalVar%SS_DelOmegaF - LocalVarOutData(49) = LocalVar%TestType - LocalVarOutData(50) = LocalVar%VS_MaxTq - LocalVarOutData(51) = LocalVar%VS_LastGenTrq - LocalVarOutData(52) = LocalVar%VS_LastGenPwr - LocalVarOutData(53) = LocalVar%VS_MechGenPwr - LocalVarOutData(54) = LocalVar%VS_SpdErrAr - LocalVarOutData(55) = LocalVar%VS_SpdErrBr - LocalVarOutData(56) = LocalVar%VS_SpdErr - LocalVarOutData(57) = LocalVar%VS_State - LocalVarOutData(58) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(59) = LocalVar%WE_Vw - LocalVarOutData(60) = LocalVar%WE_Vw_F - LocalVarOutData(61) = LocalVar%WE_VwI - LocalVarOutData(62) = LocalVar%WE_VwIdot - LocalVarOutData(63) = LocalVar%VS_LastGenTrqF - LocalVarOutData(64) = LocalVar%Fl_PitCom - LocalVarOutData(65) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(66) = LocalVar%FA_AccF - LocalVarOutData(67) = LocalVar%Flp_Angle(1) - LocalVarOutData(68) = LocalVar%RootMyb_Last(1) - LocalVarOutData(69) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(13) = LocalVar%BlPitchCMeas + LocalVarOutData(14) = LocalVar%Azimuth + LocalVarOutData(15) = LocalVar%NumBl + LocalVarOutData(16) = LocalVar%FA_Acc + LocalVarOutData(17) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(18) = LocalVar%FA_AccHPF + LocalVarOutData(19) = LocalVar%FA_AccHPFI + LocalVarOutData(20) = LocalVar%FA_PitCom(1) + LocalVarOutData(21) = LocalVar%RotSpeedF + LocalVarOutData(22) = LocalVar%GenSpeedF + LocalVarOutData(23) = LocalVar%GenTq + LocalVarOutData(24) = LocalVar%GenTqMeas + LocalVarOutData(25) = LocalVar%GenArTq + LocalVarOutData(26) = LocalVar%GenBrTq + LocalVarOutData(27) = LocalVar%IPC_PitComF(1) + LocalVarOutData(28) = LocalVar%PC_KP + LocalVarOutData(29) = LocalVar%PC_KI + LocalVarOutData(30) = LocalVar%PC_KD + LocalVarOutData(31) = LocalVar%PC_TF + LocalVarOutData(32) = LocalVar%PC_MaxPit + LocalVarOutData(33) = LocalVar%PC_MinPit + LocalVarOutData(34) = LocalVar%PC_PitComT + LocalVarOutData(35) = LocalVar%PC_PitComT_Last + LocalVarOutData(36) = LocalVar%PC_PitComTF + LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(38) = LocalVar%PC_PwrErr + LocalVarOutData(39) = LocalVar%PC_SpdErr + LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(44) = LocalVar%IPC_KI(1) + LocalVarOutData(45) = LocalVar%IPC_KP(1) + LocalVarOutData(46) = LocalVar%IPC_IntSat + LocalVarOutData(47) = LocalVar%PC_State + LocalVarOutData(48) = LocalVar%PitCom(1) + LocalVarOutData(49) = LocalVar%PitComAct(1) + LocalVarOutData(50) = LocalVar%SS_DelOmegaF + LocalVarOutData(51) = LocalVar%TestType + LocalVarOutData(52) = LocalVar%VS_MaxTq + LocalVarOutData(53) = LocalVar%VS_LastGenTrq + LocalVarOutData(54) = LocalVar%VS_LastGenPwr + LocalVarOutData(55) = LocalVar%VS_MechGenPwr + LocalVarOutData(56) = LocalVar%VS_SpdErrAr + LocalVarOutData(57) = LocalVar%VS_SpdErrBr + LocalVarOutData(58) = LocalVar%VS_SpdErr + LocalVarOutData(59) = LocalVar%VS_State + LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(61) = LocalVar%WE_Vw + LocalVarOutData(62) = LocalVar%WE_Vw_F + LocalVarOutData(63) = LocalVar%WE_VwI + LocalVarOutData(64) = LocalVar%WE_VwIdot + LocalVarOutData(65) = LocalVar%VS_LastGenTrqF + LocalVarOutData(66) = LocalVar%Fl_PitCom + LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(68) = LocalVar%FA_AccF + LocalVarOutData(69) = LocalVar%Flp_Angle(1) + LocalVarOutData(70) = LocalVar%RootMyb_Last(1) + LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & - 'rootMOOPF', 'BlPitch', 'Azimuth', 'NumBl', 'FA_Acc', & - 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'RotSpeedF', & - 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', & - 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & - 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & - 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & - 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', 'PC_State', & - 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', & - 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & - 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & - 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & + 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & + 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & + 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & + 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & + 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & + 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', & + 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & + 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & + 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & + 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & + 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 3426ae9f..ad2b631b 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -28,6 +28,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: IPC_ControlMode ! Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0 - off, 1 - 1P reductions, 2 - 1P+2P reductions} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_Vramp ! Wind speeds for IPC cut-in sigma function [m/s] REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) + INTEGER(IntKi) :: IPC_SatMode ! IPC Saturation method (0 - no saturation, 1 - saturate by PC_MinPit, 2 - saturate by PS_BldPitchMin) REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KP ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KI ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_aziOffset ! Phase offset added to the azimuth angle for the individual pitch controller, [rad]. @@ -200,6 +201,7 @@ MODULE ROSCO_Types REAL(DbKi) :: rootMOOP(3) ! Blade root bending moment [Nm] REAL(DbKi) :: rootMOOPF(3) ! Filtered Blade root bending moment [Nm] REAL(DbKi) :: BlPitch(3) ! Blade pitch [rad] + REAL(DbKi) :: BlPitchCMeas ! Mean (collective) blade pitch [rad] REAL(DbKi) :: Azimuth ! Rotor aziumuth angle [rad] INTEGER(IntKi) :: NumBl ! Number of blades [-] REAL(DbKi) :: FA_Acc ! Tower fore-aft acceleration [m/s^2] @@ -232,6 +234,7 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_AxisYaw_2P ! Integral of quadrature, 2P REAL(DbKi) :: IPC_KI(2) ! Integral gain for IPC, after ramp [-] REAL(DbKi) :: IPC_KP(2) ! Proportional gain for IPC, after ramp [-] + REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) INTEGER(IntKi) :: PC_State ! State of the pitch control system REAL(DbKi) :: PitCom(3) ! Commanded pitch of each blade the last time the controller was called [rad]. REAL(DbKi) :: PitComAct(3) ! Actuated pitch command of each blade [rad]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 9b00c1f2..9ba9e80c 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -72,11 +72,13 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ELSE LocalVar%BlPitch(1) = LocalVar%PitComAct(1) LocalVar%BlPitch(2) = LocalVar%PitComAct(2) - LocalVar%BlPitch(3) = LocalVar%PitComAct(3) + LocalVar%BlPitch(3) = LocalVar%PitComAct(3) END IF ENDIF + LocalVar%BlPitchCMeas = (1 / REAL(LocalVar%NumBl)) * (LocalVar%BlPitch(1) + LocalVar%BlPitch(2) + LocalVar%BlPitch(3)) + IF (LocalVar%iStatus == 0) THEN ! TODO: Technically, LocalVar%Time > 0, too, but this restart is in many places as a reset LocalVar%restart = .True. ELSE @@ -301,6 +303,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz !------------------- IPC CONSTANTS ----------------------- CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_Vramp', CntrPar%IPC_Vramp, 2, accINFILE(1), ErrVar ) + CALL ParseInput(UnControllerParameters,CurLine,'IPC_SatMode',accINFILE(1),CntrPar%IPC_SatMode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'IPC_IntSat',accINFILE(1),CntrPar%IPC_IntSat,ErrVar) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KP', CntrPar%IPC_KP, 2, accINFILE(1), ErrVar ) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KI', CntrPar%IPC_KI, 2, accINFILE(1), ErrVar ) @@ -805,6 +808,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'Corner frequency of IPC actuator model must be positive, or set to 0 to disable.' ENDIF + IF (CntrPar%IPC_SatMode < 0 .OR. CntrPar%IPC_SatMode > 3) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'IPC_SatMode must be 0, 1, 2, or 3.' + ENDIF + IF (CntrPar%IPC_KI(1) < 0.0) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'IPC_KI(1) must be zero or greater than zero.' diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index d88c346e..432785df 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -606,6 +606,9 @@ properties: type: number description: Integrator saturation (maximum signal amplitude contribution to pitch from IPC) units: rad + IPC_SatMode: + type: integer + description: IPC Saturation method (0 - no saturation, 1 - saturate by PC_MinPit, 2 - saturate by PS_BldPitchMin) IPC_KP: type: array items: diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 10ddc7d3..055a76f8 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -116,7 +116,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- INDIVIDUAL PITCH CONTROL -----------------------------------------\n') file.write('{}! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s]\n'.format(''.join('{:<4.6f} '.format(rosco_vt['IPC_Vramp'][i]) for i in range(len(rosco_vt['IPC_Vramp']))))) - file.write('{:<13.1f} ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n'.format(rosco_vt['IPC_IntSat'])) # Hardcode to 5 degrees + file.write('{:<11d} ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin)\n'.format(int(rosco_vt['IPC_SatMode']))) # Hardcode to 5 degrees + file.write('{:<13.1f} ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n'.format(rosco_vt['IPC_IntSat'])) file.write('{}! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n'.format(''.join('{:<4.3e} '.format(rosco_vt['IPC_KP'][i]) for i in range(len(rosco_vt['IPC_KP']))))) file.write('{}! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n'.format(''.join('{:<4.3e} '.format(rosco_vt['IPC_KI'][i]) for i in range(len(rosco_vt['IPC_KI']))))) file.write('{}! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. \n'.format(''.join('{:<4.6f} '.format(rosco_vt['IPC_aziOffset'][i]) for i in range(len(rosco_vt['IPC_aziOffset']))))) @@ -437,6 +438,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): # ------- INDIVIDUAL PITCH CONTROL ------- DISCON_dict['IPC_Vramp'] = controller.IPC_Vramp DISCON_dict['IPC_IntSat'] = 0.2618 + DISCON_dict['IPC_SatMode'] = 2 DISCON_dict['IPC_KP'] = [controller.Kp_ipc1p, controller.Kp_ipc2p] DISCON_dict['IPC_KI'] = [controller.Ki_ipc1p, controller.Ki_ipc2p] DISCON_dict['IPC_aziOffset'] = [0.0, 0.0] diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index f05cc03d..e7f5a1bd 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.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- 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)} @@ -53,6 +53,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] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 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, [-] @@ -94,8 +95,8 @@ -0.00972164 -0.01031092 -0.01090020 -0.01148948 -0.01207877 -0.01266805 -0.01325733 -0.01384662 -0.01443590 -0.01502518 -0.01561447 -0.01620375 -0.01679303 -0.01738232 -0.01797160 -0.01856088 -0.01915016 -0.01973945 -0.02032873 -0.02091801 -0.02150730 -0.02209658 -0.02268586 -0.02327515 -0.02386443 -0.02445371 -0.02504300 -0.02563228 -0.02622156 -0.02378670 -0.02062296 -0.02541485 -0.03159105 -0.03849962 -0.04595997 -0.05389417 -0.06225884 -0.07101431 -0.08016995 -0.08970426 -0.09955610 -0.10976762 -0.12028100 -0.13120419 -0.14238799 -0.15383228 -0.16572504 -0.17783697 -0.19011487 -0.20289651 -0.21593424 -0.22919262 -0.24255457 -0.25635133 -0.27049546 -0.28482651 -0.29923376 -0.31380076 -0.32862514 -0.34372726 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [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 82eec8be..6be782e5 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.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- 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)} @@ -53,6 +53,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] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 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, [-] @@ -94,8 +95,8 @@ -0.02438353 -0.02655283 -0.02872212 -0.03089141 -0.03306071 -0.03523000 -0.03739930 -0.03956859 -0.04173788 -0.04390718 -0.04607647 -0.04824576 -0.05041506 -0.05258435 -0.05475365 -0.05692294 -0.05909223 -0.06126153 -0.06343082 -0.06560011 -0.06776941 -0.06993870 -0.07210800 -0.07427729 -0.07644658 -0.07861588 -0.08078517 -0.08295446 -0.08512376 -0.08490640 -0.05739531 -0.05967534 -0.06643664 -0.07537721 -0.08537869 -0.09664144 -0.10851650 -0.12137925 -0.13453168 -0.14834459 -0.16280188 -0.17753158 -0.19283401 -0.20862160 -0.22461456 -0.24120058 -0.25817445 -0.27538476 -0.29299882 -0.31103587 -0.32941546 -0.34807902 -0.36693717 -0.38625237 -0.40583167 -0.42579305 -0.44596365 -0.46626113 -0.48675074 -0.50756940 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat index f402ab4b..51a09d4e 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat @@ -81,7 +81,7 @@ True GenTiStp - Method to stop the generator {T: timed usin 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 - Cuttoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] 0.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.0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] 0.0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] 0.0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 7369eac9..29b3a8e8 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.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- 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)} @@ -53,6 +53,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] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 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, [-] @@ -94,8 +95,8 @@ -0.01638154 -0.01796321 -0.01954487 -0.02112654 -0.02270820 -0.02428987 -0.02587154 -0.02745320 -0.02903487 -0.03061653 -0.03219820 -0.03377987 -0.03536153 -0.03694320 -0.03852486 -0.04010653 -0.04168820 -0.04326986 -0.04485153 -0.04643319 -0.04801486 -0.04959652 -0.05117819 -0.05275986 -0.05434152 -0.05592319 -0.05758373 -0.05882656 -0.06845507 -0.05992890 0.02094683 0.01327182 0.00285485 -0.00935731 -0.02210773 -0.03573037 -0.04990222 -0.06404904 -0.07899629 -0.09463190 -0.10954192 -0.12525205 -0.14168652 -0.15843395 -0.17415061 -0.19052486 -0.20780146 -0.22581018 -0.24373777 -0.26010871 -0.27706767 -0.29551708 -0.31430599 -0.33428552 -0.35420853 -0.37183729 -0.38936451 -0.40828911 -0.42758878 -0.44818175 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad]