Skip to content

Commit

Permalink
Implementing an effective wind speed estimator
Browse files Browse the repository at this point in the history
  • Loading branch information
Unknown committed Oct 5, 2018
1 parent b4eea60 commit 227a54d
Show file tree
Hide file tree
Showing 3 changed files with 96 additions and 57 deletions.
12 changes: 12 additions & 0 deletions Source/DRC_Types.f90
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,13 @@ 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_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_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)
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)
Expand All @@ -64,6 +71,7 @@ MODULE DRC_Types
REAL(4) :: DT
REAL(4) :: VS_GenPwr
REAL(4) :: GenSpeed
REAL(4) :: RotSpeed
REAL(4) :: Y_M
REAL(4) :: HorWindV
REAL(4) :: rootMOOP(3)
Expand All @@ -74,6 +82,7 @@ MODULE DRC_Types
! Internal controller variables
REAL(4) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s].
REAL(4) :: GenTq ! Electrical generator torque, [Nm].
REAL(4) :: GenTqMeas ! Measured generator torque [Nm]
REAL(4) :: GenArTq ! Electrical generator torque, for above-rated PI-control [Nm].
REAL(4) :: GenBrTq ! Electrical generator torque, for below-rated PI-control [Nm].
INTEGER(4) :: GlobalState ! Current global state to determine the behavior of the different controllers [-].
Expand All @@ -95,6 +104,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) :: 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
93 changes: 51 additions & 42 deletions Source/Functions.f90
Original file line number Diff line number Diff line change
Expand Up @@ -141,47 +141,7 @@ REAL FUNCTION DFController(error, Kd, Tf, DT, inst)
DFControllerLast(inst) = DFController
END FUNCTION DFController
!-------------------------------------------------------------------------------------------------------------------------------
! PRBS identification signal generator function
!REAL FUNCTION PRBSgen(mean, amplitude, cycleTime, seed, initValue, reset, inst)
!!
! IMPLICIT NONE
!
! ! Inputs
! REAL(4), INTENT(IN) :: mean
! REAL(4), INTENT(IN) :: amplitude
! INTEGER(4), INTENT(IN) :: cycleTime
! INTEGER(4), INTENT(IN) :: seed
! LOGICAL, INTENT(IN) :: reset
! REAL(4), INTENT(IN) :: initValue
!
! ! Local
! INTEGER(4) :: i ! Counter for making arrays
! REAL(4) :: randomNumber
! INTEGER(4), DIMENSION(99), SAVE :: FirstCall = (/ (1, i=1,99) /)
!
! IF ((FirstCall(inst) == 1) .OR. reset) THEN
! RANDOM_NUMBER(1)
! RAND(seed)
!
! FirstCall(inst) = 0
! PRBSgen = initValue
! ELSE
! randomNumber = RAND()
!
! IF randomNumber > 0.5 THEN
! randomNumber = 1
! ELSE
! randomNumber = 0
! END IF
!
! randomNumber = randomNumber - 0.5
! randomNumber = randomNumber*amplitude*2 + mean
! PRBSgen = randomNumber
! END IF
!
!END FUNCTION PRBSgen
!-------------------------------------------------------------------------------------------------------------------------------
! Stata machines, determines the state of the wind turbine to determine the corresponding control actions
! State machines, determines the state of the wind turbine to determine the corresponding control actions
! States:
! - VS/PC_State = 0, Error state, for debugging purposes (VS) / No pitch control active, pitch constant at fine-pitch (PC)
! - VS_State = 1, Region 1(.5) operation, torque control to keep the rotor at cut-in speed towards the Cp-max operational curve
Expand Down Expand Up @@ -342,7 +302,7 @@ SUBROUTINE ColemanTransformInverse(axTIn, axYIn, aziAngle, nHarmonic, aziOffset,
REAL(4), INTENT(IN) :: axTIn, axYIn ! Direct axis and quadrature axis
REAL(4), INTENT(IN) :: aziAngle ! Rotor azimuth angle
REAL(4), INTENT(IN) :: aziOffset ! Phase shift added to the azimuth angle
INTEGER(4), INTENT(IN) :: nHarmonic ! The harmonic number, nP
INTEGER(4), INTENT(IN) :: nHarmonic ! The harmonic number, nP

! Outputs

Expand All @@ -361,4 +321,53 @@ 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)
IMPLICIT NONE

