diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 81866dee..522337ae 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -111,6 +111,10 @@ ControlParameters: IPC_ControlMode: <<: *integer description: Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0 - off, 1 - 1P reductions, 2 - 1P+2P reductions} + IPC_Vramp: + <<: *real + description: Wind speeds for IPC cut-in sigma function [m/s] + allocatable: True IPC_IntSat: <<: *real description: Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) @@ -750,6 +754,14 @@ LocalVariables: IPC_AxisYaw_2P: <<: *real description: Integral of quadrature, 2P + IPC_KI: + <<: *real + description: Integral gain for IPC, after ramp [-] + size: 2 + IPC_KP: + <<: *real + description: Proportional gain for IPC, after ramp [-] + size: 2 PC_State: <<: *integer description: State of the pitch control system @@ -966,7 +978,6 @@ DebugVariables: <<: *real description: Yaw component of coleman transformation, 2P - ErrorVariables: size_avcMSG: <<: *integer diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 7b9501e3..15bf1188 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -61,7 +61,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) DebugVar%PC_PICommand = LocalVar%PC_PitComT ! Find individual pitch control contribution IF ((CntrPar%IPC_ControlMode >= 1) .OR. (CntrPar%Y_ControlMode == 2)) THEN - CALL IPC(CntrPar, LocalVar, objInst, DebugVar) + CALL IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ELSE LocalVar%IPC_PitComF = 0.0 ! THIS IS AN ARRAY!! END IF @@ -105,7 +105,7 @@ 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%PC_PitComT + 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) = saturate(LocalVar%PitCom(K), CntrPar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the absolute pitch angle limits LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), LocalVar%BlPitch(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT) ! Saturate the overall command of blade K using the pitch rate limit END DO @@ -281,27 +281,29 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) END SUBROUTINE YawRateControl !------------------------------------------------------------------------------------------------------------------------------- - SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar) + SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Individual pitch control subroutine ! - Calculates the commanded pitch angles for IPC employed for blade fatigue load reductions at 1P and 2P ! - Includes yaw by IPC - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables, ErrorVariables TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst - TYPE(DebugVariables), INTENT(INOUT) :: DebugVar + TYPE(DebugVariables), INTENT(INOUT) :: DebugVar + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Local variables REAL(DbKi) :: PitComIPC(3), PitComIPCF(3), PitComIPC_1P(3), PitComIPC_2P(3) - INTEGER(IntKi) :: K ! Integer used to loop through turbine blades + INTEGER(IntKi) :: i, K ! Integer used to loop through gains and turbine blades REAL(DbKi) :: axisTilt_1P, axisYaw_1P, axisYawF_1P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisTilt_2P, axisYaw_2P, axisYawF_2P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] - + CHARACTER(*), PARAMETER :: RoutineName = 'IPC' + ! Body ! Pass rootMOOPs through the Coleman transform to get the tilt and yaw moment axis CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_1, axisTilt_1P, axisYaw_1P) @@ -316,15 +318,21 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar) Y_MErrF = 0.0 Y_MErrF_IPC = 0.0 END IF + + ! Soft cutin with sigma function + DO i = 1,2 + 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 ! 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, CntrPar%IPC_KP(1), CntrPar%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, CntrPar%IPC_KP(1), CntrPar%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), -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) IF (CntrPar%IPC_ControlMode >= 2) THEN - LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, CntrPar%IPC_KP(2), CntrPar%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, CntrPar%IPC_KP(2), CntrPar%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), -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) END IF ELSE LocalVar%IPC_axisTilt_1P = 0.0 @@ -361,6 +369,12 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar) DebugVar%axisYaw_2P = axisYaw_2P + + ! Add RoutineName to error message + IF (ErrVar%aviFAIL < 0) THEN + ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) + ENDIF + END SUBROUTINE IPC !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE ForeAftDamping(CntrPar, LocalVar, objInst) diff --git a/ROSCO/src/Filters.f90 b/ROSCO/src/Filters.f90 index 0204c5bc..4fb4239b 100644 --- a/ROSCO/src/Filters.f90 +++ b/ROSCO/src/Filters.f90 @@ -137,30 +137,47 @@ REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, i END FUNCTION HPFilter !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst) + REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst, Moving) ! Discrete time inverted Notch Filter with descending slopes, G = CornerFreq*s/(Damp*s^2+CornerFreq*s+Damp*CornerFreq^2) USE ROSCO_Types, ONLY : FilterParameters TYPE(FilterParameters), INTENT(INOUT) :: FP - REAL(DbKi), INTENT(IN) :: InputSignal - REAL(DbKi), INTENT(IN) :: DT ! time step [s] - REAL(DbKi), INTENT(IN) :: CornerFreq ! corner frequency [rad/s] - REAL(DbKi), INTENT(IN) :: Damp ! Dampening constant - INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. - INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. - LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal - + REAL(DbKi), INTENT(IN) :: InputSignal + REAL(DbKi), INTENT(IN) :: DT ! time step [s] + REAL(DbKi), INTENT(IN) :: CornerFreq ! corner frequency [rad/s] + REAL(DbKi), INTENT(IN) :: Damp ! Dampening constant + INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. + INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. + LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + LOGICAL, OPTIONAL, INTENT(IN) :: Moving ! Moving CornerFreq flag + + LOGICAL :: Moving_ ! Local version + REAL(DbKi) :: CornerFreq_ ! Local version + + Moving_ = .FALSE. + IF (PRESENT(Moving)) Moving_ = Moving + + ! Saturate Corner Freq at 0 + IF (CornerFreq < 0) THEN + CornerFreq_ = 0 + ELSE + CornerFreq_ = CornerFreq + ENDIF + ! Initialization IF ((iStatus == 0) .OR. reset) THEN FP%nfs_OutputSignalLast1(inst) = InputSignal FP%nfs_OutputSignalLast2(inst) = InputSignal FP%nfs_InputSignalLast1(inst) = InputSignal FP%nfs_InputSignalLast2(inst) = InputSignal - FP%nfs_b2(inst) = 2.0 * DT * CornerFreq + ENDIF + + IF ((iStatus == 0) .OR. reset .OR. Moving_) THEN + FP%nfs_b2(inst) = 2.0 * DT * CornerFreq_ FP%nfs_b0(inst) = -FP%nfs_b2(inst) - FP%nfs_a2(inst) = Damp*DT**2.0*CornerFreq**2.0 + 2.0*DT*CornerFreq + 4.0*Damp - FP%nfs_a1(inst) = 2.0*Damp*DT**2.0*CornerFreq**2.0 - 8.0*Damp - FP%nfs_a0(inst) = Damp*DT**2.0*CornerFreq**2.0 - 2*DT*CornerFreq + 4.0*Damp + FP%nfs_a2(inst) = Damp*DT**2.0*CornerFreq_**2.0 + 2.0*DT*CornerFreq_ + 4.0*Damp + FP%nfs_a1(inst) = 2.0*Damp*DT**2.0*CornerFreq_**2.0 - 8.0*Damp + FP%nfs_a0(inst) = Damp*DT**2.0*CornerFreq_**2.0 - 2*DT*CornerFreq_ + 4.0*Damp ENDIF NotchFilterSlopes = 1.0/FP%nfs_a2(inst) * (FP%nfs_b2(inst)*InputSignal + FP%nfs_b0(inst)*FP%nfs_InputSignalLast1(inst) & @@ -270,7 +287,8 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar ! Blade root bending moment for IPC DO K = 1,LocalVar%NumBl IF ((CntrPar%IPC_ControlMode > 0) .OR. (CntrPar%Flp_Mode == 3)) THEN - LocalVar%RootMOOPF(K) = NotchFilterSlopes(LocalVar%rootMOOP(K), LocalVar%DT, LocalVar%RotSpeedF, 0.7_DbKi, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotchSlopes) + ! Moving inverted notch at rotor speed to isolate 1P + LocalVar%RootMOOPF(K) = NotchFilterSlopes(LocalVar%rootMOOP(K), LocalVar%DT, LocalVar%RotSpeedF, 0.7_DbKi, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotchSlopes, .TRUE.) ELSEIF ( CntrPar%Flp_Mode == 2 ) THEN ! Filter Blade root bending moments LocalVar%RootMOOPF(K) = SecLPFilter(LocalVar%rootMOOP(K),LocalVar%DT, CntrPar%F_FlpCornerFreq(1), CntrPar%F_FlpCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart,objInst%instSecLPF) diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index f34ba272..c3d64603 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -510,6 +510,43 @@ REAL(DbKi) FUNCTION AeroDynTorque(RotSpeed, BldPitch, LocalVar, CntrPar, PerfDat END FUNCTION AeroDynTorque +!------------------------------------------------------------------------------------------------------------------------------- + REAL(DbKi) FUNCTION sigma(x, x0, x1, y0, y1, ErrVar) + ! Generic sigma function + USE ROSCO_Types, ONLY : ErrorVariables + IMPLICIT NONE + + ! Inputs + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar + + REAL(DbKi), Intent(IN) :: x, x0, x1 + REAL(DbKi), Intent(IN) :: y0, y1 + + ! Local + REAL(DbKi) :: a3, a2, a1, a0 + + CHARACTER(*), PARAMETER :: RoutineName = 'sigma' + + a3 = 2/(x0-x1)**3 + a2 = -3*(x0+x1)/(x0-x1)**3 + a1 = 6*x1*x0/(x0-x1)**3 + a0 = (x0-3*x1)*x0**2/(x0-x1)**3 + + IF (x < x0) THEN + sigma = y0 + ELSEIF (x > x1) THEN + sigma = y1 + ELSE + sigma = (a3*x**3 + a2*x**2 + a1*x + a0)*(y1-y0) + y0 + ENDIF + + ! Add RoutineName to error message + IF (ErrVar%aviFAIL < 0) THEN + ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) + ENDIF + + END FUNCTION sigma + !------------------------------------------------------------------------------------------------------------------------------- ! Copied from NWTC_IO.f90 diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index ba4d64b0..1744a385 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -86,6 +86,10 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, objInst, RootName, size_avcOUTNAM WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) + 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%PC_State WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -260,6 +264,10 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) + 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%PC_State READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -416,7 +424,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, avrSWAP, RootName, size_avcOUTNAME '[m/s]', '[m/s]', '[rad]', '[rad]', '[rad/s]', & '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '', '', '', ''] - nLocalVars = 70 + nLocalVars = 72 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -460,35 +468,37 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, avrSWAP, RootName, size_avcOUTNAME LocalVarOutData(39) = LocalVar%IPC_AxisYaw_1P LocalVarOutData(40) = LocalVar%IPC_AxisTilt_2P LocalVarOutData(41) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(42) = LocalVar%PC_State - LocalVarOutData(43) = LocalVar%PitCom(1) - LocalVarOutData(44) = LocalVar%SS_DelOmegaF - LocalVarOutData(45) = LocalVar%TestType - LocalVarOutData(46) = LocalVar%VS_MaxTq - LocalVarOutData(47) = LocalVar%VS_LastGenTrq - LocalVarOutData(48) = LocalVar%VS_LastGenPwr - LocalVarOutData(49) = LocalVar%VS_MechGenPwr - LocalVarOutData(50) = LocalVar%VS_SpdErrAr - LocalVarOutData(51) = LocalVar%VS_SpdErrBr - LocalVarOutData(52) = LocalVar%VS_SpdErr - LocalVarOutData(53) = LocalVar%VS_State - LocalVarOutData(54) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(55) = LocalVar%WE_Vw - LocalVarOutData(56) = LocalVar%WE_Vw_F - LocalVarOutData(57) = LocalVar%WE_VwI - LocalVarOutData(58) = LocalVar%WE_VwIdot - LocalVarOutData(59) = LocalVar%VS_LastGenTrqF - LocalVarOutData(60) = LocalVar%Y_AccErr - LocalVarOutData(61) = LocalVar%Y_ErrLPFFast - LocalVarOutData(62) = LocalVar%Y_ErrLPFSlow - LocalVarOutData(63) = LocalVar%Y_MErr - LocalVarOutData(64) = LocalVar%Y_YawEndT - LocalVarOutData(65) = LocalVar%Fl_PitCom - LocalVarOutData(66) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(67) = LocalVar%FA_AccF - LocalVarOutData(68) = LocalVar%Flp_Angle(1) - LocalVarOutData(69) = LocalVar%RootMyb_Last(1) - LocalVarOutData(70) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(42) = LocalVar%IPC_KI(1) + LocalVarOutData(43) = LocalVar%IPC_KP(1) + LocalVarOutData(44) = LocalVar%PC_State + LocalVarOutData(45) = LocalVar%PitCom(1) + LocalVarOutData(46) = LocalVar%SS_DelOmegaF + LocalVarOutData(47) = LocalVar%TestType + LocalVarOutData(48) = LocalVar%VS_MaxTq + LocalVarOutData(49) = LocalVar%VS_LastGenTrq + LocalVarOutData(50) = LocalVar%VS_LastGenPwr + LocalVarOutData(51) = LocalVar%VS_MechGenPwr + LocalVarOutData(52) = LocalVar%VS_SpdErrAr + LocalVarOutData(53) = LocalVar%VS_SpdErrBr + LocalVarOutData(54) = LocalVar%VS_SpdErr + LocalVarOutData(55) = LocalVar%VS_State + LocalVarOutData(56) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(57) = LocalVar%WE_Vw + LocalVarOutData(58) = LocalVar%WE_Vw_F + LocalVarOutData(59) = LocalVar%WE_VwI + LocalVarOutData(60) = LocalVar%WE_VwIdot + LocalVarOutData(61) = LocalVar%VS_LastGenTrqF + LocalVarOutData(62) = LocalVar%Y_AccErr + LocalVarOutData(63) = LocalVar%Y_ErrLPFFast + LocalVarOutData(64) = LocalVar%Y_ErrLPFSlow + LocalVarOutData(65) = LocalVar%Y_MErr + LocalVarOutData(66) = LocalVar%Y_YawEndT + LocalVarOutData(67) = LocalVar%Fl_PitCom + LocalVarOutData(68) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(69) = LocalVar%FA_AccF + LocalVarOutData(70) = LocalVar%Flp_Angle(1) + LocalVarOutData(71) = LocalVar%RootMyb_Last(1) + LocalVarOutData(72) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'Y_M', 'HorWindV', 'rootMOOP', 'rootMOOPF', & 'BlPitch', 'Azimuth', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', & @@ -497,13 +507,13 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, avrSWAP, RootName, size_avcOUTNAME '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', 'PC_State', 'PitCom', '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', 'Y_AccErr', & - 'Y_ErrLPFFast', 'Y_ErrLPFSlow', 'Y_MErr', 'Y_YawEndT', 'Fl_PitCom', & - 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE' & - ] + 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', 'PC_State', 'PitCom', & + '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', 'Y_AccErr', 'Y_ErrLPFFast', 'Y_ErrLPFSlow', 'Y_MErr', & + 'Y_YawEndT', '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 56841b63..ef2fa0b1 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -24,6 +24,7 @@ MODULE ROSCO_Types REAL(DbKi) :: FA_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from FA damper), [rad] REAL(DbKi) :: FA_KI ! Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] 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) 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, [-]. @@ -214,6 +215,8 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_AxisYaw_1P ! Integral of quadrature, 1P REAL(DbKi) :: IPC_AxisTilt_2P ! Integral of the direct axis, 2P 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 [-] 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) :: SS_DelOmegaF ! Filtered setpoint shifting term defined in setpoint smoother [rad/s]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 549ab3a8..d4d24dea 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -288,6 +288,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, accINFILE, accINFILE_size,ErrVar !------------------- IPC CONSTANTS ----------------------- CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseAry(UnControllerParameters, CurLine, 'IPC_Vramp', CntrPar%IPC_Vramp, 2, accINFILE(1), 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 ) diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 5b49961f..b4e70bb1 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -85,6 +85,7 @@ def __init__(self, controller_params): self.Ki_ipc1p = controller_params['IPC_Ki1p'] self.Kp_ipc2p = controller_params['IPC_Kp2p'] self.Ki_ipc2p = controller_params['IPC_Kp2p'] + self.IPC_Vramp = controller_params['IPC_Vramp'] # Optional parameters without defaults if self.Flp_Mode > 0: @@ -315,6 +316,10 @@ def tune_controller(self, turbine): else: self.sd_maxpit = pitch_op[-1] + # Set IPC ramp inputs if not already defined + if max(self.IPC_Vramp) == 0.0: + self.IPC_Vramp = [turbine.v_rated*0.8, turbine.v_rated] + # Store some variables self.v = v # Wind speed (m/s) self.v_below_rated = v_below_rated diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 48d51ed7..cd631643 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -331,6 +331,15 @@ properties: minimum: 0 description: integral gain for IPC, 2P [-] default: 0.0 + IPC_Vramp: + type: array + description: wind speeds for IPC cut-in sigma function [m/s] + items: + type: number + minimum: 0.0 + default: [0.0, 0.0] + unit: m/s + filter_params: type: object default: {} diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 24dc6b0e..4d289147 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -84,12 +84,12 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.5f} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s]\n'.format(rosco_vt['F_LPFCornerFreq'])) file.write('{:<13.5f} ! F_LPFDamping - Damping coefficient {{used only when F_FilterType = 2}} [-]\n'.format(rosco_vt['F_LPFDamping'])) file.write('{:<13.5f} ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s]\n'.format(rosco_vt['F_NotchCornerFreq'])) - file.write('{} ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-]\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_NotchBetaNumDen'][i]) for i in range(len(rosco_vt['F_NotchBetaNumDen']))))) + file.write('{}! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-]\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_NotchBetaNumDen'][i]) for i in range(len(rosco_vt['F_NotchBetaNumDen']))))) file.write('{:<13.5f} ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s].\n'.format(rosco_vt['F_SSCornerFreq'])) file.write('{:<13.5f} ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s].\n'.format(rosco_vt['F_WECornerFreq'])) - file.write('{} ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlCornerFreq'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) + file.write('{}! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlCornerFreq'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) file.write('{:<13.5f} ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s].\n'.format(rosco_vt['F_FlHighPassFreq'])) - file.write('{} ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlpCornerFreq'][i]) for i in range(len(rosco_vt['F_FlpCornerFreq']))))) + file.write('{}! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlpCornerFreq'][i]) for i in range(len(rosco_vt['F_FlpCornerFreq']))))) file.write('\n') file.write('!------- BLADE PITCH CONTROL ----------------------------------------------\n') @@ -108,10 +108,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<014.5f} ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad]\n'.format(rosco_vt['PC_Switch'])) 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('{} ! 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']))))) + 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']))))) file.write('{:<13.1f} ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {{0: Disable}}, [rad/s]\n'.format(rosco_vt['IPC_CornerFreqAct'])) file.write('\n') file.write('!------- VS TORQUE CONTROL ------------------------------------------------\n') @@ -137,7 +138,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- WIND SPEED ESTIMATOR ---------------------------------------------\n') file.write('{:<13.3f} ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m]\n'.format(rosco_vt['WE_BladeRadius'])) file.write('{:<11d} ! WE_CP_n - Amount of parameters in the Cp array\n'.format(int(rosco_vt['WE_CP_n']))) - file.write('{} ! WE_CP - Parameters that define the parameterized CP(lambda) function\n'.format(rosco_vt['WE_CP'])) + file.write('{:<13.1f} ! WE_CP - Parameters that define the parameterized CP(lambda) function\n'.format(rosco_vt['WE_CP'])) file.write('{:<13.1f} ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]\n'.format(rosco_vt['WE_Gamma'])) file.write('{:<13.1f} ! WE_GearboxRatio - Gearbox ratio [>=1], [-]\n'.format(rosco_vt['WE_GearboxRatio'])) file.write('{:<14.5f} ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2]\n'.format(rosco_vt['WE_Jtot'])) @@ -409,6 +410,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PC_FinePit'] = controller.min_pitch DISCON_dict['PC_Switch'] = 1 * deg2rad # ------- INDIVIDUAL PITCH CONTROL ------- + DISCON_dict['IPC_Vramp'] = controller.IPC_Vramp DISCON_dict['IPC_IntSat'] = 0.087266 DISCON_dict['IPC_KP'] = [controller.Kp_ipc1p, controller.Kp_ipc2p] DISCON_dict['IPC_KI'] = [controller.Ki_ipc1p, controller.Ki_ipc2p] diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 6f4472c5..64db4dc3 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 03/21/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 04/14/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file} @@ -16,19 +16,19 @@ 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -2 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: open loop control vs. wind speed} !------- FILTERS ---------------------------------------------------------- 0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] 0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -2.61601 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.500000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. -0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -7.848030 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +7.848030 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -46,10 +46,11 @@ 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- 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] -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]. +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]. 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] !------- VS TORQUE CONTROL ------------------------------------------------ @@ -75,7 +76,7 @@ !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array -0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function 0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 96.8 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] 311169343.31448 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] @@ -118,8 +119,8 @@ !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] -1.46445122e-08 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] -1.46445122e-09 ! Flp_Ki - Flap displacement integral gain for flap control [-] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] 0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] !------- Open Loop Control ----------------------------------------------------- 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 0889cb8a..c96242be 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 03/21/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 04/14/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file} @@ -23,12 +23,12 @@ 1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] 0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] 3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. -0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -10.461600 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +10.461600 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -46,10 +46,11 @@ 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- 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.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]. +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]. 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] !------- VS TORQUE CONTROL ------------------------------------------------ @@ -75,7 +76,7 @@ !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array -0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function 0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 1.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] 318628138.00000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 1ef3dcf9..a344bb32 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 03/21/22 +! - File written using ROSCO version 2.5.0 controller tuning logic on 04/14/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file} @@ -23,12 +23,12 @@ 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] 0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] 0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. -0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -46,10 +46,11 @@ 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- 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.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]. +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]. 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] !------- VS TORQUE CONTROL ------------------------------------------------ @@ -75,7 +76,7 @@ !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array -0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function 0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] 43702538.05700 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 4571d79f..db482001 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,6 +9,17 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +2.5.0 to ROSCO develop +------------------------------- +IPC +- A wind speed based soft cut-in using a sigma interpolation is added for the IPC controller + +====== ================= ====================================================================================================================================================================================================== +Line Flag Name Example Value +====== ================= ====================================================================================================================================================================================================== +49 IPC_Vramp 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] +====== ================= ====================================================================================================================================================================================================== + ROSCO v2.4.1 to ROSCO v2.5.0 ------------------------------- @@ -24,8 +35,6 @@ IPC - Proportional Control capabilities were added, 1P and 2P gains should be specified ====== ================= ====================================================================================================================================================================================================== -Added in ROSCO develop ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Flag Name Example Value ====== ================= ====================================================================================================================================================================================================== 27 F_WECornerFreq 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s].