From ca63d615f1e46b1117b8e9ae68943f9830e4e320 Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Mon, 18 Nov 2019 17:33:55 -0700 Subject: [PATCH 1/7] Rename to pitch saturation --- src/ControllerBlocks.f90 | 10 +++++----- src/Controllers.f90 | 2 +- src/ROSCO_Types.f90 | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index abe95bd4..ea666ef8 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -269,10 +269,10 @@ SUBROUTINE SetpointSmoother(LocalVar, CntrPar, objInst) END SUBROUTINE SetpointSmoother !------------------------------------------------------------------------------------------------------------------------------- - REAL FUNCTION PeakShaving(LocalVar, CntrPar, objInst) - ! PeakShaving defines a minimum blade pitch angle based on a lookup table provided by DISON.IN + REAL FUNCTION PitchSaturation(LocalVar, CntrPar, objInst) + ! PitchSaturation defines a minimum blade pitch angle based on a lookup table provided by DISCON.IN ! SS_Mode = 0, No setpoint smoothing - ! SS_Mode = 1, Implement setpoint smoothing + ! SS_Mode = 1, Implement pitch saturation USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ObjectInstances IMPLICIT NONE ! Inputs @@ -293,9 +293,9 @@ REAL FUNCTION PeakShaving(LocalVar, CntrPar, objInst) 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) + PitchSaturation = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, Vhatf) - END FUNCTION PeakShaving + END FUNCTION PitchSaturation !------------------------------------------------------------------------------------------------------------------------------- REAL FUNCTION Shutdown(LocalVar, CntrPar, objInst) ! PeakShaving defines a minimum blade pitch angle based on a lookup table provided by DISON.IN diff --git a/src/Controllers.f90 b/src/Controllers.f90 index 878588b1..b7be2261 100644 --- a/src/Controllers.f90 +++ b/src/Controllers.f90 @@ -93,7 +93,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst) ! Peak Shaving IF (CntrPar%PS_Mode == 1) THEN - LocalVar%PC_MinPit = PeakShaving(LocalVar,CntrPar,objInst) + LocalVar%PC_MinPit = PitchSaturation(LocalVar,CntrPar,objInst) ELSE LocalVar%PC_MinPit = CntrPar%PC_MinPit ENDIF diff --git a/src/ROSCO_Types.f90 b/src/ROSCO_Types.f90 index 4720f508..c1f45539 100644 --- a/src/ROSCO_Types.f90 +++ b/src/ROSCO_Types.f90 @@ -108,7 +108,7 @@ MODULE ROSCO_Types REAL(4) :: Z_PitchAmplitude ! Amplitude of sine pitch excitation REAL(4) :: Z_PitchFrequency ! Frequency of sine pitch excitation - INTEGER(4) :: PS_Mode ! Peak shaving mode {0: no peak shaving, 1: implement peak shaving} + INTEGER(4) :: PS_Mode ! Pitch saturation mode {0: no peak shaving, 1: implement pitch saturation} INTEGER(4) :: PS_BldPitchMin_N ! Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) REAL(4), DIMENSION(:), ALLOCATABLE :: PS_WindSpeeds ! Wind speeds corresponding to minimum blade pitch angles [m/s] REAL(4), DIMENSION(:), ALLOCATABLE :: PS_BldPitchMin ! Minimum blade pitch angles [rad] From f0030cfa2489bac8301ca23e93147f44aab2318a Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Thu, 12 Dec 2019 10:15:03 -0700 Subject: [PATCH 2/7] Revert back to Torque based setpoint smoothing --- src/ControllerBlocks.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index ea666ef8..e73bc02f 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -259,7 +259,7 @@ SUBROUTINE SetpointSmoother(LocalVar, CntrPar, objInst) ! ------ Setpoint Smoothing ------ IF ( CntrPar%SS_Mode == 1) THEN ! Find setpoint shift amount - DelOmega = ((LocalVar%BlPitch(1) - CntrPar%PC_MinPit)/0.524) * CntrPar%SS_VSGain - ((CntrPar%VS_RtPwr - LocalVar%VS_GenPwr))/CntrPar%VS_RtPwr * CntrPar%SS_PCGain ! Normalize to 30 degrees for now + DelOmega = ((LocalVar%BlPitch(1) - CntrPar%PC_MinPit)/0.524) * CntrPar%SS_VSGain - ((CntrPar%VS_RtTq - LocalVar%VS_LastGenTrq))/CntrPar%VS_RtTq * CntrPar%SS_PCGain ! Normalize to 30 degrees for now DelOmega = DelOmega * CntrPar%PC_RefSpd ! Filter LocalVar%SS_DelOmegaF = LPFilter(DelOmega, LocalVar%DT, CntrPar%F_SSCornerFreq, LocalVar%iStatus, .FALSE., objInst%instLPF) From a3d7990befd589d6bd712031dc3e65ddb295e0df Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Wed, 18 Dec 2019 10:53:21 -0700 Subject: [PATCH 3/7] Remove WSE filter --- src/ReadSetParameters.f90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ReadSetParameters.f90 b/src/ReadSetParameters.f90 index 9029a4fe..d42b0484 100644 --- a/src/ReadSetParameters.f90 +++ b/src/ReadSetParameters.f90 @@ -240,8 +240,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] IF (CntrPar%VS_ControlMode == 2) THEN - WE_Vw_f = LPFilter(LocalVar%We_Vw, LocalVar%DT, 0.625, LocalVar%iStatus, .FALSE., objInst%instLPF) - ! WE_Vw_f = LocalVar%We_Vw + ! WE_Vw_f = LPFilter(LocalVar%We_Vw, LocalVar%DT, 0.625, LocalVar%iStatus, .FALSE., objInst%instLPF) + WE_Vw_f = LocalVar%We_Vw VS_RefSpd = (CntrPar%VS_TSRopt * WE_Vw_f / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio VS_RefSpd = saturate(VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) ELSE From f043813d2d281d9c43fffe945b62a08c46f705f7 Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Wed, 18 Dec 2019 13:01:19 -0700 Subject: [PATCH 4/7] Bug fix and cleanup --- src/ControllerBlocks.f90 | 23 ++++------------------- src/Functions.f90 | 3 ++- 2 files changed, 6 insertions(+), 20 deletions(-) diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index e73bc02f..0539f395 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -129,11 +129,6 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) REAL(4) :: Tau_r ! Estimated rotor torque [Nm] REAL(4) :: a ! wind variance REAL(4) :: lambda ! tip-speed-ratio [rad] - - ! REAL(4), DIMENSION(1,23) :: WE_EKF_Vref - ! REAL(4) :: WE_EKF_Vref(23) - ! REAL(4) :: WE_EKF_Aref(23) - ! REAL(4) :: WE_EKF_Cpref(23) ! - Covariance matrices REAL(4), DIMENSION(3,3) :: F ! First order system jacobian REAL(4), DIMENSION(3,3), SAVE :: P ! Covariance estiamte @@ -144,12 +139,6 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) REAL(4), DIMENSION(1,1) :: S ! Innovation covariance REAL(4), DIMENSION(3,1), SAVE :: K ! Kalman gain matrix REAL(4) :: R_m ! Measurement noise covariance [(rad/s)^2] - REAL(4) :: temp ! temp variable - - ! WE_EKF_Vref = (/ 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25 /) - ! WE_EKF_Aref = (/ -0.0203, -0.0270, -0.0338, -0.0405, -0.0473, -0.0540, -0.0608, -0.0675, -0.0743, -0.0671, -0.0939, -0.1257, -0.1601, -0.1973, -0.2364, -0.2783, -0.3223, -0.3678, -0.4153, -0.4632, -0.5122, -0.5629, -0.6194 /) - ! WE_EKF_Cpref = (/ 0.4957, 0.4957, 0.4957, 0.4957, 0.4957, 0.4957, 0.4957, 0.4957, 0.4957, 0.4193, 0.3298, 0.2641, 0.2147, 0.1769, 0.1475, 0.1242, 0.1056, 0.0906, 0.0782, 0.0680, 0.0596, 0.0524, 0.0464 /) - ! ---- Define wind speed estimate ---- @@ -178,11 +167,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) xh = RESHAPE((/om_r, v_t, v_m/),(/3,1/)) P = RESHAPE((/0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 1.0/),(/3,3/)) K = RESHAPE((/0.0,0.0,0.0/),(/3,1/)) + ELSE - ! Update estimated values - ! v_h = v_m + v_t - a = PI * v_m/(2.0*L) - ! Find estimated operating Cp and system pole A_op = interp1d(CntrPar%WE_FOPoles_v,CntrPar%WE_FOPoles,v_h) @@ -204,8 +190,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) 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) + a = PI * v_m/(2.0*L) dxh(1,1) = 1.0/CntrPar%WE_Jtot * (Tau_r - CntrPar%WE_GearboxRatio * LocalVar%VS_LastGenTrq) dxh(2,1) = -a*v_t dxh(3,1) = 0.0 @@ -216,7 +202,8 @@ 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 - xh(1,1)) + xh = xh + K*(LocalVar%GenSpeedF/CntrPar%WE_GearboxRatio - om_r) P = MATMUL(identity(3) - MATMUL(K,H),P) ! Wind Speed Estimate @@ -227,9 +214,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) v_t = xh(2,1) v_m = xh(3,1) 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 diff --git a/src/Functions.f90 b/src/Functions.f90 index bf5bf92d..3ba5039f 100644 --- a/src/Functions.f90 +++ b/src/Functions.f90 @@ -206,7 +206,8 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) DO i = 1,size(yData) IF (yq == yData(i)) THEN ! On axis, just need 1d interpolation ii = i - interp2d = interp1d(yData,zData(i,:),xq) + interp2d = interp1d(xData,zData(i,:),xq) + ! interp2d = interp1d(yData,zData(i,:),xq) RETURN ELSEIF (yq <= yData(i)) THEN ii = i From ff99949ea822278055912253ca38224107dafbcb Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Wed, 18 Dec 2019 13:02:25 -0700 Subject: [PATCH 5/7] Read input filename - initial commit --- src/DISCON.F90 | 2 +- src/Filters.f90 | 12 +++++++++--- src/Functions.f90 | 6 +++--- src/ReadSetParameters.f90 | 23 +++++++++++++++++------ 4 files changed, 30 insertions(+), 13 deletions(-) diff --git a/src/DISCON.F90 b/src/DISCON.F90 index f74fd126..8912f1a2 100644 --- a/src/DISCON.F90 +++ b/src/DISCON.F90 @@ -59,7 +59,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME !------------------------------------------------------------------------------------------------------------------------------ ! Read avrSWAP array into derived types/variables CALL ReadAvrSWAP(avrSWAP, LocalVar) -CALL SetParameters(avrSWAP, aviFAIL, ErrMsg, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData) +CALL SetParameters(avrSWAP, aviFAIL, accINFILE, ErrMsg, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData) 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 diff --git a/src/Filters.f90 b/src/Filters.f90 index 6d41703d..c8cb0919 100644 --- a/src/Filters.f90 +++ b/src/Filters.f90 @@ -27,7 +27,9 @@ MODULE Filters CONTAINS !------------------------------------------------------------------------------------------------------------------------------- REAL FUNCTION LPFilter(InputSignal, DT, CornerFreq, iStatus, reset, inst) - ! Discrete time Low-Pass Filter + ! Discrete time Low-Pass Filter of the form: + ! H(z) = (b1z + b0) / (a1*z + a0) + ! REAL(4), INTENT(IN) :: InputSignal REAL(4), INTENT(IN) :: DT ! time step [s] REAL(4), INTENT(IN) :: CornerFreq ! corner frequency [rad/s] @@ -36,13 +38,17 @@ REAL FUNCTION LPFilter(InputSignal, DT, CornerFreq, iStatus, reset, inst) LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal ! Local + REAL(4), SAVE :: a1 ! Denominator coefficient 1 + REAL(4), SAVE :: a0 ! Denominator coefficient 0 + REAL(4), SAVE :: b1 ! Numerator coefficient 1 + REAL(4), SAVE :: b0 ! Numerator coefficient 0 REAL(4), DIMENSION(99), SAVE :: InputSignalLast ! Input signal the last time this filter was called. Supports 99 separate instances. REAL(4), DIMENSION(99), SAVE :: OutputSignalLast ! Output signal the last time this filter was called. Supports 99 separate instances. ! Initialization - - IF ((iStatus == 0) .OR. reset) THEN + IF ((iStatus == 0) .OR. reset) THEN + ! a1 = OutputSignalLast(inst) = InputSignal InputSignalLast(inst) = InputSignal ENDIF diff --git a/src/Functions.f90 b/src/Functions.f90 index bf5bf92d..988b865c 100644 --- a/src/Functions.f90 +++ b/src/Functions.f90 @@ -416,8 +416,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, avrSWAP, RootName, size_avcOUTNAME) 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//' SS_DelOmega ' - WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(m/s) ' //Tab//'(rad) ' + WRITE (UnDb,'(A)') ' Time ' //Tab//' WE_TowerTop ' //Tab//' WE_Vw ' //Tab//' GenSpeedF ' + WRITE (UnDb,'(A)') ' (sec) ' //Tab//'(m/s) ' //Tab//'(m/s) ' //Tab//'(rad/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 @@ -440,7 +440,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, avrSWAP, RootName, size_avcOUTNAME) ! Output debugging information if requested: IF (CntrPar%LoggingLevel > 0) THEN - WRITE (UnDb,FmtDat) LocalVar%Time, LocalVar%TestType, LocalVar%WE_Vw, LocalVar%SS_DelOmegaF + WRITE (UnDb,FmtDat) LocalVar%Time, LocalVar%TestType, LocalVar%WE_Vw, LocalVar%GenSpeedF END IF IF (CntrPar%LoggingLevel > 1) THEN diff --git a/src/ReadSetParameters.f90 b/src/ReadSetParameters.f90 index d42b0484..f0140df5 100644 --- a/src/ReadSetParameters.f90 +++ b/src/ReadSetParameters.f90 @@ -31,13 +31,24 @@ MODULE ReadSetParameters CONTAINS ! ----------------------------------------------------------------------------------- ! Read all constant control parameters from DISCON.IN parameter file - SUBROUTINE ReadControlParameterFileSub(CntrPar) + SUBROUTINE ReadControlParameterFileSub(CntrPar, accINFILE, accINFILE_size)!, accINFILE_size) + USE ROSCO_Types, ONLY : ControlParameters + INTEGER(4) :: accINFILE_size + CHARACTER(KIND=C_CHAR), INTENT(IN) :: accINFILE(89) + CHARACTER(89) :: DISCON_IN INTEGER(4), PARAMETER :: UnControllerParameters = 89 TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + ! CHARACTER(KIND=C_CHAR) :: DISCON_IN(LEN(TRIM(accINFILE))) - OPEN(unit=UnControllerParameters, file='DISCON.IN', status='old', action='read') + ! OPEN(unit=UnControllerParameters, file='/Users/nabbas/Documents/TurbineModels/NREL_5MW/5MW_Land/./DISCON.IN', status='old', action='read') + ! print *, 'accINFILE: ', accINFILE + ! DISCON_IN = TRIM(accINFILE) + ! accINFILE = "DISCON.IN" + DISCON_IN = TRANSFER(accINFILE,' ') + print *, DISCON_IN + OPEN(unit=UnControllerParameters, FILE=trim(DISCON_IN), status='old', action='read') !----------------------- HEADER ------------------------ READ(UnControllerParameters, *) @@ -467,7 +478,7 @@ SUBROUTINE Assert(LocalVar, CntrPar, avrSWAP, aviFAIL, ErrMsg, size_avcMSG) END SUBROUTINE Assert ! ----------------------------------------------------------------------------------- ! Define parameters for control actions - SUBROUTINE SetParameters(avrSWAP, aviFAIL, ErrMsg, size_avcMSG, CntrPar, LocalVar, objInst, PerfData) + SUBROUTINE SetParameters(avrSWAP, aviFAIL, accINFILE, ErrMsg, size_avcMSG, CntrPar, LocalVar, objInst, PerfData) USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, PerformanceData INTEGER(4), INTENT(IN) :: size_avcMSG @@ -475,9 +486,10 @@ SUBROUTINE SetParameters(avrSWAP, aviFAIL, ErrMsg, size_avcMSG, CntrPar, LocalVa TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(PerformanceData), INTENT(INOUT) :: PerfData - + REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. INTEGER(C_INT), INTENT(OUT) :: aviFAIL ! A flag used to indicate the success of this DLL call set as follows: 0 if the DLL call was successful, >0 if the DLL call was successful but cMessage should be issued as a warning messsage, <0 if the DLL call was unsuccessful or for any other reason the simulation is to be stopped at this point with cMessage as the error message. + CHARACTER(KIND=C_CHAR), INTENT(IN) :: accINFILE(NINT(avrSWAP(50))) ! The name of the parameter input file CHARACTER(size_avcMSG-1), INTENT(OUT) :: ErrMsg ! a Fortran version of the C string argument (not considered an array here) [subtract 1 for the C null-character] INTEGER(4) :: K ! Index used for looping through blades. @@ -523,8 +535,7 @@ SUBROUTINE SetParameters(avrSWAP, aviFAIL, ErrMsg, size_avcMSG, CntrPar, LocalVa 'Visit our GitHub-page to contribute to this project: '//NEW_LINE('A')// & 'https://github.com/NREL/ROSCO '//NEW_LINE('A')// & '------------------------------------------------------------------------------' - - CALL ReadControlParameterFileSub(CntrPar) + CALL ReadControlParameterFileSub(CntrPar, accINFILE, NINT(avrSWAP(50))) IF (CntrPar%WE_Mode > 0) THEN CALL READCpFile(CntrPar,PerfData) From 461f6ec111e4bde45842f70c485c0c757b447874 Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Wed, 18 Dec 2019 13:10:33 -0700 Subject: [PATCH 6/7] Update to read file --- src/ReadSetParameters.f90 | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/src/ReadSetParameters.f90 b/src/ReadSetParameters.f90 index f0140df5..2946da4a 100644 --- a/src/ReadSetParameters.f90 +++ b/src/ReadSetParameters.f90 @@ -32,23 +32,20 @@ MODULE ReadSetParameters ! ----------------------------------------------------------------------------------- ! Read all constant control parameters from DISCON.IN parameter file SUBROUTINE ReadControlParameterFileSub(CntrPar, accINFILE, accINFILE_size)!, accINFILE_size) - + USE, INTRINSIC :: ISO_C_Binding USE ROSCO_Types, ONLY : ControlParameters INTEGER(4) :: accINFILE_size - CHARACTER(KIND=C_CHAR), INTENT(IN) :: accINFILE(89) - CHARACTER(89) :: DISCON_IN + CHARACTER, DIMENSION(accINFILE_size), INTENT(IN) :: accINFILE INTEGER(4), PARAMETER :: UnControllerParameters = 89 TYPE(ControlParameters), INTENT(INOUT) :: CntrPar ! CHARACTER(KIND=C_CHAR) :: DISCON_IN(LEN(TRIM(accINFILE))) ! OPEN(unit=UnControllerParameters, file='/Users/nabbas/Documents/TurbineModels/NREL_5MW/5MW_Land/./DISCON.IN', status='old', action='read') - ! print *, 'accINFILE: ', accINFILE + print *, 'accINFILE: ', accINFILE ! DISCON_IN = TRIM(accINFILE) ! accINFILE = "DISCON.IN" - DISCON_IN = TRANSFER(accINFILE,' ') - print *, DISCON_IN - OPEN(unit=UnControllerParameters, FILE=trim(DISCON_IN), status='old', action='read') + OPEN(unit=UnControllerParameters, file=accINFILE, status='old', action='read') !----------------------- HEADER ------------------------ READ(UnControllerParameters, *) From 6e51b263f996db8d58d39757055151786798acd4 Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Wed, 18 Dec 2019 13:56:43 -0700 Subject: [PATCH 7/7] Load ServoDyn-defined DISCON input file --- src/ReadSetParameters.f90 | 18 +++++++----------- 1 file changed, 7 insertions(+), 11 deletions(-) diff --git a/src/ReadSetParameters.f90 b/src/ReadSetParameters.f90 index 2946da4a..2db294b7 100644 --- a/src/ReadSetParameters.f90 +++ b/src/ReadSetParameters.f90 @@ -35,17 +35,13 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, accINFILE, accINFILE_size)!, acc USE, INTRINSIC :: ISO_C_Binding USE ROSCO_Types, ONLY : ControlParameters - INTEGER(4) :: accINFILE_size - CHARACTER, DIMENSION(accINFILE_size), INTENT(IN) :: accINFILE - INTEGER(4), PARAMETER :: UnControllerParameters = 89 - TYPE(ControlParameters), INTENT(INOUT) :: CntrPar - ! CHARACTER(KIND=C_CHAR) :: DISCON_IN(LEN(TRIM(accINFILE))) - - ! OPEN(unit=UnControllerParameters, file='/Users/nabbas/Documents/TurbineModels/NREL_5MW/5MW_Land/./DISCON.IN', status='old', action='read') - print *, 'accINFILE: ', accINFILE - ! DISCON_IN = TRIM(accINFILE) - ! accINFILE = "DISCON.IN" - OPEN(unit=UnControllerParameters, file=accINFILE, status='old', action='read') + INTEGER(4) :: accINFILE_size ! size of DISCON input filename + CHARACTER(accINFILE_size), INTENT(IN) :: accINFILE(accINFILE_size) ! DISCON input filename + INTEGER(4), PARAMETER :: UnControllerParameters = 89 ! Unit number to open file + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar ! Control parameter type + + + OPEN(unit=UnControllerParameters, file=accINFILE(1), status='old', action='read') !----------------------- HEADER ------------------------ READ(UnControllerParameters, *)