Skip to content

Commit

Permalink
Cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
nikhar-abbas committed Jan 10, 2020
1 parent 2300380 commit dcbb2bc
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 26 deletions.
10 changes: 4 additions & 6 deletions src/ControllerBlocks.f90
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
! State Machine: determine the state of the wind turbine to specify the corresponding control actions
! WindSpeedEstimator: Estimate wind speed
! SetpointSmoother: Modify generator torque and blade pitch controller setpoints in transition region
! PeakShaving: Limit rotor thrust near rated operation
! PitchSaturation: Prescribe specific minimum pitch schedule
! Shutdown: Shutdown control for max bld pitch

MODULE ControllerBlocks
Expand Down Expand Up @@ -202,14 +202,10 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData)
! Measurement update
S = MATMUL(H,MATMUL(P,TRANSPOSE(H))) + R_m ! NJA: (H*T*H') \approx 0
K = MATMUL(P,TRANSPOSE(H))/S(1,1)
! xh = xh + K*(LocalVar%GenSpeedF/CntrPar%WE_GearboxRatio - xh(1,1))
xh = xh + K*(LocalVar%GenSpeedF/CntrPar%WE_GearboxRatio - om_r)
P = MATMUL(identity(3) - MATMUL(K,H),P)

! Wind Speed Estimate
! xh(1,1) = saturate(xh(1,1),0.0, CntrPar%PC_RefSpd * 1.5)
! xh(2,1) = saturate(xh(2,1),-10.0, 10.0)
! xh(3,1) = saturate(xh(3,1),0.0, MAXVAL(WE_EKF_Vref))
om_r = xh(1,1)
v_t = xh(2,1)
v_m = xh(3,1)
Expand Down Expand Up @@ -276,7 +272,7 @@ REAL FUNCTION PitchSaturation(LocalVar, CntrPar, objInst)

Vhat = LocalVar%WE_Vw
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
PitchSaturation = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, Vhatf)

Expand All @@ -301,7 +297,9 @@ REAL FUNCTION Shutdown(LocalVar, CntrPar, objInst)

! See if we should shutdown
IF (.NOT. LocalVar%SD ) THEN
! Filter pitch signal
SD_BlPitchF = LPFilter(LocalVar%PC_PitComT, LocalVar%DT, CntrPar%SD_CornerFreq, LocalVar%iStatus, .FALSE., objInst%instLPF)

! Go into shutdown if above max pit
IF (SD_BlPitchF > CntrPar%SD_MaxPit) THEN
LocalVar%SD = .TRUE.
Expand Down
24 changes: 13 additions & 11 deletions src/Controllers.f90
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
! YawRateControl: Nacelle yaw control
! IPC: Individual pitch control
! ForeAftDamping: Tower fore-aft damping control
! FloatingFeedback: Tower fore-aft feedback for floating offshore wind turbines

MODULE Controllers

Expand Down Expand Up @@ -111,9 +112,10 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst)

! Saturate collective pitch commands:
LocalVar%PC_PitComT = saturate(LocalVar%PC_PitComT, LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command using the pitch angle limits

! Combine and saturate all individual pitch commands:
DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate
LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%IPC_PitComF(K) + LocalVar%FA_PitCom(K) + LocalVar%PC_SineExcitation !+ LocalVar%Fl_PitCom
LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%IPC_PitComF(K) + LocalVar%FA_PitCom(K) + LocalVar%PC_SineExcitation
LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command using the 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
Expand Down Expand Up @@ -145,17 +147,17 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst)
REAL(4) :: VS_MaxTq ! Locally allocated maximum torque saturation limits

! -------- Variable-Speed Torque Controller --------
! Define max torque
IF (LocalVar%VS_State == 4) THEN
VS_MaxTq = CntrPar%VS_RtTq
ELSE
VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque
! VS_MaxTq = CntrPar%VS_RtTq
ENDIF

