Skip to content

Commit

Permalink
Fully implemented WS estimator, with a little bug
Browse files Browse the repository at this point in the history
  • Loading branch information
Unknown committed Oct 5, 2018
1 parent 227a54d commit d3c5e58
Show file tree
Hide file tree
Showing 5 changed files with 67 additions and 46 deletions.
7 changes: 7 additions & 0 deletions Parameter_files/NREL5MW/ControllerParameters.in
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,13 @@
1 ! VS_n - Number of controller gains
-4200 ! VS_KP - Proportional gain for generator PI torque controller, used in the transitional 2.5 region, [1/(rad/s) Nm]
-2100 ! VS_KI - Integral gain for generator PI torque controller, used in the transitional 2.5 region, [1/rad Nm]
63.0 ! WE_BladeRadius - Blade length [m]
4 ! WE_CP_n - Amount of parameters in the Cp array
14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(\lambda) function
20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]
97 ! WE_GearboxRatio - Gearbox ratio, >=1 [-]
4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS [kg m^2]
1.225 ! WE_RhoAir - Air density [kg m^-3]
0 ! Y_ControlMode - Yaw control mode: (0 = no yaw control, 1 = yaw rate control, 2 = yaw-by-IPC)
1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s]
0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contrbution to pitch from yaw-by-IPC), [rad]
Expand Down
1 change: 1 addition & 0 deletions Source/DISCON.f90
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME

IF ((LocalVar%iStatus >= 0) .AND. (aviFAIL >= 0)) THEN ! Only compute control calculations if no error has occurred and we are not on the last time step
CALL StateMachine(CntrPar, LocalVar)
CALL WindSpeedEstimator(LocalVar, CntrPar)
CALL VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst)
CALL PitchControl(avrSWAP, CntrPar, LocalVar, objInst)
CALL YawRateControl(avrSWAP, CntrPar, LocalVar, objInst)
Expand Down
28 changes: 17 additions & 11 deletions Source/DRC_Types.f90
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,17 @@ MODULE DRC_Types

TYPE, PUBLIC :: ControlParameters
INTEGER(4) :: LoggingLevel ! 0 = write no debug files, 1 = write standard output .dbg-file, 2 = write standard output .dbg-file and complete avrSWAP-array .dbg2-file

INTEGER(4) :: F_FilterType ! 1 = first-order low-pass filter, 2 = second-order low-pass filter
REAL(4) :: F_CornerFreq ! Corner frequency (-3dB point) in the first-order low-pass filter, [rad/s]
REAL(4) :: F_Damping ! Damping coefficient if F_FilterType = 2, unused otherwise
INTEGER(4) :: IPC_ControlMode ! Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) 0 = off / 1 = (1P reductions) / 2 = (1P+2P reductions)

INTEGER(4) :: IPC_ControlMode ! Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) 0 = off / 1 = (1P reductions) / 2 = (1P+2P reductions)
REAL(4) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC)
REAL(4), DIMENSION(:), ALLOCATABLE :: IPC_KI ! Integral gain for the individual pitch controller, [-]. 8E-10
REAL(4), DIMENSION(:), ALLOCATABLE :: IPC_aziOffset ! Phase offset added to the azimuth angle for the individual pitch controller, [rad].
INTEGER(4) :: PC_GS_n ! Amount of gain-scheduling table entries

INTEGER(4) :: PC_GS_n ! Amount of gain-scheduling table entries
REAL(4), DIMENSION(:), ALLOCATABLE :: PC_GS_angles ! Gain-schedule table: pitch angles
REAL(4), DIMENSION(:), ALLOCATABLE :: PC_GS_KP ! Gain-schedule table: pitch controller kp gains
REAL(4), DIMENSION(:), ALLOCATABLE :: PC_GS_KI ! Gain-schedule table: pitch controller ki gains
Expand All @@ -24,7 +27,8 @@ MODULE DRC_Types
REAL(4) :: PC_RefSpd ! Desired (reference) HSS speed for pitch controller, [rad/s].
REAL(4) :: PC_FinePit ! Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface]
REAL(4) :: PC_Switch ! Angle above lowest minimum pitch angle for switch [rad]
INTEGER(4) :: VS_ControlMode ! Generator torque control mode in above rated conditions, 0 = constant torque / 1 = constant power

