Skip to content

Commit

Permalink
Regen registry files, discons
Browse files Browse the repository at this point in the history
  • Loading branch information
dzalkind committed Jul 24, 2023
1 parent 2f551d1 commit 486f97b
Show file tree
Hide file tree
Showing 7 changed files with 93 additions and 80 deletions.
1 change: 1 addition & 0 deletions Examples/22_cable_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,7 @@ def main():
r.controller_params = controller_params
r.save_dir = run_dir
r.rosco_dir = rosco_dir
r.openfast_exe = '/Users/dzalkind/opt/anaconda3/envs/rosco-env2/bin/openfast'

r.run_FAST()

Expand Down
117 changes: 60 additions & 57 deletions ROSCO/src/ROSCO_IO.f90
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a
WRITE( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3)
WRITE( Un, IOSTAT=ErrStat) LocalVar%SS_DelOmegaF
WRITE( Un, IOSTAT=ErrStat) LocalVar%TestType
WRITE( Un, IOSTAT=ErrStat) LocalVar%Kp_Float
WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_MaxTq
WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrq
WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenPwr
Expand Down Expand Up @@ -398,6 +399,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa
READ( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3)
READ( Un, IOSTAT=ErrStat) LocalVar%SS_DelOmegaF
READ( Un, IOSTAT=ErrStat) LocalVar%TestType
READ( Un, IOSTAT=ErrStat) LocalVar%Kp_Float
READ( Un, IOSTAT=ErrStat) LocalVar%VS_MaxTq
READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrq
READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenPwr
Expand Down Expand Up @@ -641,7 +643,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av
'[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', &
'[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', &
'[deg]', '[deg]', '[deg]', '[N/A]']
nLocalVars = 107
nLocalVars = 108
Allocate(LocalVarOutData(nLocalVars))
Allocate(LocalVarOutStrings(nLocalVars))
LocalVarOutData(1) = LocalVar%iStatus
Expand Down Expand Up @@ -708,49 +710,50 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av
LocalVarOutData(62) = LocalVar%PitComAct(1)
LocalVarOutData(63) = LocalVar%SS_DelOmegaF
LocalVarOutData(64) = LocalVar%TestType
LocalVarOutData(65) = LocalVar%VS_MaxTq
LocalVarOutData(66) = LocalVar%VS_LastGenTrq
LocalVarOutData(67) = LocalVar%VS_LastGenPwr
LocalVarOutData(68) = LocalVar%VS_MechGenPwr
LocalVarOutData(69) = LocalVar%VS_SpdErrAr
LocalVarOutData(70) = LocalVar%VS_SpdErrBr
LocalVarOutData(71) = LocalVar%VS_SpdErr
LocalVarOutData(72) = LocalVar%VS_State
LocalVarOutData(73) = LocalVar%VS_Rgn3Pitch
LocalVarOutData(74) = LocalVar%WE_Vw
LocalVarOutData(75) = LocalVar%WE_Vw_F
LocalVarOutData(76) = LocalVar%WE_VwI
LocalVarOutData(77) = LocalVar%WE_VwIdot
LocalVarOutData(78) = LocalVar%VS_LastGenTrqF
LocalVarOutData(79) = LocalVar%Fl_PitCom
LocalVarOutData(80) = LocalVar%NACIMU_FA_AccF
LocalVarOutData(81) = LocalVar%FA_AccF
LocalVarOutData(82) = LocalVar%PtfmTDX
LocalVarOutData(83) = LocalVar%PtfmTDY
LocalVarOutData(84) = LocalVar%PtfmTDZ
LocalVarOutData(85) = LocalVar%PtfmRDX
LocalVarOutData(86) = LocalVar%PtfmRDY
LocalVarOutData(87) = LocalVar%PtfmRDZ
LocalVarOutData(88) = LocalVar%PtfmTVX
LocalVarOutData(89) = LocalVar%PtfmTVY
LocalVarOutData(90) = LocalVar%PtfmTVZ
LocalVarOutData(91) = LocalVar%PtfmRVX
LocalVarOutData(92) = LocalVar%PtfmRVY
LocalVarOutData(93) = LocalVar%PtfmRVZ
LocalVarOutData(94) = LocalVar%PtfmTAX
LocalVarOutData(95) = LocalVar%PtfmTAY
LocalVarOutData(96) = LocalVar%PtfmTAZ
LocalVarOutData(97) = LocalVar%PtfmRAX
LocalVarOutData(98) = LocalVar%PtfmRAY
LocalVarOutData(99) = LocalVar%PtfmRAZ
LocalVarOutData(100) = LocalVar%CC_DesiredL(1)
LocalVarOutData(101) = LocalVar%CC_ActuatedL(1)
LocalVarOutData(102) = LocalVar%CC_ActuatedDL(1)
LocalVarOutData(103) = LocalVar%StC_Input(1)
LocalVarOutData(104) = LocalVar%Flp_Angle(1)
LocalVarOutData(105) = LocalVar%RootMyb_Last(1)
LocalVarOutData(106) = LocalVar%ACC_INFILE_SIZE
LocalVarOutData(107) = LocalVar%AWC_complexangle(1)
LocalVarOutData(65) = LocalVar%Kp_Float
LocalVarOutData(66) = LocalVar%VS_MaxTq
LocalVarOutData(67) = LocalVar%VS_LastGenTrq
LocalVarOutData(68) = LocalVar%VS_LastGenPwr
LocalVarOutData(69) = LocalVar%VS_MechGenPwr
LocalVarOutData(70) = LocalVar%VS_SpdErrAr
LocalVarOutData(71) = LocalVar%VS_SpdErrBr
LocalVarOutData(72) = LocalVar%VS_SpdErr
LocalVarOutData(73) = LocalVar%VS_State
LocalVarOutData(74) = LocalVar%VS_Rgn3Pitch
LocalVarOutData(75) = LocalVar%WE_Vw
LocalVarOutData(76) = LocalVar%WE_Vw_F
LocalVarOutData(77) = LocalVar%WE_VwI
LocalVarOutData(78) = LocalVar%WE_VwIdot
LocalVarOutData(79) = LocalVar%VS_LastGenTrqF
LocalVarOutData(80) = LocalVar%Fl_PitCom
LocalVarOutData(81) = LocalVar%NACIMU_FA_AccF
LocalVarOutData(82) = LocalVar%FA_AccF
LocalVarOutData(83) = LocalVar%PtfmTDX
LocalVarOutData(84) = LocalVar%PtfmTDY
LocalVarOutData(85) = LocalVar%PtfmTDZ
LocalVarOutData(86) = LocalVar%PtfmRDX
LocalVarOutData(87) = LocalVar%PtfmRDY
LocalVarOutData(88) = LocalVar%PtfmRDZ
LocalVarOutData(89) = LocalVar%PtfmTVX
LocalVarOutData(90) = LocalVar%PtfmTVY
LocalVarOutData(91) = LocalVar%PtfmTVZ
LocalVarOutData(92) = LocalVar%PtfmRVX
LocalVarOutData(93) = LocalVar%PtfmRVY
LocalVarOutData(94) = LocalVar%PtfmRVZ
LocalVarOutData(95) = LocalVar%PtfmTAX
LocalVarOutData(96) = LocalVar%PtfmTAY
LocalVarOutData(97) = LocalVar%PtfmTAZ
LocalVarOutData(98) = LocalVar%PtfmRAX
LocalVarOutData(99) = LocalVar%PtfmRAY
LocalVarOutData(100) = LocalVar%PtfmRAZ
LocalVarOutData(101) = LocalVar%CC_DesiredL(1)
LocalVarOutData(102) = LocalVar%CC_ActuatedL(1)
LocalVarOutData(103) = LocalVar%CC_ActuatedDL(1)
LocalVarOutData(104) = LocalVar%StC_Input(1)
LocalVarOutData(105) = LocalVar%Flp_Angle(1)
LocalVarOutData(106) = LocalVar%RootMyb_Last(1)
LocalVarOutData(107) = LocalVar%ACC_INFILE_SIZE
LocalVarOutData(108) = LocalVar%AWC_complexangle(1)
LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', &
'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', 'NacVane', &
'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', &
Expand All @@ -763,16 +766,16 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av
'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', &
'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', &
'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', &
'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', &
'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', &
'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', &
'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', &
'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', &
'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', &
'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', &
'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', &
'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', &
'ACC_INFILE_SIZE', 'AWC_complexangle']
'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', &
'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', &
'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', &
'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', &
'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', &
'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', &
'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', &
'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', &
'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', &
'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle']
! Initialize debug file
IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL
IF (CntrPar%LoggingLevel > 0) THEN
Expand All @@ -787,8 +790,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av
CALL GetNewUnit(UnDb2, ErrVar)
OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2')
WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version)
WRITE(UnDb2, '(108(a20,TR5:))') 'Time', LocalVarOutStrings
WRITE(UnDb2, '(108(a20,TR5:))')
WRITE(UnDb2, '(109(a20,TR5:))') 'Time', LocalVarOutStrings
WRITE(UnDb2, '(109(a20,TR5:))')
END IF