! Optimal Tip-Speed-Ratio tracking controller
IF (CntrPar%VS_ControlMode == 2) THEN
! Define max torque
IF (LocalVar%VS_State >= 4) THEN
VS_MaxTq = CntrPar%VS_RtTq
ELSE
! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque
VS_MaxTq = CntrPar%VS_RtTq
ENDIF

! TSR tracking vs control
! PI controller
LocalVar%GenTq = PIController(LocalVar%VS_SpdErr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, VS_MaxTq, LocalVar%DT, LocalVar%VS_LastGenTrq, .FALSE., objInst%instPI)
LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, VS_MaxTq)

Expand All @@ -166,6 +168,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst)
LocalVar%GenArTq = PIController(LocalVar%VS_SpdErrAr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MaxOMTq, CntrPar%VS_ArSatTq, LocalVar%DT, CntrPar%VS_MaxOMTq, .FALSE., objInst%instPI)
LocalVar%GenBrTq = PIController(LocalVar%VS_SpdErrBr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, CntrPar%VS_MinOMTq, LocalVar%DT, CntrPar%VS_MinOMTq, .FALSE., objInst%instPI)

! The action
IF (LocalVar%VS_State == 1) THEN ! Region 1.5
LocalVar%GenTq = LocalVar%GenBrTq
ELSEIF (LocalVar%VS_State == 2) THEN ! Region 2
Expand All @@ -180,7 +183,6 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst)

! Saturate
LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, VS_MaxTq)

ENDIF


Expand Down
2 changes: 1 addition & 1 deletion src/DISCON.F90
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
! specific language governing permissions and limitations under the License.
! -------------------------------------------------------------------------------------------

! Hih level run script
! High level run script

!=======================================================================
SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME='DISCON')
Expand Down
4 changes: 2 additions & 2 deletions src/Filters.f90
Original file line number Diff line number Diff line change
Expand Up @@ -226,8 +226,8 @@ REAL FUNCTION NotchFilter(InputSignal, DT, omega, betaNum, betaDen, iStatus, res

! Save signals for next time step
InputSignalLast2(inst) = InputSignalLast1(inst)
InputSignalLast1(inst) = InputSignal !Save input signal for next time step
OutputSignalLast2(inst) = OutputSignalLast1(inst) !Save input signal for next time step
InputSignalLast1(inst) = InputSignal ! Save input signal for next time step
OutputSignalLast2(inst) = OutputSignalLast1(inst) ! Save input signal for next time step
OutputSignalLast1(inst) = NotchFilter
inst = inst + 1

Expand Down
6 changes: 0 additions & 6 deletions src/Functions.f90
Original file line number Diff line number Diff line change
Expand Up @@ -414,16 +414,12 @@ 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(unit=UnDb, FILE=TRIM(RootName)//'.dbg', STATUS='NEW')
OPEN(unit=UnDb, FILE='DEBUG.dbg')
WRITE (UnDb,'(A)') ' Time ' //Tab//' WE_TowerTop ' //Tab//' WE_Vw ' //Tab//' NacIMU_FA_Acc ' //Tab//' FA_Acc ' //Tab//' Fl_Pitcom '
WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(m/s) ' //Tab//'(rad) ' //Tab//'(rad/s^2) ' //Tab//'(m/s^2) '//Tab//'(rad) '
!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(unit=UnDb2, FILE='DEBUG2.dbg')
WRITE(UnDb2,'(/////)')
WRITE(UnDb2,'(A,85("'//Tab//'AvrSWAP(",I2,")"))') 'LocalVar%Time ', (i,i=1,85)
Expand All @@ -434,8 +430,6 @@ SUBROUTINE Debug(LocalVar, CntrPar, avrSWAP, RootName, size_avcOUTNAME)
IF (MODULO(LocalVar%Time, 10.0) == 0) THEN
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:
Expand Down

0 comments on commit dcbb2bc

Please sign in to comment.