Skip to content

Commit

Permalink
Update DRC_Fortran from Nikhar's repo
Browse files Browse the repository at this point in the history
  • Loading branch information
nikhar-abbas committed Oct 8, 2019
1 parent 1f87bda commit 1fcf157
Show file tree
Hide file tree
Showing 6 changed files with 50 additions and 40 deletions.
Binary file modified DRC_Fortran/DISCON/DISCON_glin64.so
Binary file not shown.
9 changes: 5 additions & 4 deletions DRC_Fortran/Source/ControllerBlocks.f90
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData)
! Extended Kalman Filter (EKF) implementation
ELSEIF (CntrPar%WE_Mode == 2) THEN
! Define contant values
L = 2.0 * CntrPar%WE_BladeRadius
L = 4.0 * CntrPar%WE_BladeRadius
Ti = 0.2
R_m = 0.02
H = RESHAPE((/1.0 , 0.0 , 0.0/),(/1,3/))
Expand Down Expand Up @@ -185,10 +185,10 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData)
F(2,3) = PI * v_t/(2.0*L)

! Update process noise covariance
Q(1,1) = 0.0001
Q(1,1) = 0.00001
Q(2,2) =(PI * (v_m**3.0) * (Ti**2.0)) / L
Q(3,3) = (2.0**2.0)/600.0
\

! Prediction update
! Tau_r = 0.5 * CntrPar%WE_RhoAir * PI *CntrPar%WE_BladeRadius**3 * Cp_op * v_h**2 * 1.0/(lambda)
Tau_r = AeroDynTorque(LocalVar,CntrPar,PerfData)
Expand All @@ -215,6 +215,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData)
v_h = v_t + v_m
LocalVar%TestType = v_m + v_t
LocalVar%WE_Vw = v_m + v_t
! LocalVar%WE_Vw = LPFilter(v_m + v_t,LocalVar%DT,0.5,LocalVar%iStatus,.FALSE.,objInst%instLPF)
ENDIF

ELSE
Expand Down Expand Up @@ -274,7 +275,7 @@ REAL FUNCTION PeakShaving(LocalVar, CntrPar, objInst)
! V_towertop = PIController(LocalVar%FA_Acc, 0.0, 1.0, -100.00, 100.00, LocalVar%DT, 0.0, .FALSE., objInst%instPI)

Vhat = LocalVar%WE_Vw
Vhatf = LPFilter(Vhat,LocalVar%DT,0.04,LocalVar%iStatus,.FALSE.,objInst%instLPF)
Vhatf = LPFilter(Vhat,LocalVar%DT,0.2,LocalVar%iStatus,.FALSE.,objInst%instLPF)
LocalVar%TestType = Vhatf
! Define minimum blade pitch angle as a function of estimated wind speed
PeakShaving = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, Vhatf)
Expand Down
4 changes: 2 additions & 2 deletions DRC_Fortran/Source/Controllers.f90
Original file line number Diff line number Diff line change
Expand Up @@ -118,12 +118,12 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst)
IF (LocalVar%VS_State >= 4) THEN
VS_MaxTq = CntrPar%VS_RtTq
ELSE
! VS_MaxTq = CntrPar%VS_MaxTq
! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque
VS_MaxTq = CntrPar%VS_RtTq
ENDIF
LocalVar%GenTq = PIController(LocalVar%VS_SpdErr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, VS_MaxTq, LocalVar%DT, CntrPar%VS_MaxOMTq, .FALSE., objInst%instPI)

! K*Omega^2 control law with PI torque control in transition regions
! K*Omega^2 control law with PI torque control in transition regions
ELSE
! Update PI loops for region 1.5 and 2.5 PI control
! LocalVar%GenArTq = PIController(LocalVar%VS_SpdErrAr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MaxOMTq, CntrPar%VS_ArSatTq, LocalVar%DT, CntrPar%VS_RtTq, .TRUE., objInst%instPI)
Expand Down
3 changes: 2 additions & 1 deletion DRC_Fortran/Source/DISCON.f90
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME
TYPE(LocalVariables), SAVE :: LocalVar
TYPE(ObjectInstances), SAVE :: objInst
TYPE(PerformanceData), SAVE :: PerfData

!------------------------------------------------------------------------------------------------------------------------------
! Main control calculations
!------------------------------------------------------------------------------------------------------------------------------
Expand All @@ -48,7 +49,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME
CALL PreFilterMeasuredSignals(CntrPar, LocalVar, objInst)

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 ComputeVariablesSetpoints(CntrPar, LocalVar)
CALL ComputeVariablesSetpoints(CntrPar, LocalVar, objInst)

CALL StateMachine(CntrPar, LocalVar)
CALL WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData)
Expand Down
1 change: 1 addition & 0 deletions DRC_Fortran/Source/DRC_Types.f90
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ 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) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad]