INTEGER(4) :: VS_ControlMode ! Generator torque control mode in above rated conditions, 0 = constant torque / 1 = constant power
REAL(4) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-]
REAL(4) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900
REAL(4) :: VS_MaxRat ! Maximum torque rate (in absolute value) in torque controller, [Nm/s].
Expand All @@ -38,14 +42,16 @@ MODULE DRC_Types
INTEGER(4) :: VS_n ! Number of controller gains
REAL(4), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region
REAL(4), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region
REAL(4) :: WE_BladeRadius ! Blade length [m]
REAL(4) :: WE_CP_n ! Amount of parameters in the Cp array
REAL(4), DIMENSION(:), ALLOCATABLE :: WE_CP ! Paremeters that define the parameterized CP(\lambda) function

REAL(4) :: WE_BladeRadius ! Blade length [m]
INTEGER(4) :: WE_CP_n ! Amount of parameters in the Cp array
REAL(4), DIMENSION(:), ALLOCATABLE :: WE_CP ! Parameters that define the parameterized CP(\lambda) function
REAL(4) :: WE_Gamma ! Adaption gain of the wind speed estimator algorithm [m/rad]
REAL(4) :: WE_GearboxRatio ! Gearbox ratio, >=1 [-]
REAL(4) :: WE_Jtot ! Total drivetrain inertia, including blades, hub and casted generator intertia to LSS [kg m^2]
REAL(4) :: WE_Jtot ! Total drivetrain inertia, including blades, hub and casted generator inertia to LSS [kg m^2]
REAL(4) :: WE_RhoAir ! Air density [kg m^-3]
INTEGER(4) :: Y_ControlMode ! Yaw control mode: (0 = no yaw control, 1 = yaw rate control, 2 = yaw-by-IPC)

INTEGER(4) :: Y_ControlMode ! Yaw control mode: (0 = no yaw control, 1 = yaw rate control, 2 = yaw-by-IPC)
REAL(4) :: Y_ErrThresh ! Error threshold [rad]. Turbine begins to yaw when it passes this. (104.71975512) -- 1.745329252
REAL(4) :: Y_IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from yaw-by-IPC)
INTEGER(4) :: Y_IPC_n ! Number of controller gains (yaw-by-IPC)
Expand Down Expand Up @@ -104,9 +110,9 @@ MODULE DRC_Types
REAL(4) :: VS_SpdErrAr ! Current speed error (generator torque control) [rad/s].
REAL(4) :: VS_SpdErrBr ! Current speed error (generator torque control) [rad/s].
INTEGER(4) :: VS_State ! State of the torque control system
REAL(4) :: WS_Vw ! Estimated wind speed [m/s]
REAL(4) :: WS_VwI ! Integrated wind speed quantity for estimation [m/s]
REAL(4) :: WS_VwIdot ! Differentated integrated wind speed quantity for estimation [m/s]
REAL(4) :: WE_Vw ! Estimated wind speed [m/s]
REAL(4) :: WE_VwI ! Integrated wind speed quantity for estimation [m/s]
REAL(4) :: WE_VwIdot ! Differentated integrated wind speed quantity for estimation [m/s]
REAL(4) :: Y_AccErr ! Accumulated yaw error [rad].
REAL(4) :: Y_ErrLPFFast ! Filtered yaw error by fast low pass filter [rad].
REAL(4) :: Y_ErrLPFSlow ! Filtered yaw error by slow low pass filter [rad].
Expand Down
37 changes: 22 additions & 15 deletions Source/Functions.f90
Original file line number Diff line number Diff line change
Expand Up @@ -240,8 +240,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, avrSWAP, RootName, size_avcOUTNAME)
ELSE
! Print simulation status, every 10 seconds
IF (MODULO(LocalVar%Time, 10.0) == 0) THEN
WRITE(*, 100) LocalVar%GenSpeedF*RPS2RPM, LocalVar%BlPitch(1)*R2D, avrSWAP(15)/1000.0 ! LocalVar%Time !/1000.0
100 FORMAT('Generator speed: ', f6.1, ' RPM, Pitch angle: ', f5.1, ' deg, Power: ', f7.1, ' kW')
WRITE(*, 100) LocalVar%GenSpeedF*RPS2RPM, LocalVar%BlPitch(1)*R2D, avrSWAP(15)/1000.0, LocalVar%WE_Vw ! LocalVar%Time !/1000.0
100 FORMAT('Generator speed: ', f6.1, ' RPM, Pitch angle: ', f5.1, ' deg, Power: ', f7.1, ' kW, Wind Speed: ', f5.1, ' m/s')
! PRINT *, LocalVar%PC_State, LocalVar%VS_State, CntrPar%VS_Rgn3Pitch, CntrPar%PC_FinePit, CntrPar%PC_Switch, LocalVar%BlPitch(1) ! Additional debug info
END IF

