From 122c75864c1c0c1a828975180f46e77220771e60 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Wed, 11 Dec 2024 14:40:40 -0700 Subject: [PATCH 1/2] Check for prior initialization of ROSCO (#401) * Add mpi_tools to rosco * Check for prior initialization * Check if ROSCO has already been initialized * Add unit test for rosco initialization * Run example 4 * Only publish on macos-latest * Update install directory --- Examples/04_simple_sim.py | 3 + rosco/controller/CMakeLists.txt | 2 +- .../rosco_registry/rosco_types.yaml | 4 + .../rosco_registry/write_registry.py | 4 +- rosco/controller/src/DISCON.F90 | 6 +- rosco/controller/src/ROSCO_IO.f90 | 324 +++++++++--------- rosco/controller/src/ROSCO_Types.f90 | 3 +- rosco/controller/src/ReadSetParameters.f90 | 16 +- rosco/test/test_initialization.py | 34 ++ 9 files changed, 227 insertions(+), 169 deletions(-) create mode 100644 rosco/test/test_initialization.py diff --git a/Examples/04_simple_sim.py b/Examples/04_simple_sim.py index acd0848e..61d40cac 100644 --- a/Examples/04_simple_sim.py +++ b/Examples/04_simple_sim.py @@ -103,3 +103,6 @@ def main(): else: plt.savefig(os.path.join(example_out_dir,'04_NREL5MW_SimpSim.png')) +if __name__=='__main__': + main() + diff --git a/rosco/controller/CMakeLists.txt b/rosco/controller/CMakeLists.txt index 46705c25..2576d9dd 100644 --- a/rosco/controller/CMakeLists.txt +++ b/rosco/controller/CMakeLists.txt @@ -108,5 +108,5 @@ set(linuxDefault ${CMAKE_INSTALL_PREFIX} STREQUAL "/usr/local") set(windowsDefault ${CMAKE_INSTALL_PREFIX} STREQUAL "C:\\Program Files (x86)") if(${linuxDefault} OR ${windowsDefault}) message("TRUE") - set(CMAKE_INSTALL_PREFIX "${CMAKE_SOURCE_DIR}/../../") + set(CMAKE_INSTALL_PREFIX "${CMAKE_SOURCE_DIR}/../") endif() diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 6f888f81..dde52b60 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -924,6 +924,10 @@ LocalVariables: iStatus: <<: *integer description: Initialization status + AlreadyInitialized: + <<: *integer + description: Has ROSCO already been initialized (0-no, 1-yes) + equals: 0 Time: <<: *real description: Time [s] diff --git a/rosco/controller/rosco_registry/write_registry.py b/rosco/controller/rosco_registry/write_registry.py index 1c07fc98..acaf63cb 100644 --- a/rosco/controller/rosco_registry/write_registry.py +++ b/rosco/controller/rosco_registry/write_registry.py @@ -39,8 +39,8 @@ def write_types(yfile): for attype in reg[toptype].keys(): f90type = read_type(reg[toptype][attype]) atstr = check_size(reg[toptype], attype) - if reg[toptype][attype]['equals']: - atstr += ' = ' + reg[toptype][attype]['equals'] + if reg[toptype][attype]['equals'] is not None: + atstr += ' = ' + str(reg[toptype][attype]['equals']) file.write(' {:<25s} :: {:<25s} ! {}\n'.format(f90type, atstr, reg[toptype][attype]['description'])) file.write('END TYPE {}\n'.format(toptype)) file.write('\n') diff --git a/rosco/controller/src/DISCON.F90 b/rosco/controller/src/DISCON.F90 index 4787e19f..e95c1580 100644 --- a/rosco/controller/src/DISCON.F90 +++ b/rosco/controller/src/DISCON.F90 @@ -78,10 +78,12 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME END IF ! Read avrSWAP array into derived types/variables -CALL ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) +CALL ReadAvrSWAP(avrSWAP, LocalVar, CntrPar, ErrVar) ! Set Control Parameters -CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, RootName, ErrVar) +IF (ErrVar%aviFAIL >= 0) THEN + CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, RootName, ErrVar) +ENDIF ! Call external controller, if desired IF (CntrPar%Ext_Mode > 0 .AND. ErrVar%aviFAIL >= 0) THEN diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index c537f9b4..f041c7a7 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -1,5 +1,5 @@ ! ROSCO IO -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_IO @@ -37,6 +37,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a ELSE WRITE( Un, IOSTAT=ErrStat) LocalVar%iStatus + WRITE( Un, IOSTAT=ErrStat) LocalVar%AlreadyInitialized WRITE( Un, IOSTAT=ErrStat) LocalVar%Time WRITE( Un, IOSTAT=ErrStat) LocalVar%DT WRITE( Un, IOSTAT=ErrStat) LocalVar%WriteThisStep @@ -339,6 +340,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ELSE READ( Un, IOSTAT=ErrStat) LocalVar%iStatus + READ( Un, IOSTAT=ErrStat) LocalVar%AlreadyInitialized READ( Un, IOSTAT=ErrStat) LocalVar%Time READ( Un, IOSTAT=ErrStat) LocalVar%DT READ( Un, IOSTAT=ErrStat) LocalVar%WriteThisStep @@ -692,158 +694,160 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 124 + nLocalVars = 125 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus - LocalVarOutData(2) = LocalVar%Time - LocalVarOutData(3) = LocalVar%DT - LocalVarOutData(4) = LocalVar%n_DT - LocalVarOutData(5) = LocalVar%Time_Last - LocalVarOutData(6) = LocalVar%VS_GenPwr - LocalVarOutData(7) = LocalVar%VS_GenPwrF - LocalVarOutData(8) = LocalVar%GenSpeed - LocalVarOutData(9) = LocalVar%RotSpeed - LocalVarOutData(10) = LocalVar%NacHeading - LocalVarOutData(11) = LocalVar%NacVane - LocalVarOutData(12) = LocalVar%HorWindV - LocalVarOutData(13) = LocalVar%rootMOOP(1) - LocalVarOutData(14) = LocalVar%rootMOOPF(1) - LocalVarOutData(15) = LocalVar%BlPitch(1) - LocalVarOutData(16) = LocalVar%BlPitchCMeas - LocalVarOutData(17) = LocalVar%Azimuth - LocalVarOutData(18) = LocalVar%OL_Azimuth - LocalVarOutData(19) = LocalVar%AzUnwrapped - LocalVarOutData(20) = LocalVar%AzError - LocalVarOutData(21) = LocalVar%GenTqAz - LocalVarOutData(22) = LocalVar%AzBuffer(1) - LocalVarOutData(23) = LocalVar%NumBl - LocalVarOutData(24) = LocalVar%FA_Acc - LocalVarOutData(25) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(26) = LocalVar%FA_AccHPF - LocalVarOutData(27) = LocalVar%FA_AccHPFI - LocalVarOutData(28) = LocalVar%FA_PitCom(1) - LocalVarOutData(29) = LocalVar%VS_RefSpd - LocalVarOutData(30) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(31) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(32) = LocalVar%VS_RefSpd_RL - LocalVarOutData(33) = LocalVar%PC_RefSpd - LocalVarOutData(34) = LocalVar%PC_RefSpd_SS - LocalVarOutData(35) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(36) = LocalVar%RotSpeedF - LocalVarOutData(37) = LocalVar%GenSpeedF - LocalVarOutData(38) = LocalVar%GenTq - LocalVarOutData(39) = LocalVar%GenTqMeas - LocalVarOutData(40) = LocalVar%GenArTq - LocalVarOutData(41) = LocalVar%GenBrTq - LocalVarOutData(42) = LocalVar%IPC_PitComF(1) - LocalVarOutData(43) = LocalVar%PC_KP - LocalVarOutData(44) = LocalVar%PC_KI - LocalVarOutData(45) = LocalVar%PC_KD - LocalVarOutData(46) = LocalVar%PC_TF - LocalVarOutData(47) = LocalVar%PC_MaxPit - LocalVarOutData(48) = LocalVar%PC_MinPit - LocalVarOutData(49) = LocalVar%PC_PitComT - LocalVarOutData(50) = LocalVar%PC_PitComT_Last - LocalVarOutData(51) = LocalVar%PC_PitComTF - LocalVarOutData(52) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(53) = LocalVar%PC_PwrErr - LocalVarOutData(54) = LocalVar%PC_SpdErr - LocalVarOutData(55) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(56) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(57) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(58) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(59) = LocalVar%axisTilt_1P - LocalVarOutData(60) = LocalVar%axisYaw_1P - LocalVarOutData(61) = LocalVar%axisYawF_1P - LocalVarOutData(62) = LocalVar%axisTilt_2P - LocalVarOutData(63) = LocalVar%axisYaw_2P - LocalVarOutData(64) = LocalVar%axisYawF_2P - LocalVarOutData(65) = LocalVar%IPC_KI(1) - LocalVarOutData(66) = LocalVar%IPC_KP(1) - LocalVarOutData(67) = LocalVar%IPC_IntSat - LocalVarOutData(68) = LocalVar%PC_State - LocalVarOutData(69) = LocalVar%PitCom(1) - LocalVarOutData(70) = LocalVar%PitComAct(1) - LocalVarOutData(71) = LocalVar%SS_DelOmegaF - LocalVarOutData(72) = LocalVar%TestType - LocalVarOutData(73) = LocalVar%Kp_Float - LocalVarOutData(74) = LocalVar%VS_MaxTq - LocalVarOutData(75) = LocalVar%VS_LastGenTrq - LocalVarOutData(76) = LocalVar%VS_LastGenPwr - LocalVarOutData(77) = LocalVar%VS_MechGenPwr - LocalVarOutData(78) = LocalVar%VS_SpdErrAr - LocalVarOutData(79) = LocalVar%VS_SpdErrBr - LocalVarOutData(80) = LocalVar%VS_SpdErr - LocalVarOutData(81) = LocalVar%VS_State - LocalVarOutData(82) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(83) = LocalVar%WE_Vw - LocalVarOutData(84) = LocalVar%WE_Vw_F - LocalVarOutData(85) = LocalVar%WE_VwI - LocalVarOutData(86) = LocalVar%WE_VwIdot - LocalVarOutData(87) = LocalVar%VS_LastGenTrqF - LocalVarOutData(88) = LocalVar%PRC_WSE_F - LocalVarOutData(89) = LocalVar%Fl_PitCom - LocalVarOutData(90) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(91) = LocalVar%FA_AccF - LocalVarOutData(92) = LocalVar%FA_Hist - LocalVarOutData(93) = LocalVar%TRA_LastRefSpd - LocalVarOutData(94) = LocalVar%VS_RefSpeed - LocalVarOutData(95) = LocalVar%PtfmTDX - LocalVarOutData(96) = LocalVar%PtfmTDY - LocalVarOutData(97) = LocalVar%PtfmTDZ - LocalVarOutData(98) = LocalVar%PtfmRDX - LocalVarOutData(99) = LocalVar%PtfmRDY - LocalVarOutData(100) = LocalVar%PtfmRDZ - LocalVarOutData(101) = LocalVar%PtfmTVX - LocalVarOutData(102) = LocalVar%PtfmTVY - LocalVarOutData(103) = LocalVar%PtfmTVZ - LocalVarOutData(104) = LocalVar%PtfmRVX - LocalVarOutData(105) = LocalVar%PtfmRVY - LocalVarOutData(106) = LocalVar%PtfmRVZ - LocalVarOutData(107) = LocalVar%PtfmTAX - LocalVarOutData(108) = LocalVar%PtfmTAY - LocalVarOutData(109) = LocalVar%PtfmTAZ - LocalVarOutData(110) = LocalVar%PtfmRAX - LocalVarOutData(111) = LocalVar%PtfmRAY - LocalVarOutData(112) = LocalVar%PtfmRAZ - LocalVarOutData(113) = LocalVar%CC_DesiredL(1) - LocalVarOutData(114) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(115) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(116) = LocalVar%StC_Input(1) - LocalVarOutData(117) = LocalVar%Flp_Angle(1) - LocalVarOutData(118) = LocalVar%RootMyb_Last(1) - LocalVarOutData(119) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(120) = LocalVar%AWC_complexangle(1) - LocalVarOutData(121) = LocalVar%ZMQ_ID - LocalVarOutData(122) = LocalVar%ZMQ_YawOffset - LocalVarOutData(123) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(124) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & - 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & - 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & - 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', & - 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', & - 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', & - 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', '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', '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', 'PRC_WSE_F', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', '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', & - 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset'] + LocalVarOutData(2) = LocalVar%AlreadyInitialized + LocalVarOutData(3) = LocalVar%Time + LocalVarOutData(4) = LocalVar%DT + LocalVarOutData(5) = LocalVar%n_DT + LocalVarOutData(6) = LocalVar%Time_Last + LocalVarOutData(7) = LocalVar%VS_GenPwr + LocalVarOutData(8) = LocalVar%VS_GenPwrF + LocalVarOutData(9) = LocalVar%GenSpeed + LocalVarOutData(10) = LocalVar%RotSpeed + LocalVarOutData(11) = LocalVar%NacHeading + LocalVarOutData(12) = LocalVar%NacVane + LocalVarOutData(13) = LocalVar%HorWindV + LocalVarOutData(14) = LocalVar%rootMOOP(1) + LocalVarOutData(15) = LocalVar%rootMOOPF(1) + LocalVarOutData(16) = LocalVar%BlPitch(1) + LocalVarOutData(17) = LocalVar%BlPitchCMeas + LocalVarOutData(18) = LocalVar%Azimuth + LocalVarOutData(19) = LocalVar%OL_Azimuth + LocalVarOutData(20) = LocalVar%AzUnwrapped + LocalVarOutData(21) = LocalVar%AzError + LocalVarOutData(22) = LocalVar%GenTqAz + LocalVarOutData(23) = LocalVar%AzBuffer(1) + LocalVarOutData(24) = LocalVar%NumBl + LocalVarOutData(25) = LocalVar%FA_Acc + LocalVarOutData(26) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(27) = LocalVar%FA_AccHPF + LocalVarOutData(28) = LocalVar%FA_AccHPFI + LocalVarOutData(29) = LocalVar%FA_PitCom(1) + LocalVarOutData(30) = LocalVar%VS_RefSpd + LocalVarOutData(31) = LocalVar%VS_RefSpd_TSR + LocalVarOutData(32) = LocalVar%VS_RefSpd_TRA + LocalVarOutData(33) = LocalVar%VS_RefSpd_RL + LocalVarOutData(34) = LocalVar%PC_RefSpd + LocalVarOutData(35) = LocalVar%PC_RefSpd_SS + LocalVarOutData(36) = LocalVar%PC_RefSpd_PRC + LocalVarOutData(37) = LocalVar%RotSpeedF + LocalVarOutData(38) = LocalVar%GenSpeedF + LocalVarOutData(39) = LocalVar%GenTq + LocalVarOutData(40) = LocalVar%GenTqMeas + LocalVarOutData(41) = LocalVar%GenArTq + LocalVarOutData(42) = LocalVar%GenBrTq + LocalVarOutData(43) = LocalVar%IPC_PitComF(1) + LocalVarOutData(44) = LocalVar%PC_KP + LocalVarOutData(45) = LocalVar%PC_KI + LocalVarOutData(46) = LocalVar%PC_KD + LocalVarOutData(47) = LocalVar%PC_TF + LocalVarOutData(48) = LocalVar%PC_MaxPit + LocalVarOutData(49) = LocalVar%PC_MinPit + LocalVarOutData(50) = LocalVar%PC_PitComT + LocalVarOutData(51) = LocalVar%PC_PitComT_Last + LocalVarOutData(52) = LocalVar%PC_PitComTF + LocalVarOutData(53) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(54) = LocalVar%PC_PwrErr + LocalVarOutData(55) = LocalVar%PC_SpdErr + LocalVarOutData(56) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(57) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(58) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(59) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(60) = LocalVar%axisTilt_1P + LocalVarOutData(61) = LocalVar%axisYaw_1P + LocalVarOutData(62) = LocalVar%axisYawF_1P + LocalVarOutData(63) = LocalVar%axisTilt_2P + LocalVarOutData(64) = LocalVar%axisYaw_2P + LocalVarOutData(65) = LocalVar%axisYawF_2P + LocalVarOutData(66) = LocalVar%IPC_KI(1) + LocalVarOutData(67) = LocalVar%IPC_KP(1) + LocalVarOutData(68) = LocalVar%IPC_IntSat + LocalVarOutData(69) = LocalVar%PC_State + LocalVarOutData(70) = LocalVar%PitCom(1) + LocalVarOutData(71) = LocalVar%PitComAct(1) + LocalVarOutData(72) = LocalVar%SS_DelOmegaF + LocalVarOutData(73) = LocalVar%TestType + LocalVarOutData(74) = LocalVar%Kp_Float + LocalVarOutData(75) = LocalVar%VS_MaxTq + LocalVarOutData(76) = LocalVar%VS_LastGenTrq + LocalVarOutData(77) = LocalVar%VS_LastGenPwr + LocalVarOutData(78) = LocalVar%VS_MechGenPwr + LocalVarOutData(79) = LocalVar%VS_SpdErrAr + LocalVarOutData(80) = LocalVar%VS_SpdErrBr + LocalVarOutData(81) = LocalVar%VS_SpdErr + LocalVarOutData(82) = LocalVar%VS_State + LocalVarOutData(83) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(84) = LocalVar%WE_Vw + LocalVarOutData(85) = LocalVar%WE_Vw_F + LocalVarOutData(86) = LocalVar%WE_VwI + LocalVarOutData(87) = LocalVar%WE_VwIdot + LocalVarOutData(88) = LocalVar%VS_LastGenTrqF + LocalVarOutData(89) = LocalVar%PRC_WSE_F + LocalVarOutData(90) = LocalVar%Fl_PitCom + LocalVarOutData(91) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(92) = LocalVar%FA_AccF + LocalVarOutData(93) = LocalVar%FA_Hist + LocalVarOutData(94) = LocalVar%TRA_LastRefSpd + LocalVarOutData(95) = LocalVar%VS_RefSpeed + LocalVarOutData(96) = LocalVar%PtfmTDX + LocalVarOutData(97) = LocalVar%PtfmTDY + LocalVarOutData(98) = LocalVar%PtfmTDZ + LocalVarOutData(99) = LocalVar%PtfmRDX + LocalVarOutData(100) = LocalVar%PtfmRDY + LocalVarOutData(101) = LocalVar%PtfmRDZ + LocalVarOutData(102) = LocalVar%PtfmTVX + LocalVarOutData(103) = LocalVar%PtfmTVY + LocalVarOutData(104) = LocalVar%PtfmTVZ + LocalVarOutData(105) = LocalVar%PtfmRVX + LocalVarOutData(106) = LocalVar%PtfmRVY + LocalVarOutData(107) = LocalVar%PtfmRVZ + LocalVarOutData(108) = LocalVar%PtfmTAX + LocalVarOutData(109) = LocalVar%PtfmTAY + LocalVarOutData(110) = LocalVar%PtfmTAZ + LocalVarOutData(111) = LocalVar%PtfmRAX + LocalVarOutData(112) = LocalVar%PtfmRAY + LocalVarOutData(113) = LocalVar%PtfmRAZ + LocalVarOutData(114) = LocalVar%CC_DesiredL(1) + LocalVarOutData(115) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(116) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(117) = LocalVar%StC_Input(1) + LocalVarOutData(118) = LocalVar%Flp_Angle(1) + LocalVarOutData(119) = LocalVar%RootMyb_Last(1) + LocalVarOutData(120) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(121) = LocalVar%AWC_complexangle(1) + LocalVarOutData(122) = LocalVar%ZMQ_ID + LocalVarOutData(123) = LocalVar%ZMQ_YawOffset + LocalVarOutData(124) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(125) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'AlreadyInitialized', 'Time', 'DT', 'n_DT', & + 'Time_Last', 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', & + 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', & + 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', & + 'AzError', 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', & + 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', & + 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', & + 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', & + 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', & + 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', & + 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', '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', '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', 'PRC_WSE_F', 'Fl_PitCom', & + 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', & + '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', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset' & + ] ! 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 @@ -858,8 +862,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, '(125(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(125(a20,TR5:))') + WRITE(UnDb2, '(126(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(126(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -904,25 +908,25 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ! Process DebugOutData, LocalVarOutData ! Remove very small numbers that cause ******** outputs DO I = 1,SIZE(DebugOutData) - IF (ABS(DebugOutData(I)) < 1D-99) THEN + IF (ABS(DebugOutData(I)) < 1E-99) THEN DebugOutData(I) = 0 END IF - IF (ABS(DebugOutData(I)) > 1D+99) THEN - DebugOutData(I) = 1D+99 + IF (ABS(DebugOutData(I)) > 1E+99) THEN + DebugOutData(I) = 1E+99 END IF END DO DO I = 1,SIZE(LocalVarOutData) - IF (ABS(LocalVarOutData(I)) < 1D-99) THEN + IF (ABS(LocalVarOutData(I)) < 1E-99) THEN LocalVarOutData(I) = 0 END IF - IF (ABS(LocalVarOutData(I)) > 1D+99) THEN - LocalVarOutData(I) = 1D+99 + IF (ABS(LocalVarOutData(I)) > 1E+99) THEN + LocalVarOutData(I) = 1E+99 END IF END DO ! Write debug files - FmtDat = "(F20.5,TR5,124(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,125(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, TRIM(FmtDat)) LocalVar%Time, DebugOutData @@ -945,4 +949,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO +END MODULE ROSCO_IO \ No newline at end of file diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 64385192..5e84cbc7 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -1,5 +1,5 @@ ! ROSCO Registry -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_Types @@ -248,6 +248,7 @@ MODULE ROSCO_Types TYPE, PUBLIC :: LocalVariables INTEGER(IntKi) :: iStatus ! Initialization status + INTEGER(IntKi) :: AlreadyInitialized = 0 ! Has ROSCO already been initialized (0-no, 1-yes) REAL(DbKi) :: Time ! Time [s] REAL(DbKi) :: DT ! Time step [s] LOGICAL :: WriteThisStep ! Write an output line this time step diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 131b6581..e48e375e 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -25,12 +25,13 @@ MODULE ReadSetParameters CONTAINS ! ----------------------------------------------------------------------------------- ! Read avrSWAP array passed from ServoDyn - SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) + SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar, ErrVar) USE ROSCO_Types, ONLY : LocalVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ControlParameters), INTENT(IN) :: CntrPar + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Allocate Variables: INTEGER(IntKi) :: K ! Index used for looping through blades. @@ -79,9 +80,18 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ENDIF - ! GenTemp = avrSWAP(1026) - ! WRITE(1000,*) LocalVar%GenSpeed*RPS2RPM, GenTemp + ! Check that we haven't already loaded this dynamic library + IF (LocalVar%iStatus == 0) THEN + IF (LocalVar%AlreadyInitialized == 0) THEN + LocalVar%AlreadyInitialized = 1 + ELSE + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'ERROR: This ROSCO dynamic library has already been loaded.' + RETURN + ENDIF + ENDIF + diff --git a/rosco/test/test_initialization.py b/rosco/test/test_initialization.py new file mode 100644 index 00000000..7f695604 --- /dev/null +++ b/rosco/test/test_initialization.py @@ -0,0 +1,34 @@ +''' +Unit testing for ROSCO + +Tests: + initialization +''' + +import os +import unittest + + +# ROSCO toolbox modules +from rosco import discon_lib_path +from rosco.toolbox import control_interface as ROSCO_ci + + +class UnitTesting(unittest.TestCase): + def test_initialization(self): + + this_dir = os.path.dirname(os.path.abspath(__file__)) + param_filename = os.path.join(this_dir,'../../Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN') + + + # Load controller library + ci_1 = ROSCO_ci.ControllerInterface(discon_lib_path,param_filename=param_filename,sim_name='sim1') + + ci_2 = ROSCO_ci.ControllerInterface(discon_lib_path,param_filename=param_filename,sim_name='sim2') + + # Check that the error is as expected + assert("b'ROSCO:ERROR: This ROSCO dynamic library has already been loaded" == str(ci_2.avcMSG.raw).split('.')[0]) + + +if __name__ == "__main__": + unittest.main() From 5fd09f75cea1528b880ee99df3c7b8105522ae42 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Wed, 11 Dec 2024 14:41:11 -0700 Subject: [PATCH 2/2] Sync controller/OL attributes with input names (#390) * Sync controller/OL attributes with input names * Align open loop attributes and variables to DISCON name * Add mpi_tools to rosco --- rosco/toolbox/controller.py | 178 +++++++++++++---------- rosco/toolbox/inputs/toolbox_schema.yaml | 6 +- rosco/toolbox/utilities.py | 22 +-- 3 files changed, 115 insertions(+), 91 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 1fdec790..9b8febd7 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -67,6 +67,7 @@ def __init__(self, controller_params): self.Flp_Mode = controller_params['Flp_Mode'] self.PA_Mode = controller_params['PA_Mode'] self.PF_Mode = controller_params['PF_Mode'] + self.PRC_Mode = controller_params['PRC_Mode'] self.AWC_Mode = controller_params['AWC_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] @@ -145,26 +146,49 @@ def __init__(self, controller_params): # Open loop parameters: set up and error catching self.OL_Mode = controller_params['OL_Mode'] self.OL_Filename = controller_params['open_loop']['filename'] - self.OL_Ind_Breakpoint = self.OL_Ind_GenTq = self.OL_Ind_YawRate = self.OL_Ind_Azimuth = 0 - self.OL_Ind_R_Speed = self.OL_Ind_R_Torque = self.OL_Ind_R_Pitch = 0 - self.OL_Ind_BldPitch = [0,0,0] - self.OL_Ind_CableControl = [0] - self.OL_Ind_StructControl = [0] + self.Ind_Breakpoint = self.Ind_GenTq = self.Ind_YawRate = self.Ind_Azimuth = 0 + self.Ind_R_Speed = self.Ind_R_Torque = self.Ind_R_Pitch = 0 + self.Ind_BldPitch = [0,0,0] + self.Ind_CableControl = [0] + self.Ind_StructControl = [0] self.OL_BP_Mode = 0 if self.OL_Mode: ol_params = controller_params['open_loop'] + + # Apply DISCON inputs if they exist + if 'OL_Filename' in controller_params['DISCON']: + ol_params['filename'] = controller_params['DISCON']['OL_Filename'] + + available_ol_params = [ + 'OL_BP_Mode', + 'Ind_Breakpoint', + 'Ind_BldPitch', + 'Ind_GenTq', + 'Ind_YawRate', + 'Ind_Azimuth', + 'Ind_R_Speed', + 'Ind_R_Torque', + 'Ind_R_Pitch', + 'Ind_CableControl', + 'Ind_StructControl' + ] + for param in available_ol_params: + if param in controller_params['DISCON']: + ol_params[param] = controller_params['DISCON'][param] + + self.OL_BP_Mode = ol_params['OL_BP_Mode'] - self.OL_Ind_Breakpoint = ol_params['OL_Ind_Breakpoint'] - self.OL_Ind_BldPitch = ol_params['OL_Ind_BldPitch'] - self.OL_Ind_GenTq = ol_params['OL_Ind_GenTq'] - self.OL_Ind_YawRate = ol_params['OL_Ind_YawRate'] - self.OL_Ind_Azimuth = ol_params['OL_Ind_Azimuth'] - self.OL_Ind_R_Speed = ol_params['OL_Ind_R_Speed'] - self.OL_Ind_R_Torque = ol_params['OL_Ind_R_Torque'] - self.OL_Ind_R_Pitch = ol_params['OL_Ind_R_Pitch'] - self.OL_Ind_CableControl = ol_params['OL_Ind_CableControl'] - self.OL_Ind_StructControl = ol_params['OL_Ind_StructControl'] + self.Ind_Breakpoint = ol_params['Ind_Breakpoint'] + self.Ind_BldPitch = ol_params['Ind_BldPitch'] + self.Ind_GenTq = ol_params['Ind_GenTq'] + self.Ind_YawRate = ol_params['Ind_YawRate'] + self.Ind_Azimuth = ol_params['Ind_Azimuth'] + self.Ind_R_Speed = ol_params['Ind_R_Speed'] + self.Ind_R_Torque = ol_params['Ind_R_Torque'] + self.Ind_R_Pitch = ol_params['Ind_R_Pitch'] + self.Ind_CableControl = ol_params['Ind_CableControl'] + self.Ind_StructControl = ol_params['Ind_StructControl'] # Check that file exists because we won't write it if not os.path.exists(controller_params['open_loop']['filename']): @@ -879,11 +903,11 @@ def write_input(self,ol_filename): ol_series = self.ol_series # Init indices - OL_Ind_Breakpoint = 1 - OL_Ind_Azimuth = OL_Ind_GenTq = OL_Ind_YawRate = OL_Ind_R_Speed = OL_Ind_R_Torque = OL_Ind_R_Pitch = 0 - OL_Ind_BldPitch = 3*[0] - OL_Ind_CableControl = [] - OL_Ind_StructControl = [] + Ind_Breakpoint = 1 + Ind_Azimuth = Ind_GenTq = Ind_YawRate = Ind_R_Speed = Ind_R_Torque = Ind_R_Pitch = 0 + Ind_BldPitch = 3*[0] + Ind_CableControl = [] + Ind_StructControl = [] ol_index_counter = 0 # start input index at 2 @@ -908,34 +932,34 @@ def write_input(self,ol_filename): # Set open loop index based on name if channel == 'time': - OL_Ind_Breakpoint = ol_index_counter + Ind_Breakpoint = ol_index_counter skip_write = True elif channel == 'wind_speed': - OL_Ind_Breakpoint = ol_index_counter + Ind_Breakpoint = ol_index_counter skip_write = True elif channel == 'blade_pitch': # collective blade pitch - OL_Ind_BldPitch = 3 * [ol_index_counter] + Ind_BldPitch = 3 * [ol_index_counter] elif channel == 'generator_torque': - OL_Ind_GenTq = ol_index_counter + Ind_GenTq = ol_index_counter elif channel == 'nacelle_yaw_rate': - OL_Ind_YawRate = ol_index_counter + Ind_YawRate = ol_index_counter elif channel == 'nacelle_yaw': ol_index_counter -= 1 # don't increment counter skip_write = True elif channel == 'blade_pitch1': - OL_Ind_BldPitch[0] = ol_index_counter + Ind_BldPitch[0] = ol_index_counter elif channel == 'blade_pitch2': - OL_Ind_BldPitch[1] = ol_index_counter + Ind_BldPitch[1] = ol_index_counter elif channel == 'blade_pitch3': - OL_Ind_BldPitch[2] = ol_index_counter + Ind_BldPitch[2] = ol_index_counter elif channel == 'azimuth': - OL_Ind_Azimuth = ol_index_counter + Ind_Azimuth = ol_index_counter elif channel == 'R_speed': - OL_Ind_R_Speed = ol_index_counter + Ind_R_Speed = ol_index_counter elif channel == 'R_torque': - OL_Ind_R_Torque = ol_index_counter + Ind_R_Torque = ol_index_counter elif channel == 'R_pitch': - OL_Ind_R_Pitch = ol_index_counter + Ind_R_Pitch = ol_index_counter elif 'cable_control' in channel or 'struct_control' in channel: skip_write = True ol_index_counter -= 1 # don't increment counter @@ -958,7 +982,7 @@ def write_input(self,ol_filename): # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown for cable_chan in cable_chan_names: ol_input_matrix = np.c_[ol_input_matrix,ol_series[cable_chan]] - OL_Ind_CableControl.append(ol_index_counter) + Ind_CableControl.append(ol_index_counter) ol_index_counter += 1 # Struct control @@ -970,7 +994,7 @@ def write_input(self,ol_filename): # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown for i_chan in range(1,n_struct_chan+1): ol_input_matrix = np.c_[ol_input_matrix,ol_series[f'struct_control_{i_chan}']] - OL_Ind_StructControl.append(ol_index_counter) + Ind_StructControl.append(ol_index_counter) ol_index_counter += 1 @@ -997,55 +1021,55 @@ def write_input(self,ol_filename): units[0] = 'm/s' - if OL_Ind_GenTq: - headers[OL_Ind_GenTq-1] = 'GenTq' - units[OL_Ind_GenTq-1] = '(Nm)' + if Ind_GenTq: + headers[Ind_GenTq-1] = 'GenTq' + units[Ind_GenTq-1] = '(Nm)' - if OL_Ind_YawRate: - headers[OL_Ind_YawRate-1] = 'YawRate' - units[OL_Ind_YawRate-1] = '(rad/s)' + if Ind_YawRate: + headers[Ind_YawRate-1] = 'YawRate' + units[Ind_YawRate-1] = '(rad/s)' - if OL_Ind_Azimuth: - headers[OL_Ind_Azimuth-1] = 'Azimuth' - units[OL_Ind_Azimuth-1] = '(rad)' + if Ind_Azimuth: + headers[Ind_Azimuth-1] = 'Azimuth' + units[Ind_Azimuth-1] = '(rad)' - if any(OL_Ind_BldPitch): - if all_same(OL_Ind_BldPitch): - headers[OL_Ind_BldPitch[0]-1] = 'BldPitch123' - units[OL_Ind_BldPitch[0]-1] = '(rad)' + if any(Ind_BldPitch): + if all_same(Ind_BldPitch): + headers[Ind_BldPitch[0]-1] = 'BldPitch123' + units[Ind_BldPitch[0]-1] = '(rad)' else: - headers[OL_Ind_BldPitch[0]-1] = 'BldPitch1' - units[OL_Ind_BldPitch[0]-1] = '(rad)' - headers[OL_Ind_BldPitch[1]-1] = 'BldPitch2' - units[OL_Ind_BldPitch[1]-1] = '(rad)' - headers[OL_Ind_BldPitch[2]-1] = 'BldPitch3' - units[OL_Ind_BldPitch[2]-1] = '(rad)' - - if OL_Ind_CableControl: + headers[Ind_BldPitch[0]-1] = 'BldPitch1' + units[Ind_BldPitch[0]-1] = '(rad)' + headers[Ind_BldPitch[1]-1] = 'BldPitch2' + units[Ind_BldPitch[1]-1] = '(rad)' + headers[Ind_BldPitch[2]-1] = 'BldPitch3' + units[Ind_BldPitch[2]-1] = '(rad)' + + if Ind_CableControl: for i_chan in range(1,n_cable_chan+1): header_line += f'\t\tCable{i_chan}' unit_line += '\t\t(m)' else: - OL_Ind_CableControl = [0] + Ind_CableControl = [0] - if OL_Ind_StructControl: + if Ind_StructControl: for i_chan in range(1,n_struct_chan+1): header_line += f'\t\tStruct{i_chan}' unit_line += '\t\t(m)' else: - OL_Ind_StructControl = [0] + Ind_StructControl = [0] - if OL_Ind_R_Speed: - headers[OL_Ind_R_Speed-1] = 'R_speed' - units[OL_Ind_R_Speed-1] = '(-)' + if Ind_R_Speed: + headers[Ind_R_Speed-1] = 'R_speed' + units[Ind_R_Speed-1] = '(-)' - if OL_Ind_R_Torque: - headers[OL_Ind_R_Torque-1] = 'R_Torque' - units[OL_Ind_R_Torque-1] = '(-)' + if Ind_R_Torque: + headers[Ind_R_Torque-1] = 'R_Torque' + units[Ind_R_Torque-1] = '(-)' - if OL_Ind_R_Pitch: - headers[OL_Ind_R_Pitch-1] = 'R_Pitch' - units[OL_Ind_R_Pitch-1] = '(-)' + if Ind_R_Pitch: + headers[Ind_R_Pitch-1] = 'R_Pitch' + units[Ind_R_Pitch-1] = '(-)' # Join headers and units header_line = '!' + '\t\t'.join(headers) + '\n' @@ -1062,16 +1086,16 @@ def write_input(self,ol_filename): # Output open_loop dict for control params open_loop = {} open_loop['filename'] = ol_filename - open_loop['OL_Ind_Breakpoint'] = OL_Ind_Breakpoint - open_loop['OL_Ind_BldPitch'] = OL_Ind_BldPitch - open_loop['OL_Ind_GenTq'] = OL_Ind_GenTq - open_loop['OL_Ind_YawRate'] = OL_Ind_YawRate - open_loop['OL_Ind_Azimuth'] = OL_Ind_Azimuth - open_loop['OL_Ind_CableControl'] = OL_Ind_CableControl - open_loop['OL_Ind_StructControl'] = OL_Ind_StructControl - open_loop['OL_Ind_R_Speed'] = OL_Ind_R_Speed - open_loop['OL_Ind_R_Torque'] = OL_Ind_R_Torque - open_loop['OL_Ind_R_Pitch'] = OL_Ind_R_Pitch + open_loop['Ind_Breakpoint'] = Ind_Breakpoint + open_loop['Ind_BldPitch'] = Ind_BldPitch + open_loop['Ind_GenTq'] = Ind_GenTq + open_loop['Ind_YawRate'] = Ind_YawRate + open_loop['Ind_Azimuth'] = Ind_Azimuth + open_loop['Ind_CableControl'] = Ind_CableControl + open_loop['Ind_StructControl'] = Ind_StructControl + open_loop['Ind_R_Speed'] = Ind_R_Speed + open_loop['Ind_R_Torque'] = Ind_R_Torque + open_loop['Ind_R_Pitch'] = Ind_R_Pitch if self.breakpoint == 'time': open_loop['OL_BP_Mode'] = 0 elif self.breakpoint == 'wind_speed': diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 3131f8bf..414371f0 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -197,7 +197,7 @@ properties: maximum: 2 default: 0 description: Flap control mode (0- no flap control, 1- steady state flap angle, 2- Proportional flap control) - PwC_Mode: + PRC_Mode: type: number minimum: 0 maximum: 2 @@ -544,13 +544,13 @@ properties: items: type: number description: The column in OL_Filename that contains the cable control inputs in m - # default: [0] # No default because it's defined in controller and DISCON_Dict + default: [0] Ind_StructControl: type: array items: type: number description: The column in OL_Filename that contains the structural control inputs in various units - # default: [0] # No default because it's defined in controller and DISCON_Dict + default: [0] PA_CornerFreq: type: number description: Pitch actuator natural frequency [rad/s] diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 30224f49..8aef0200 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -488,7 +488,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PC_ControlMode'] = int(controller.PC_ControlMode) DISCON_dict['Y_ControlMode'] = int(controller.Y_ControlMode) DISCON_dict['SS_Mode'] = int(controller.SS_Mode) - DISCON_dict['PRC_Mode'] = 0 + DISCON_dict['PRC_Mode'] = int(controller.PRC_Mode) DISCON_dict['WE_Mode'] = int(controller.WE_Mode) DISCON_dict['PS_Mode'] = int(controller.PS_Mode > 0) DISCON_dict['SD_Mode'] = int(controller.SD_Mode) @@ -616,16 +616,16 @@ def DISCON_dict(turbine, controller, txt_filename=None): # ------- Open Loop Control ------- DISCON_dict['OL_Filename'] = controller.OL_Filename DISCON_dict['OL_BP_Mode'] = controller.OL_BP_Mode - DISCON_dict['Ind_Breakpoint'] = controller.OL_Ind_Breakpoint - DISCON_dict['Ind_BldPitch'] = controller.OL_Ind_BldPitch - DISCON_dict['Ind_GenTq'] = controller.OL_Ind_GenTq - DISCON_dict['Ind_YawRate'] = controller.OL_Ind_YawRate - DISCON_dict['Ind_CableControl'] = controller.OL_Ind_CableControl - DISCON_dict['Ind_StructControl'] = controller.OL_Ind_StructControl - DISCON_dict['Ind_Azimuth'] = controller.OL_Ind_Azimuth - DISCON_dict['Ind_R_Speed'] = controller.OL_Ind_R_Speed - DISCON_dict['Ind_R_Torque'] = controller.OL_Ind_R_Torque - DISCON_dict['Ind_R_Pitch'] = controller.OL_Ind_R_Pitch + DISCON_dict['Ind_Breakpoint'] = controller.Ind_Breakpoint + DISCON_dict['Ind_BldPitch'] = controller.Ind_BldPitch + DISCON_dict['Ind_GenTq'] = controller.Ind_GenTq + DISCON_dict['Ind_YawRate'] = controller.Ind_YawRate + DISCON_dict['Ind_CableControl'] = controller.Ind_CableControl + DISCON_dict['Ind_StructControl'] = controller.Ind_StructControl + DISCON_dict['Ind_Azimuth'] = controller.Ind_Azimuth + DISCON_dict['Ind_R_Speed'] = controller.Ind_R_Speed + DISCON_dict['Ind_R_Torque'] = controller.Ind_R_Torque + DISCON_dict['Ind_R_Pitch'] = controller.Ind_R_Pitch # ------- Pitch Actuator ------- DISCON_dict['PA_Mode'] = controller.PA_Mode