! Inputs
REAL(4), INTENT(IN) :: rho(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)

END FUNCTION CPfunction
!-------------------------------------------------------------------------------------------------------------------------------
!Function for computing the aerodynamic torque, divided by the effective rotor torque of the turbine, for use in wind speed estimation
REAL FUNCTION IntertiaSpecAeroDynTorque(LocalVar, CntrPar)
USE DRC_Types, ONLY : LocalVariables, ControlParameters
IMPLICIT NONE

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

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

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

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

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

! Inputs
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))
LocalVar%WE_VwI = LocalVar%WE_VwI + LocalVar%WE_VwIdot*LocalVar%DT
LocalVar%WE_Vw = LocalVar%WE_VwI + LocalVar%WE_Gamma*LocalVar%RotSpeed

END SUBROUTINE WindSpeedEstimator
!-------------------------------------------------------------------------------------------------------------------------------
END MODULE Functions
48 changes: 33 additions & 15 deletions Source/ReadSetParameters.f90
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,18 @@ 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
Expand All @@ -109,26 +121,28 @@ END SUBROUTINE ReadControlParameterFileSub
SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar)
USE DRC_Types, ONLY : LocalVariables

REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller.
REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller.
TYPE(LocalVariables), INTENT(INOUT) :: LocalVar

! Load variables from calling program (See Appendix A of Bladed User's Guide):
LocalVar%iStatus = NINT(avrSWAP(1))
LocalVar%Time = avrSWAP(2)
LocalVar%DT = avrSWAP(3)
LocalVar%BlPitch(1) = avrSWAP(4)
LocalVar%VS_MechGenPwr = avrSWAP(14)
LocalVar%VS_GenPwr = avrSWAP(15)
LocalVar%GenSpeed = avrSWAP(20)
LocalVar%Y_M = avrSWAP(24)
LocalVar%HorWindV = avrSWAP(27)
LocalVar%rootMOOP(1) = avrSWAP(30)
LocalVar%rootMOOP(2) = avrSWAP(31)
LocalVar%rootMOOP(3) = avrSWAP(32)
LocalVar%BlPitch(2) = avrSWAP(33)
LocalVar%BlPitch(3) = avrSWAP(34)
LocalVar%Azimuth = avrSWAP(60)
LocalVar%NumBl = NINT(avrSWAP(61))
LocalVar%DT = avrSWAP(3)
LocalVar%BlPitch(1) = avrSWAP(4)
LocalVar%VS_MechGenPwr = avrSWAP(14)
LocalVar%VS_GenPwr = avrSWAP(15)
LocalVar%GenSpeed = avrSWAP(20)
LocalVar%RotSpeed = avrSWAP(21)
LocalVar%GenTqMeas = avrSWAP(24)
LocalVar%Y_M = avrSWAP(24)
LocalVar%HorWindV = avrSWAP(27)
LocalVar%rootMOOP(1) = avrSWAP(30)
LocalVar%rootMOOP(2) = avrSWAP(31)
LocalVar%rootMOOP(3) = avrSWAP(32)
LocalVar%BlPitch(2) = avrSWAP(33)
LocalVar%BlPitch(3) = avrSWAP(34)
LocalVar%Azimuth = avrSWAP(60)
LocalVar%NumBl = NINT(avrSWAP(61))
END SUBROUTINE ReadAvrSWAP

SUBROUTINE Assert(LocalVar, CntrPar, avrSWAP, aviFAIL, ErrMsg, size_avcMSG)
Expand Down Expand Up @@ -337,6 +351,10 @@ SUBROUTINE SetParameters(avrSWAP, aviFAIL, ErrMsg, size_avcMSG, CntrPar, LocalVa
! END DO
LocalVar%Y_AccErr = 0.0 ! This will ensure that the accumulated yaw error starts at zero
LocalVar%Y_YawEndT = -1.0 ! This will ensure that the initial yaw end time is lower than the actual time to prevent initial yawing

! Wind speed estimator initialization, we always assume an initial wind speed of 10 m/s
LocalVar%WE_Vw = 10
LocalVar%WE_VwI = LocalVar%WE_Vw - CntrPar%WE_Gamma*LocalVar%RotSpeed

! Check validity of input parameters:
CALL Assert(LocalVar, CntrPar, avrSWAP, aviFAIL, ErrMsg, size_avcMSG)
Expand Down

0 comments on commit 227a54d

Please sign in to comment.