Expand Down Expand Up @@ -322,15 +322,15 @@ SUBROUTINE ColemanTransformInverse(axTIn, axYIn, aziAngle, nHarmonic, aziOffset,
END SUBROUTINE ColemanTransformInverse
!-------------------------------------------------------------------------------------------------------------------------------
!Paremeterized Cp(lambda) function for a fixed pitch angle. Circumvents the need of importing a look-up table
REAL FUNCTION CPfunction(rho, lambda)
REAL FUNCTION CPfunction(CP, lambda)
IMPLICIT NONE

! Inputs
REAL(4), INTENT(IN) :: rho(4) ! Parameters defining the parameterizable Cp(lambda) function
REAL(4), INTENT(IN) :: CP(4) ! Parameters defining the parameterizable Cp(lambda) function
REAL(4), INTENT(IN) :: lambda ! Estimated or measured tip-speed ratio input
CPfunction = exp(-rho(1)/lambda)*(rho(2)/lambda-rho(3))+rho(4)*lambda
CPfunction = saturate(CPfunction, 0.01, 1.0)
CPfunction = exp(-CP(1)/lambda)*(CP(2)/lambda-CP(3))+CP(4)*lambda
CPfunction = saturate(CPfunction, 0.001, 1.0)

END FUNCTION CPfunction
!-------------------------------------------------------------------------------------------------------------------------------
Expand All @@ -341,33 +341,40 @@ REAL FUNCTION IntertiaSpecAeroDynTorque(LocalVar, CntrPar)

! Inputs
TYPE(ControlParameters), INTENT(IN) :: CntrPar
TYPE(LocalVariables), INTENT(INOUT) :: LocalVar
TYPE(LocalVariables), INTENT(IN) :: LocalVar

! Local
REAL(4) :: RotorArea
REAL(4) :: Cp
REAL(4) :: Lambda

RotorArea = PI*CntrPar%WE_BladeRadius**2
Lambda = LocalVar%RotSpeed*CntrPar%WE_BladeRadius/LocalVar%WE_Vw
Cp = CPfunction(LocalVar%RhoAir, Lambda)
Cp = CPfunction(CntrPar%WE_CP, Lambda)

IntertiaSpecAeroDynTorque = (CntrPar%WE_RhoAir*RotorArea)/(2*CntrPar%WE_Jtot)*(LocalVar%WE_Vw**3/LocalVar%RotSpeed)*Cp*Lambda
IntertiaSpecAeroDynTorque = MAX(IntertiaSpecAeroDynTorque, 0)
IntertiaSpecAeroDynTorque = MAX(IntertiaSpecAeroDynTorque, 0.0)

END FUNCTION IntertiaSpecAeroDynTorque
!-------------------------------------------------------------------------------------------------------------------------------
REAL SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar)
SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar)
USE DRC_Types, ONLY : LocalVariables, ControlParameters
IMPLICIT NONE

! Inputs
TYPE(ControlParameters), INTENT(IN) :: CntrPar
TYPE(LocalVariables), INTENT(INOUT) :: LocalVar
TYPE(ControlParameters), INTENT(IN) :: CntrPar
TYPE(LocalVariables), INTENT(INOUT) :: LocalVar

LocalVar%WE_VwIdot = CntrPar%WE_Gamma*(LocalVar%GenTqMeas*CntrPar%WE_GearboxRatio/CntrPar%WE_Jtot - IntertiaSpecAeroDynTorque(LocalVar, CntrPar))

IF (MODULO(LocalVar%Time, 5.0) == 0.0) THEN
PRINT *, LocalVar%GenTqMeas*CntrPar%WE_GearboxRatio/CntrPar%WE_Jtot
PRINT *, IntertiaSpecAeroDynTorque(LocalVar, CntrPar)
END IF