IF (CntrPar%LoggingLevel > 2) THEN
Expand Down Expand Up @@ -845,7 +848,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av
END DO

! Write debug files
FmtDat = "(F20.5,TR5,107(ES20.5E2,TR5:))" ! The format of the debugging data
FmtDat = "(F20.5,TR5,108(ES20.5E2,TR5:))" ! The format of the debugging data
IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN
IF(CntrPar%LoggingLevel > 0) THEN
WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData
Expand Down
6 changes: 3 additions & 3 deletions ROSCO/src/ROSCO_Types.f90
Original file line number Diff line number Diff line change
Expand Up @@ -128,19 +128,19 @@ MODULE ROSCO_Types
INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter}
REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s]
REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1]
INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method]
INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method]
INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-]
INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-]
INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC AWC Coleman transform harmonic [-]
REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz]
REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg]
REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg]
INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades}
REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s]
INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library)
CHARACTER(1024) :: DLL_FileName ! File name of external dynamic library
CHARACTER(1024) :: DLL_InFile ! Name of input file called by dynamic library (DISCON.IN, e.g.)
CHARACTER(1024) :: DLL_ProcName ! Process name of subprocess called in DLL_Filename (Usually DISCON)
INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades}
REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s]
INTEGER(IntKi) :: ZMQ_Mode ! Flag for ZeroMQ (0-off, 1-yaw}
CHARACTER(256) :: ZMQ_CommAddress ! Comm Address to zeroMQ client
REAL(DbKi) :: ZMQ_UpdatePeriod ! Integer for zeromq update frequency
Expand Down
4 changes: 2 additions & 2 deletions Test_Cases/BAR_10/BAR_10_DISCON.IN
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
! Controller parameter input file for the BAR_10 wind turbine
! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23
! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23

