Skip to content

Commit

Permalink
Merge branch 'WSest_dev'
Browse files Browse the repository at this point in the history
  • Loading branch information
Unknown committed Nov 14, 2018
2 parents 563b0de + 4874c87 commit 9a0dc95
Show file tree
Hide file tree
Showing 7 changed files with 150 additions and 79 deletions.
2 changes: 0 additions & 2 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,5 @@ Source/Obj_win32
Source/x64/
Source/Release/
#Archive

Scripts/CompileDISCONHereCopyRun\.cmd

\.vs/
11 changes: 9 additions & 2 deletions Parameter_files/DTU10MW/ControllerParameters.in
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,21 @@
150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s].
250000.0 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm].
0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm].
31.415 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path [rad/s]
20.94395 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path [rad/s]
104.1 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), N-m/(rad/s)^2
1.0E+07 ! VS_RtPwr - Wind turbine rated power [W]
198943.6 ! VS_RtTq - Rated torque, [Nm].
211642 ! VS_RtTq - Rated torque, [Nm]. XXX 198943.6 XXX
42.411 ! VS_RefSpd - Rated generator speed [rad/s]
1 ! VS_n - Number of controller gains
-27338.24 ! VS_KP - Proportional gain for generator PI torque controller, used in the transitional 2.5 region, [1/(rad/s) Nm]
-6134.68 ! VS_KI - Integral gain for generator PI torque controller, used in the transitional 2.5 region, [1/rad Nm]
89.166 ! 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 XXX Needs to be updated, these are values of the NREL5MW XXX
20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]
50 ! WE_GearboxRatio - Gearbox ratio, >=1 [-]
2.0E+08 ! 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
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
26 changes: 22 additions & 4 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,7 +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
INTEGER(4) :: Y_ControlMode ! Yaw control mode: (0 = no yaw control, 1 = yaw rate control, 2 = yaw-by-IPC)

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 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)
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 All @@ -64,6 +77,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 +88,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 +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) :: 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
120 changes: 71 additions & 49 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 @@ -266,28 +226,33 @@ SUBROUTINE Debug(LocalVar, CntrPar, avrSWAP, RootName, size_avcOUTNAME)
IF (LocalVar%iStatus == 0) THEN ! .TRUE. if we're on the first call to the DLL
! If we're debugging, open the debug file and write the header:
IF (CntrPar%LoggingLevel > 0) THEN
OPEN(UnDb, FILE=TRIM(RootName)//'.dbg', STATUS='REPLACE')
WRITE (UnDb,'(A)') ' LocalVar%Time ' //Tab//'LocalVar%PC_PitComT ' //Tab//'LocalVar%PC_SpdErr ' //Tab//'LocalVar%PC_KP ' //Tab//'LocalVar%PC_KI ' //Tab//'LocalVar%Y_M ' //Tab//'LocalVar%rootMOOP(1) '//Tab//'VS_RtPwr '//Tab//'LocalVar%GenTq'
WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(rad) ' //Tab//'(rad/s) '//Tab//'(-) ' //Tab//'(-) ' //Tab//'(rad) ' //Tab//'(?) ' //Tab//'(W) '//Tab//'(Nm) '
!OPEN(unit=UnDb, FILE=TRIM(RootName)//'.dbg', STATUS='NEW')
OPEN(unit=UnDb, FILE='DEBUG.dbg')
WRITE (UnDb,'(A)') ' LocalVar%Time ' //Tab//'LocalVar%WE_Vw '
WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(m/s) '
!WRITE (UnDb,'(A)') ' LocalVar%Time ' //Tab//'LocalVar%PC_PitComT ' //Tab//'LocalVar%PC_SpdErr ' //Tab//'LocalVar%PC_KP ' //Tab//'LocalVar%PC_KI ' //Tab//'LocalVar%Y_M ' //Tab//'LocalVar%rootMOOP(1) '//Tab//'VS_RtPwr '//Tab//'LocalVar%GenTq'
!WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(rad) ' //Tab//'(rad/s) '//Tab//'(-) ' //Tab//'(-) ' //Tab//'(rad) ' //Tab//'(?) ' //Tab//'(W) '//Tab//'(Nm) '
END IF

IF (CntrPar%LoggingLevel > 1) THEN
OPEN(UnDb2, FILE=TRIM(RootName)//'.dbg2', STATUS='REPLACE')
!OPEN(UnDb2, FILE=TRIM(RootName)//'.dbg2', STATUS='REPLACE')
OPEN(unit=UnDb, FILE='DEBUG2.dbg')
WRITE(UnDb2,'(/////)')
WRITE(UnDb2,'(A,85("'//Tab//'AvrSWAP(",I2,")"))') 'LocalVar%Time ', (i,i=1,85)
WRITE(UnDb2,'(A,85("'//Tab//'(-)"))') '(s)'
END IF
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, Est. 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
! PRINT *, LocalVar%RotSpeed
END IF

! Output debugging information if requested:
IF (CntrPar%LoggingLevel > 0) THEN
WRITE (UnDb,FmtDat) LocalVar%Time, LocalVar%Y_MErr, LocalVar%Y_AccErr, CntrPar%Y_ErrThresh, LocalVar%Y_ErrLPFFast, LocalVar%Y_ErrLPFSlow, avrSWAP(48)
WRITE (UnDb,FmtDat) LocalVar%Time, LocalVar%WE_Vw
END IF

IF (CntrPar%LoggingLevel > 1) THEN
Expand Down Expand Up @@ -342,7 +307,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 +326,61 @@ 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(CP, lambda)
IMPLICIT NONE

! Inputs
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(-CP(1)/lambda)*(CP(2)/lambda-CP(3))+CP(4)*lambda
CPfunction = saturate(CPfunction, 0.001, 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 AeroDynTorque(LocalVar, CntrPar)
USE DRC_Types, ONLY : LocalVariables, ControlParameters
IMPLICIT NONE

! Inputs
TYPE(ControlParameters), INTENT(IN) :: CntrPar
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(CntrPar%WE_CP, Lambda)

AeroDynTorque = 0.5*(CntrPar%WE_RhoAir*RotorArea)*(LocalVar%WE_Vw**3/LocalVar%RotSpeed)*Cp
AeroDynTorque = MAX(AeroDynTorque, 0.0)

END FUNCTION AeroDynTorque
!-------------------------------------------------------------------------------------------------------------------------------
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/CntrPar%WE_Jtot*(LocalVar%GenTqMeas*CntrPar%WE_GearboxRatio - AeroDynTorque(LocalVar, CntrPar))
LocalVar%WE_VwIdot = CntrPar%WE_Gamma/CntrPar%WE_Jtot*(LocalVar%VS_LastGenTrq*CntrPar%WE_GearboxRatio - AeroDynTorque(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 + CntrPar%WE_Gamma*LocalVar%RotSpeed

END SUBROUTINE WindSpeedEstimator
!-------------------------------------------------------------------------------------------------------------------------------
END MODULE Functions
Loading

0 comments on commit 9a0dc95

Please sign in to comment.