LocalVar%WE_VwI = LocalVar%WE_VwI + LocalVar%WE_VwIdot*LocalVar%DT
LocalVar%WE_Vw = LocalVar%WE_VwI + LocalVar%WE_Gamma*LocalVar%RotSpeed
LocalVar%WE_Vw = LocalVar%WE_VwI + CntrPar%WE_Gamma*LocalVar%RotSpeed
END SUBROUTINE WindSpeedEstimator
!-------------------------------------------------------------------------------------------------------------------------------
END MODULE Functions
40 changes: 20 additions & 20 deletions Source/ReadSetParameters.f90
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@ MODULE ReadSetParameters
SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar)
USE DRC_Types, ONLY : ControlParameters, LocalVariables

INTEGER(4), PARAMETER :: UnControllerParameters = 89
TYPE(ControlParameters), INTENT(INOUT) :: CntrPar
TYPE(LocalVariables), INTENT(IN) :: LocalVar
INTEGER(4), PARAMETER :: UnControllerParameters = 89
TYPE(ControlParameters), INTENT(INOUT) :: CntrPar
TYPE(LocalVariables), INTENT(IN) :: LocalVar

OPEN(unit=UnControllerParameters, file='ControllerParameters.in', status='old', action='read')

Expand Down Expand Up @@ -76,6 +76,18 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar)

ALLOCATE(CntrPar%VS_KI(CntrPar%VS_n))
READ(UnControllerParameters,*) CntrPar%VS_KI

!-------------- WIND SPEED ESTIMATOR CONTANTS ------------------
READ(UnControllerParameters, *) CntrPar%WE_BladeRadius
READ(UnControllerParameters, *) CntrPar%WE_CP_n

ALLOCATE(CntrPar%WE_CP(CntrPar%WE_CP_n))
READ(UnControllerParameters, *) CntrPar%WE_CP

READ(UnControllerParameters, *) CntrPar%WE_Gamma
READ(UnControllerParameters, *) CntrPar%WE_GearboxRatio
READ(UnControllerParameters, *) CntrPar%WE_Jtot
READ(UnControllerParameters, *) CntrPar%WE_RhoAir

!------------------- YAW CONSTANTS -----------------------
READ(UnControllerParameters, *) CntrPar%Y_ControlMode
Expand All @@ -97,23 +109,11 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar)
READ(UnControllerParameters, *) CntrPar%Y_omegaLPSlow
READ(UnControllerParameters, *) CntrPar%Y_Rate

!-------------- WIND SPEED ESTIMATOR CONTANTS ------------------
READ(UnControllerParameters, *) CntrPar%WE_BladeRadius
READ(UnControllerParameters, *) CntrPar%WE_Gamma
READ(UnControllerParameters, *) CntrPar%WE_GearboxRatio
READ(UnControllerParameters, *) CntrPar%WE_Jtot
READ(UnControllerParameters, *) CntrPar%WE_CP_n

ALLOCATE(CntrPar%WE_CP(CntrPar%WE_CP_n))
READ(UnControllerParameters, *) CntrPar%WE_CP

READ(UnControllerParameters, *) CntrPar%WE_RhoAir

!------------------- CALCULATED CONSTANTS -----------------------
CntrPar%PC_RtTq99 = CntrPar%VS_RtTq*0.99
CntrPar%VS_MinOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_MinOMSpd**2
CntrPar%VS_MaxOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_RefSpd**2
CntrPar%VS_Rgn3Pitch = CntrPar%PC_FinePit + CntrPar%PC_Switch
CntrPar%PC_RtTq99 = CntrPar%VS_RtTq*0.99
CntrPar%VS_MinOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_MinOMSpd**2
CntrPar%VS_MaxOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_RefSpd**2
CntrPar%VS_Rgn3Pitch = CntrPar%PC_FinePit + CntrPar%PC_Switch

CLOSE(UnControllerParameters)
END SUBROUTINE ReadControlParameterFileSub
Expand All @@ -133,7 +133,7 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar)
LocalVar%VS_GenPwr = avrSWAP(15)
LocalVar%GenSpeed = avrSWAP(20)
LocalVar%RotSpeed = avrSWAP(21)
LocalVar%GenTqMeas = avrSWAP(24)
LocalVar%GenTqMeas = avrSWAP(23)
LocalVar%Y_M = avrSWAP(24)
LocalVar%HorWindV = avrSWAP(27)
LocalVar%rootMOOP(1) = avrSWAP(30)
Expand Down

0 comments on commit d3c5e58

Please sign in to comment.