!------- SIMULATION CONTROL ------------------------------------------------------------
1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)}
Expand Down Expand Up @@ -93,7 +93,7 @@
96.8 ! WE_GearboxRatio - Gearbox ratio [>=1], [-]
311169343.31448 ! 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]
"Cp_Ct_Cq.BAR_10.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file)
"../Test_Cases/BAR_10/Cp_Ct_Cq.BAR_10.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file)
36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios
60 ! WE_FOPoles_N - Number of first-order system poles used in EKF
3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s]
Expand Down
15 changes: 9 additions & 6 deletions Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine
! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23
! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23

!------- DEBUG ------------------------------------------------------------
2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3))
!------- SIMULATION CONTROL ------------------------------------------------------------
2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)}
0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST}
0 ! Echo - (0 - no Echo, 1 - Echo input data to <RootName>.echo)

!------- CONTROLLER FLAGS -------------------------------------------------
Expand Down Expand Up @@ -92,7 +93,7 @@
1.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-]
318628138.00000 ! 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]
"Cp_Ct_Cq.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file)
"../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file)
36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios
60 ! WE_FOPoles_N - Number of first-order system poles used in EKF
3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s]
Expand Down Expand Up @@ -135,9 +136,11 @@
!------- Open Loop Control -----------------------------------------------------
"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file)
0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1)
0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad
0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array]
0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm
0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s
0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm
0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2)
0.0000 0.0000 0.0000 ! RP_Gains - PID gains for rotor position control (used if OL_Mode = 2)
0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]
0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]

Expand Down
Loading

0 comments on commit 486f97b

Please sign in to comment.