INTEGER(4) :: SS_Mode ! Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing}
REAL(4) :: SS_VSGainBias ! Variable speed torque controller gain bias, [(rad/s)/rad].
Expand Down
73 changes: 40 additions & 33 deletions DRC_Fortran/Source/ReadSetParameters.f90
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar)
READ(UnControllerParameters,*) CntrPar%VS_KP
ALLOCATE(CntrPar%VS_KI(CntrPar%VS_n))
READ(UnControllerParameters,*) CntrPar%VS_KI
READ(UnControllerParameters,*) CntrPar%VS_TSRopt
READ(UnControllerParameters, *)

!------- Setpoint Smoother --------------------------------
Expand Down Expand Up @@ -179,17 +180,20 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar)
END SUBROUTINE ReadControlParameterFileSub
! -----------------------------------------------------------------------------------
! Calculate setpoints for primary control actions
SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar)
USE DRC_Types, ONLY : ControlParameters, LocalVariables
SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst)
USE DRC_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances

! Allocate variables
TYPE(ControlParameters), INTENT(INOUT) :: CntrPar
TYPE(LocalVariables), INTENT(INOUT) :: LocalVar
TYPE(ObjectInstances), INTENT(INOUT) :: objInst

REAL(4) :: VS_RefSpd ! Referece speed for variable speed torque controller, [rad/s]
REAL(4) :: PC_RefSpd ! Referece speed for pitch controller, [rad/s]
REAL(4) :: Omega_op ! Optimal TSR-tracking generator speed, [rad/s]
REAL(4) :: WE_Vw_f ! Filtered Wind Speed Estimate
! temp
REAL(4) :: VS_TSRop = 7.5
! REAL(4) :: VS_TSRop = 7.5

! ----- Calculate yaw misalignment error -----
LocalVar%Y_MErr = LocalVar%Y_M + CntrPar%Y_MErrSet ! Yaw-alignment error
Expand All @@ -207,7 +211,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar)
! ----- Torque controller reference errors -----
! Define VS reference generator speed [rad/s]
IF (CntrPar%VS_ControlMode == 2) THEN
VS_RefSpd = (VS_TSRop * LocalVar%WE_Vw / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio
WE_Vw_f = LPFilter(LocalVar%We_Vw, LocalVar%DT, 0.1, LocalVar%iStatus, .FALSE., objInst%instLPF)
VS_RefSpd = (CntrPar%VS_TSRopt * WE_Vw_f / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio
VS_RefSpd = saturate(VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%PC_RefSpd)
ELSE
VS_RefSpd = CntrPar%VS_RefSpd
Expand Down Expand Up @@ -366,36 +371,38 @@ SUBROUTINE Assert(LocalVar, CntrPar, avrSWAP, aviFAIL, ErrMsg, size_avcMSG)
ErrMsg = 'IPC_KI(2) must be zero or greater than zero.'
ENDIF

IF (CntrPar%Y_IPC_omegaLP <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_IPC_omegaLP must be greater than zero.'
ENDIF

IF (CntrPar%Y_IPC_zetaLP <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_IPC_zetaLP must be greater than zero.'
ENDIF

IF (CntrPar%Y_ErrThresh <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_ErrThresh must be greater than zero.'
ENDIF

IF (CntrPar%Y_Rate <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'CntrPar%Y_Rate must be greater than zero.'
ENDIF

IF (CntrPar%Y_omegaLPFast <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_omegaLPFast must be greater than zero.'
ENDIF

IF (CntrPar%Y_omegaLPSlow <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_omegaLPSlow must be greater than zero.'
! ---- Yaw Control ----
IF (CntrPar%Y_ControlMode > 0) THEN
IF (CntrPar%Y_IPC_omegaLP <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_IPC_omegaLP must be greater than zero.'
ENDIF

IF (CntrPar%Y_IPC_zetaLP <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_IPC_zetaLP must be greater than zero.'
ENDIF

IF (CntrPar%Y_ErrThresh <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_ErrThresh must be greater than zero.'
ENDIF

IF (CntrPar%Y_Rate <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'CntrPar%Y_Rate must be greater than zero.'
ENDIF

IF (CntrPar%Y_omegaLPFast <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_omegaLPFast must be greater than zero.'
ENDIF

IF (CntrPar%Y_omegaLPSlow <= 0.0) THEN
aviFAIL = -1
ErrMsg = 'Y_omegaLPSlow must be greater than zero.'
ENDIF
ENDIF

! Abort if the user has not requested a pitch angle actuator (See Appendix A
! of Bladed User's Guide):
IF (NINT(avrSWAP(10)) /= 0) THEN ! .TRUE. if a pitch angle actuator hasn't been requested
Expand Down

0 comments on commit 1fcf157

Please sign in to comment.