From 9117b352d7abe48b4102e19385afdf73487ed676 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Mon, 17 Mar 2025 12:06:16 -0600 Subject: [PATCH 01/63] bug fix: Adjust steady-state solver small angle assumptions was using log maps in the steady-state solver for differencing, but the perturbation function assumed they were angles when it adjusted them later --- .../openfast-library/src/FAST_SS_Solver.f90 | 22 ++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/modules/openfast-library/src/FAST_SS_Solver.f90 b/modules/openfast-library/src/FAST_SS_Solver.f90 index f4ea398e61..ffd64c979a 100644 --- a/modules/openfast-library/src/FAST_SS_Solver.f90 +++ b/modules/openfast-library/src/FAST_SS_Solver.f90 @@ -586,8 +586,11 @@ SUBROUTINE SteadyStateSolve_Residual(caseData, p_FAST, y_FAST, m_FAST, ED, BD, A INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*) , INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None + REAL(R8Ki) :: Orientation(3,3) + INTEGER(IntKi) :: k, node INTEGER(IntKi) :: ErrStat2 INTEGER(IntKi) :: Indx_u_start + INTEGER(IntKi) :: Indx_u_angle_start(p_FAST%NumBl_Lin) CHARACTER(ErrMsgLen) :: ErrMsg2 CHARACTER(*), PARAMETER :: RoutineName = 'SteadyStateSolve_Residual' @@ -608,12 +611,23 @@ SUBROUTINE SteadyStateSolve_Residual(caseData, p_FAST, y_FAST, m_FAST, ED, BD, A !.................. ! Pack the output "residual vector" with these state derivatives and new inputs: !.................. - CALL Create_SS_Vector( p_FAST, y_FAST, U_Resid, AD, ED, BD, InputIndex, STATE_PRED ) + CALL Create_SS_Vector( p_FAST, y_FAST, U_Resid, AD, ED, BD, InputIndex, STATE_PRED, Indx_u_angle_start ) ! Make the inputs a residual (subtract from previous inputs) Indx_u_start = y_FAST%Lin%Glue%SizeLin(LIN_ContSTATE_COL) + 1 U_Resid(Indx_u_start : ) = u_in(Indx_u_start : ) - U_Resid(Indx_u_start : ) + ! we need to make a special case for the orientation matrices + do k=1,p_FAST%NumBl_Lin + Indx_u_start = Indx_u_angle_start(k) + do node=1, AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%NNodes + Orientation = EulerConstruct( u_in( Indx_u_start:Indx_u_start+2 ) ) + Orientation = MATMUL(TRANSPOSE( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node)), Orientation) + U_Resid(Indx_u_start:Indx_u_start+2) = EulerExtract(Orientation) + Indx_u_start = Indx_u_start + 3 + end do + end do + END SUBROUTINE SteadyStateSolve_Residual !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine saves the current states so they can be used to compute the residual. @@ -794,7 +808,7 @@ END SUBROUTINE Precondition_Jmat !---------------------------------------------------------------------------------------------------------------------------------- !> This routine basically packs the relevant parts of the modules' inputs and states for use in the steady-state solver. -SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateIndex ) +SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateIndex, IndxOrientStart ) !.................................................................................................................................. TYPE(FAST_ParameterType) , INTENT(IN ) :: p_FAST !< Glue-code simulation parameters TYPE(FAST_OutputFileType), INTENT(IN ) :: y_FAST !< Output variables for the glue code @@ -804,6 +818,7 @@ SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateInd TYPE(AeroDyn_Data), INTENT(INOUT) :: AD !< AeroDyn data INTEGER(IntKi), INTENT(IN ) :: InputIndex INTEGER(IntKi), INTENT(IN ) :: StateIndex + INTEGER(IntKi), optional, INTENT( OUT) :: IndxOrientStart(p_FAST%NumBl_Lin) ! local variables: INTEGER :: n @@ -904,8 +919,9 @@ SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateInd end do end do + if (PRESENT(IndxOrientStart)) IndxOrientStart(k) = n ! keep track of index for AD orientation do node = 1, AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%NNodes - CALL DCM_LogMap( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node), u(n:n+2), ErrStat2, ErrMsg2 ) + u(n:n+2) = EulerExtract( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node) ) n = n+3 end do From 411bcf834cbc31f12241b6e9b81191bb9b38baf7 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Mon, 16 Sep 2024 14:41:08 -0600 Subject: [PATCH 02/63] Lidar cleanup - set `NumPulseGate` and `NumBeam` consistently so we can cleanup some of the IF statement in the code - don't allow pulsed lidars to have 0 gates - remove unused lidar states - updated computation of `MsrPositionsY` and `MsrPositionsZ` for pulsed lidar. Previous calculations didn't make any sense to me --- modules/inflowwind/src/InflowWind.f90 | 23 +- modules/inflowwind/src/InflowWind.txt | 2 +- modules/inflowwind/src/InflowWind_Subs.f90 | 30 +-- modules/inflowwind/src/InflowWind_Types.f90 | 2 +- modules/inflowwind/src/Lidar.f90 | 268 +++++++------------- modules/inflowwind/src/Lidar.txt | 21 +- modules/inflowwind/src/Lidar_Types.f90 | 227 +---------------- modules/openfast-library/src/FAST_Subs.f90 | 2 +- modules/servodyn/src/BladedInterface_EX.f90 | 32 +-- 9 files changed, 139 insertions(+), 468 deletions(-) diff --git a/modules/inflowwind/src/InflowWind.f90 b/modules/inflowwind/src/InflowWind.f90 index de2d713a3b..d4e82820d6 100644 --- a/modules/inflowwind/src/InflowWind.f90 +++ b/modules/inflowwind/src/InflowWind.f90 @@ -186,22 +186,25 @@ SUBROUTINE InflowWind_Init( InitInp, InputGuess, p, ContStates, DiscStates, Cons endif ! initialize sensor data: - p%lidar%SensorType = InputFileData%SensorType - IF (InputFileData%SensorType /= SensorType_None) THEN + p%lidar%SensorType = InputFileData%SensorType + IF (InputFileData%SensorType == SensorType_None) THEN + p%lidar%NumBeam = 0 + p%lidar%NumPulseGate = 0 + ELSE p%lidar%NumBeam = InputFileData%NumBeam p%lidar%RotorApexOffsetPos = InputFileData%RotorApexOffsetPos p%lidar%LidRadialVel = InputFileData%LidRadialVel p%lidar%NumPulseGate = InputFileData%NumPulseGate - p%lidar%FocalDistanceX = InputFileData%FocalDistanceX ! these are allocatable. Should allocate then copy - p%lidar%FocalDistanceY = InputFileData%FocalDistanceY - p%lidar%FocalDistanceZ = InputFileData%FocalDistanceZ + call move_alloc(InputFileData%FocalDistanceX, p%lidar%FocalDistanceX) + call move_alloc(InputFileData%FocalDistanceY, p%lidar%FocalDistanceY) + call move_alloc(InputFileData%FocalDistanceZ, p%lidar%FocalDistanceZ) p%lidar%MeasurementInterval= InputFileData%MeasurementInterval p%lidar%PulseSpacing = InputFileData%PulseSpacing p%lidar%URefLid = InputFileData%URefLid p%lidar%ConsiderHubMotion = InputFileData%ConsiderHubMotion - CALL Lidar_Init( InitInp, InputGuess, p, ContStates, DiscStates, ConstrStateGuess, OtherStates, & - y, m, TimeInterval, InitOutData, TmpErrStat, TmpErrMsg ); if (Failed()) return + CALL Lidar_Init( InitInp, InputGuess, p, y, m, TimeInterval, InitOutData, TmpErrStat, TmpErrMsg ) + if (Failed()) return endif ! If a summary file was requested, open it. @@ -619,12 +622,10 @@ SUBROUTINE InflowWind_CalcOutput( Time, InputData, p, & ! return sensor values IF (p%lidar%SensorType /= SensorType_None) THEN - CALL Lidar_CalcOutput(Time, InputData, p, & - ContStates, DiscStates, ConstrStates, OtherStates, & - OutputData, m, TmpErrStat, TmpErrMsg ) + CALL Lidar_CalcOutput(Time, InputData, p, OutputData, m, TmpErrStat, TmpErrMsg ) CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) - END IF + END IF !----------------------------- diff --git a/modules/inflowwind/src/InflowWind.txt b/modules/inflowwind/src/InflowWind.txt index 924573b8f5..16f4ee0c97 100644 --- a/modules/inflowwind/src/InflowWind.txt +++ b/modules/inflowwind/src/InflowWind.txt @@ -76,7 +76,7 @@ typedef ^ ^ ReKi PulseSpacin typedef ^ ^ ReKi MeasurementInterval - - - "Time between each measurement" s typedef ^ ^ ReKi URefLid - - - "Reference average wind speed for the lidar" m/s typedef ^ ^ LOGICAL LidRadialVel - - - "TRUE => return radial component, FALSE => return 'x' direction estimate" - -typedef ^ ^ IntKi ConsiderHubMotion - - - "Flag whether or not the hub motion's impact on the Lidar measurement will be considered [0 for no, 1 for yes]" - +typedef ^ ^ LOGICAL ConsiderHubMotion - - - "whether or not the hub motion's impact on the Lidar measurement will be considered" - typedef ^ ^ Grid3D_InitInputType FF - - - "scaling data" - diff --git a/modules/inflowwind/src/InflowWind_Subs.f90 b/modules/inflowwind/src/InflowWind_Subs.f90 index 3041c710a2..f0ba82f95c 100644 --- a/modules/inflowwind/src/InflowWind_Subs.f90 +++ b/modules/inflowwind/src/InflowWind_Subs.f90 @@ -1177,7 +1177,7 @@ SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) ! Passed variables CHARACTER(ChanLen), INTENT(IN) :: OutList(:) !< The list of user-requested outputs - TYPE(InflowWind_ParameterType), INTENT(INOUT) :: p !< The module parameters + TYPE(InflowWind_ParameterType), INTENT(INOUT) :: p !< The module parameters INTEGER(IntKi), INTENT(OUT) :: ErrStat !< The error status code CHARACTER(*), INTENT(OUT) :: ErrMsg !< The error message, if an error occurred @@ -1288,17 +1288,9 @@ SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) InvalidOutput(WindAccZ) = .TRUE. end if - if (p%lidar%SensorType /= SensorType_None) then - IF (p%lidar%SensorType == SensorType_SinglePoint) THEN - DO I=p%lidar%NumBeam+1,5 - InvalidOutput( WindMeas(I) ) = .TRUE. - END DO - ELSE - DO I=p%lidar%NumPulseGate+1,5 - InvalidOutput( WindMeas(I) ) = .TRUE. - END DO - END IF - endif + do I=p%lidar%NumMeasurements+1,SIZE(WindMeas) + InvalidOutput( WindMeas(I) ) = .TRUE. + end do ! ................. End of validity checking ................. @@ -1521,16 +1513,10 @@ SUBROUTINE SetAllOuts( p, y, m, ErrStat, ErrMsg ) !FIXME: Add in Wind1Dir etc. -- although those can be derived outside of FAST. - if (p%lidar%SensorType /= SensorType_None) then - IF ( p%lidar%SensorType == SensorType_SinglePoint) THEN - DO I = 1,MIN(5, p%lidar%NumBeam ) - m%AllOuts( WindMeas(I) ) = y%lidar%LidSpeed(I) - END DO - ELSE - DO I = 1,MIN(5, p%lidar%NumPulseGate ) - m%AllOuts( WindMeas(I) ) = y%lidar%LidSpeed(I) - END DO - END IF + if (ALLOCATED(y%lidar%LidSpeed)) then + DO I = 1,MIN(SIZE(WindMeas), SIZE(y%lidar%LidSpeed) ) + m%AllOuts( WindMeas(I) ) = y%lidar%LidSpeed(I) + END DO endif END SUBROUTINE SetAllOuts diff --git a/modules/inflowwind/src/InflowWind_Types.f90 b/modules/inflowwind/src/InflowWind_Types.f90 index 646d366064..7c0dcfeee7 100644 --- a/modules/inflowwind/src/InflowWind_Types.f90 +++ b/modules/inflowwind/src/InflowWind_Types.f90 @@ -94,7 +94,7 @@ MODULE InflowWind_Types REAL(ReKi) :: MeasurementInterval = 0.0_ReKi !< Time between each measurement [s] REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] LOGICAL :: LidRadialVel = .false. !< TRUE => return radial component, FALSE => return 'x' direction estimate [-] - INTEGER(IntKi) :: ConsiderHubMotion = 0_IntKi !< Flag whether or not the hub motion's impact on the Lidar measurement will be considered [0 for no, 1 for yes] [-] + LOGICAL :: ConsiderHubMotion = .false. !< whether or not the hub motion's impact on the Lidar measurement will be considered [-] TYPE(Grid3D_InitInputType) :: FF !< scaling data [-] END TYPE InflowWind_InputFile ! ======================= diff --git a/modules/inflowwind/src/Lidar.f90 b/modules/inflowwind/src/Lidar.f90 index ddb5861b0e..35cd42d128 100644 --- a/modules/inflowwind/src/Lidar.f90 +++ b/modules/inflowwind/src/Lidar.f90 @@ -62,15 +62,11 @@ MODULE Lidar !! The parameters are set here and not changed during the simulation. !! The initial states and initial guess for the input are defined. !! note that we're calling this with the InflowWind data types, so that data is INOUT instead of OUT -SUBROUTINE Lidar_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut, ErrStat, ErrMsg ) +SUBROUTINE Lidar_Init( InitInp, u, p, y, m, Interval, InitOut, ErrStat, ErrMsg ) TYPE(InflowWind_InitInputType), INTENT(IN ) :: InitInp !< Input data for initialization routine TYPE(InflowWind_InputType), INTENT(INOUT) :: u !< An initial guess for the input; input mesh must be defined TYPE(InflowWind_ParameterType), INTENT(INOUT) :: p !< Parameters - TYPE(InflowWind_ContinuousStateType), INTENT(INOUT) :: x !< Initial continuous states - TYPE(InflowWind_DiscreteStateType), INTENT(INOUT) :: xd !< Initial discrete states - TYPE(InflowWind_ConstraintStateType), INTENT(INOUT) :: z !< Initial guess of the constraint states - TYPE(InflowWind_OtherStateType), INTENT(INOUT) :: OtherState !< Initial other states TYPE(InflowWind_MiscVarType), INTENT(INOUT) :: m !< Misc variables for optimization (not copied in glue code) TYPE(InflowWind_OutputType), INTENT(INOUT) :: y !< Initial system outputs (outputs are not calculated; !! only the output mesh is initialized) @@ -102,148 +98,94 @@ SUBROUTINE Lidar_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, Init ErrStat = ErrID_None ErrMsg = "" - ! Check for errors in the InflowWind Input File - - ! Make sure that NumPulseGate makes sense - IF ( (p%lidar%SensorType == 3) .and. (p%lidar%NumPulseGate < 0 .OR. p%lidar%NumPulseGate > 5) ) THEN - CALL SetErrStat( ErrID_Fatal, 'NumPulseGate must be greater than or equal to zero and less than 5.', & - ErrStat, ErrMsg, RoutineName ) - RETURN - ENDIF - - ! Make sure that multiple beams are only used when using single point beams - IF ( p%lidar%NumBeam > 1 .AND. p%lidar%SensorType > 1) THEN - CALL SetErrStat( ErrID_Fatal, 'Multiple beams can only be used with single point lidar', & - ErrStat, ErrMsg, RoutineName ) - RETURN - ENDIF - - CALL AllocAry(p%lidar%MsrPosition , 3, max(1,p%lidar%NumBeam), 'Array for measurement coordinates', TmpErrStat, TmpErrMsg ) - CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName) - IF ( ErrStat>= AbortErrLev ) RETURN - - - IF (p%lidar%SensorType == SensorType_None) THEN + if (p%lidar%SensorType == SensorType_None) then p%lidar%NumPulseGate = 0 - ELSEIF (p%lidar%SensorType == SensorType_SinglePoint) THEN + p%lidar%NumBeam = 0 + return + elseif (p%lidar%SensorType == SensorType_SinglePoint) then p%lidar%NumPulseGate = 1 - ELSE + + if (p%lidar%NumBeam < 1) then + call SetErrStat( ErrID_Fatal, 'NumBeam must be greater than 0 for single-point beams.', ErrStat, ErrMsg, RoutineName ) + return + end if + else + ! Make sure that multiple beams are only used when using single-point beams + if ( p%lidar%NumBeam > 1 ) then + call SetErrStat( ErrID_Fatal, 'Multiple beams can only be used with single point lidar', ErrStat, ErrMsg, RoutineName ) + return + endif + p%lidar%NumBeam = 1 + ! variables for both pulsed and continuous-wave lidars - - - - - p%lidar%SpatialRes = 0.5_ReKi*p%lidar%URefLid*Interval + p%lidar%SpatialRes = 0.5_ReKi*p%lidar%URefLid*Interval p%lidar%RayRangeSq = (Pi*(BeamRad**2)/LsrWavLen)**2 - - - - - IF (p%lidar%SensorType == SensorType_ContinuousLidar) THEN - p%lidar%WtFnTrunc = 0.02_ReKi + if (p%lidar%SensorType == SensorType_ContinuousLidar) then p%lidar%NumPulseGate = 1 - - ELSEIF (p%lidar%SensorType == SensorType_PulsedLidar) THEN + p%lidar%WtFnTrunc = 0.02_ReKi + elseif (p%lidar%SensorType == SensorType_PulsedLidar) then - p%lidar%WtFnTrunc = 0.01_ReKi + ! Make sure that NumPulseGate makes sense + if ( (p%lidar%NumPulseGate < 1 .OR. p%lidar%NumPulseGate > 5) ) then + call SetErrStat( ErrID_Fatal, 'NumPulseGate must be greater than zero and less than 6.', ErrStat, ErrMsg, RoutineName ) + return + endif + p%lidar%WtFnTrunc = 0.01_ReKi - ! values for the WindCube - ! p%lidar%DeltaP = 30.0_ReKi !Replaced by pulse spacing p%lidar%DeltaR = 30.0_ReKi - ! p%lidar%PulseRangeOne = 50.0 ReKi ! Replaced by the focal distance + ! p%lidar%PulseRangeOne = 50.0 ReKi ! Replaced by the focal distance; bjj: it's used in an IF statement, so initializing below: + p%lidar%PulseRangeOne = 0.0_ReKi p%lidar%r_p = p%lidar%DeltaR/(2.0_ReKi*SQRT(LOG(2.0_ReKi))) - ELSE - - CALL SetErrStat(ErrID_Fatal, "Invalid sensor type.", ErrStat, ErrMsg, RoutineName) - RETURN - - END IF - - END IF - - - !............................................................................................ - ! Define initial system states here: - !............................................................................................ + else + call SetErrStat(ErrID_Fatal, "Invalid sensor type.", ErrStat, ErrMsg, RoutineName) + return + end if + endif - !x%lidar%DummyContState = 0.0_ReKi - !xdlidar%%DummyDiscState = 0.0_ReKi - !z%lidar%DummyConstrState = 0.0_ReKi - !OtherState%lidar%DummyOtherState = 0.0_ReKi - ! + p%lidar%LidPosition = InitInp%lidar%HubPosition + p%lidar%NumMeasurements = MAX(p%lidar%NumBeam,p%lidar%NumPulseGate) !note, this is at least 1 for every case (except SensorType_None, which cannot get to this place) - !............................................................................................ - ! Define initial guess for the system inputs here: - !............................................................................................ + CALL AllocAry(p%lidar%MsrPosition , 3, p%lidar%NumBeam, 'Array for measurement coordinates (per beam)', TmpErrStat, TmpErrMsg ) + CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName) + IF ( ErrStat>= AbortErrLev ) RETURN - p%lidar%LidPosition = InitInp%lidar%HubPosition DO IBeam = 1,p%lidar%NumBeam - p%lidar%MsrPosition(:,IBeam) = (/ p%lidar%FocalDistanceX(IBeam), p%lidar%FocalDistanceY(IBeam), p%lidar%FocalDistanceZ(IBeam) /) !bjj: todo FIXME with initial guess of lidar focus. + p%lidar%MsrPosition(:,IBeam) = (/ p%lidar%FocalDistanceX(IBeam), p%lidar%FocalDistanceY(IBeam), p%lidar%FocalDistanceZ(IBeam) /) ! bjj: todo FIXME with initial guess of lidar focus. END DO + + !............................................................................................ + ! Define initial guess for the system inputs here: + !............................................................................................ u%lidar%PulseLidEl = 0.0_ReKi u%lidar%PulseLidAz = 0.0_ReKi - !............................................................................................ - ! Define system output initializations (set up mesh) here: + ! Define system output initializations here: !............................................................................................ - !CALL AllocAry( y%WriteOutput, p%NumOuts, 'WriteOutput', ErrStat2, ErrMsg2 ) - ! CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) - ! IF (ErrStat >= AbortErrLev) RETURN - !y%WriteOutput = 0 - - IF (p%lidar%SensorType == SensorType_SinglePoint) THEN - CALL AllocAry( y%lidar%LidSpeed, p%lidar%NumBeam, 'y%lidar%LidSpeed', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); + CALL AllocAry( y%lidar%LidSpeed, p%lidar%NumMeasurements, 'y%lidar%LidSpeed', ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - !CALL AllocAry( y%LidErr, p%NumPulseGate, 'y%LidErr', ErrStat2, ErrMsg2 ) - ! CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - CALL AllocAry( y%lidar%WtTrunc, p%lidar%NumBeam, 'y%lidar%WtTrunc', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - CALL AllocAry( y%lidar%MsrPositionsX, p%lidar%NumBeam, 'y%lidar%MsrPositionsX', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); + CALL AllocAry( y%lidar%WtTrunc, p%lidar%NumMeasurements, 'y%lidar%WtTrunc', ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - CALL AllocAry( y%lidar%MsrPositionsY, p%lidar%NumBeam, 'y%lidar%MsrPositionsY', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); + CALL AllocAry( y%lidar%MsrPositionsX, p%lidar%NumMeasurements, 'y%lidar%MsrPositionsX', ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - CALL AllocAry( y%lidar%MsrPositionsZ, p%lidar%NumBeam, 'y%lidar%MsrPositionsZ', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - ELSEIF (p%lidar%NumPulseGate > 0) then ! the Cray Fortran compiler doesn't like allocating size zero - CALL AllocAry( y%lidar%LidSpeed, p%lidar%NumPulseGate, 'y%lidar%LidSpeed', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - !CALL AllocAry( y%LidErr, p%NumPulseGate, 'y%LidErr', ErrStat2, ErrMsg2 ) - !CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - CALL AllocAry( y%lidar%WtTrunc, p%lidar%NumPulseGate, 'y%lidar%WtTrunc', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - CALL AllocAry( y%lidar%MsrPositionsX, p%lidar%NumPulseGate, 'y%lidar%MsrPositionsX', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - - CALL AllocAry( y%lidar%MsrPositionsY, p%lidar%NumPulseGate, 'y%lidar%MsrPositionsY', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); + CALL AllocAry( y%lidar%MsrPositionsY, p%lidar%NumMeasurements, 'y%lidar%MsrPositionsY', ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - CALL AllocAry( y%lidar%MsrPositionsZ, p%lidar%NumPulseGate, 'y%lidar%MsrPositionsZ', ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); - ENDIF - + CALL AllocAry( y%lidar%MsrPositionsZ, p%lidar%NumMeasurements, 'y%lidar%MsrPositionsZ', ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ); IF (ErrStat >= AbortErrLev) RETURN - if (allocated(y%lidar%LidSpeed)) y%lidar%LidSpeed = 0.0 - if (allocated(y%lidar%WtTrunc )) y%lidar%WtTrunc = 0.0 - - !............................................................................................ - ! Define initialization-routine output here: - !............................................................................................ + y%lidar%LidSpeed = 0.0 + y%lidar%WtTrunc = 0.0 RETURN @@ -304,16 +246,12 @@ END SUBROUTINE Lidar_End !> Routine for computing outputs, used in both loose and tight coupling. !! @note this breaks the framework because we're passing the IfW types instead of the Lidar types... this is necessary to get !! appropriate wind speeds for the lidar measurements. -SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMsg ) +SUBROUTINE Lidar_CalcOutput( t, u, p, y, m, ErrStat, ErrMsg ) !.................................................................................................................................. REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds TYPE(InflowWind_InputType), INTENT(IN ) :: u !< Inputs at t TYPE(InflowWind_ParameterType), INTENT(IN ) :: p !< Parameters - TYPE(InflowWind_ContinuousStateType), INTENT(IN ) :: x !< Continuous states at t - TYPE(InflowWind_DiscreteStateType), INTENT(IN ) :: xd !< Discrete states at t - TYPE(InflowWind_ConstraintStateType), INTENT(IN ) :: z !< Constraint states at t - TYPE(InflowWind_OtherStateType), INTENT(IN ) :: OtherState !< Other/optimization states TYPE(InflowWind_OutputType), INTENT(INOUT) :: y !< Outputs computed at t (Input only so that mesh con- !! nectivity information does not have to be recalculated) TYPE(InflowWind_MiscVarType), INTENT(INOUT) :: m !< Misc variables for optimization (not copied in glue code) @@ -357,37 +295,37 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs ErrStat = ErrID_None ErrMsg = "" - + + IF (p%lidar%SensorType == SensorType_None) RETURN + MeasurementCurrentStep = INT(t / p%lidar%MeasurementInterval) IF ( (p%lidar%MeasurementInterval * MeasurementCurrentStep) /= t ) THEN - VelocityUVW(:,1) = 0 + !bjj: note: no error set; no output set. RETURN ENDIF - + LidPosition = p%lidar%LidPosition + p%lidar%RotorApexOffsetPos ! lidar offset-from-rotor-apex position - IF (p%lidar%ConsiderHubMotion == 1) THEN + IF (p%lidar%ConsiderHubMotion) THEN LidPosition = LidPosition + (/ u%lidar%HubDisplacementX, u%lidar%HubDisplacementY, u%lidar%HubDisplacementZ /) ! rotor apex position (absolute) END IF - IF (p%lidar%SensorType == SensorType_None) RETURN - !............................................................................................................................... ! Compute the outputs !............................................................................................................................... - ! Initialize position to zero in case no all values are set + ! Initialize position to zero in case not all values are set PositionXYZ = 0.0_ReKi + IBeam = 1 IF (p%lidar%SensorType == SensorType_SinglePoint) THEN DO IBeam = 1,p%lidar%NumBeam !get lidar speed at the focal point to see if it is out of bounds - PositionXYZ(:,1) = LidPosition + p%lidar%MsrPosition(:,IBeam) + PositionXYZ(:,1) = LidPosition + p%lidar%MsrPosition(:,IBeam) - call IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, & - AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) + call IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) y%lidar%LidSpeed(IBeam) = SQRT( DOT_PRODUCT(VelocityUVW(:,1), VelocityUVW(:,1)) ) @@ -395,15 +333,16 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs y%lidar%MsrPositionsX(IBeam) = PositionXYZ(1,1) y%lidar%MsrPositionsY(IBeam) = PositionXYZ(2,1) - y%lidar%MsrPositionsZ(IBeam) = PositionXYZ(3,1) + y%lidar%MsrPositionsZ(IBeam) = PositionXYZ(3,1) END DO ELSEIF (p%lidar%SensorType == SensorType_ContinuousLidar) THEN !calculate the focal distance of the lidar as well as the modified focal distance so that the peak of the weighting func !is at the intended focal distance - - Distance = p%lidar%MsrPosition(:,1) - LidPosition + IBeam = 1 + + Distance = p%lidar%MsrPosition(:,IBeam) - LidPosition FocDist = SQRT( DOT_PRODUCT( Distance, Distance ) ) !TwoNorm IF(EqualRealNos(FocDist,0.0_ReKi)) THEN ! Avoid division-by-zero @@ -429,19 +368,17 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs LidWtRatio = 1.0_ReKi !LidWt/LidWtMax !get lidar speed at the focal point to see if it is out of bounds - PositionXYZ(:,1) = LidPosition + p%lidar%MsrPosition(:,1) + PositionXYZ(:,1) = LidPosition + p%lidar%MsrPosition(:,IBeam) - y%lidar%MsrPositionsX(1) = LidPosition(1) + p%lidar%MsrPosition(1,1) - y%lidar%MsrPositionsY(1) = LidPosition(2) + p%lidar%MsrPosition(2,1) - y%lidar%MsrPositionsZ(1) = LidPosition(3) + p%lidar%MsrPosition(3,1) + y%lidar%MsrPositionsX(IBeam) = PositionXYZ(1,1) + y%lidar%MsrPositionsY(IBeam) = PositionXYZ(2,1) + y%lidar%MsrPositionsZ(IBeam) = PositionXYZ(3,1) - CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, & - AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) - CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ(:,1:1), VelocityUVW(:,1:1), AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) !if out of bounds IF (ErrStat >= AbortErrLev) THEN - !y%lidar%LidErr = 1 y%lidar%LidSpeed = -99.0 RETURN !escape function ENDIF @@ -474,7 +411,6 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs IF (LidRange > FocDist) THEN IF (NWTC_VerboseLevel == NWTC_Verbose) & CALL SetErrStat( ErrID_Info, "Lidar truncation point is behind the lidar. Truncation ratio is "//trim(num2lstr(LidWtRatio))//'.', ErrStat, ErrMsg, RoutineName) ! set informational message about point being behind lidar - !y%LidErr = 3 y%lidar%WtTrunc = LidWtRatio EXIT ENDIF @@ -490,17 +426,15 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs PositionXYZ(1,2) = LidPosition(1) - COS(LidTheta)*COS(LidPhi)*(FocDist - LidRange) PositionXYZ(2,2) = LidPosition(2) + SIN(LidTheta)*COS(LidPhi)*(FocDist - LidRange) - CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, & - AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) + CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) IF (ErrStat2 >= AbortErrLev) THEN !out of bounds IF (NWTC_VerboseLevel == NWTC_Verbose) & CALL SetErrStat( ErrID_Warn, "Lidar speed truncated. Truncation ratio is "//trim(num2lstr(LidWtRatio))//".", ErrStat, ErrMsg, RoutineName ) - !y%LidErr = 2 y%lidar%WtTrunc = LidWtRatio EXIT ENDIF - y%lidar%LidSpeed = y%lidar%LidSpeed + LidWt*DOT_PRODUCT(-1*LidDirUnVec, VelocityUVW(:,1) + VelocityUVW(:,2)) + y%lidar%LidSpeed = y%lidar%LidSpeed + LidWt*DOT_PRODUCT(-1*LidDirUnVec, VelocityUVW(:,1) + VelocityUVW(:,2)) WtFuncSum = WtFuncSum + 2*LidWt END DO @@ -516,40 +450,35 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs ENDIF ELSE !p%SensorType == SensorType_PulsedLidar - - + IBeam = 1 LidDirUnVec(1) = -1*COS(u%lidar%PulseLidEl) LidDirUnVec(2) = SIN(u%lidar%PulseLidEl)*SIN(u%lidar%PulseLidAz) LidDirUnVec(3) = SIN(u%lidar%PulseLidEl)*COS(u%lidar%PulseLidAz) - DO IRangeGt = 1,p%lidar%NumPulseGate - !y%lidar%LidErr(IRangeGt) = 0 - - LidPosition(2) = LidPosition(2) + p%lidar%MsrPosition(2,1) - LidPosition(3) = LidPosition(3) + p%lidar%MsrPosition(3,1) + LidPosition(2) = LidPosition(2) + p%lidar%MsrPosition(2,IBeam) + LidPosition(3) = LidPosition(3) + p%lidar%MsrPosition(3,IBeam) !get lidar speed at the focal point to see if it is out of bounds - PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,1) - (IRangeGt-1)*p%lidar%PulseSpacing) + PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,IBeam) - (IRangeGt-1)*p%lidar%PulseSpacing) - y%lidar%MsrPositionsX(IRangeGt) = LidPosition(1) + LidDirUnVec(1)*(-p%lidar%MsrPosition(1,1) - (IRangeGt-1)*p%lidar%PulseSpacing) - y%lidar%MsrPositionsY(IRangeGt) = LidPosition(2) + p%lidar%MsrPosition(2,1) - y%lidar%MsrPositionsZ(IRangeGt) = LidPosition(3) + p%lidar%MsrPosition(3,1) + !bjj: I don't think this makes any sense in the Y and Z components. Will modify MsrPositionsY and MsrPositionsZ + y%lidar%MsrPositionsX(IRangeGt) = PositionXYZ(1,1) + y%lidar%MsrPositionsY(IRangeGt) = PositionXYZ(2,1) ! was LidPosition(2) + p%lidar%MsrPosition(2,IBeam) + y%lidar%MsrPositionsZ(IRangeGt) = PositionXYZ(3,1) ! was LidPosition(3) + p%lidar%MsrPosition(3,IBeam) - CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, & - AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) + CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ(:,1:1), VelocityUVW(:,1:1), AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - LidWt = NWTC_ERF((p%lidar%PulseSpacing/2)/p%lidar%r_p)/p%lidar%PulseSpacing + LidWt = NWTC_ERF((p%lidar%PulseSpacing/2)/p%lidar%r_p)/p%lidar%PulseSpacing LidWtMax = LidWt LidWtRatio = 1.0_ReKi !LidWt/LidWtMax !if out of bounds IF (ErrStat2 >= AbortErrLev) THEN - !y%LidErr(IRangeGt) = 1 y%lidar%LidSpeed(IRangeGt) = -99 RETURN !escape function ENDIF @@ -580,26 +509,23 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs IF (NWTC_VerboseLevel == NWTC_Verbose) & CALL SetErrStat( ErrID_Info, "Lidar truncation point at gate "//trim(num2lstr(IRangeGt))//" is behind the lidar. Truncation ratio is "& //trim(num2lstr(LidWtRatio))//'.', ErrStat, ErrMsg, RoutineName) ! set informational message about point being behind lidar - !y%LidErr(IRangeGt) = 3 y%lidar%WtTrunc(IRangeGt) = LidWtRatio EXIT ENDIF !calculate points to scan for current beam point - PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,1) - (IRangeGt-1)*p%lidar%PulseSpacing + LidRange) - PositionXYZ(:,2) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,1) - (IRangeGt-1)*p%lidar%PulseSpacing - LidRange) - CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, & - AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) + PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,IBeam) - (IRangeGt-1)*p%lidar%PulseSpacing + LidRange) + PositionXYZ(:,2) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,IBeam) - (IRangeGt-1)*p%lidar%PulseSpacing - LidRange) + CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ, VelocityUVW, AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) IF (ErrStat2 >= AbortErrLev) THEN !out of bounds IF (NWTC_VerboseLevel == NWTC_Verbose) & CALL SetErrStat( ErrID_Warn, "Lidar speed at gate "//trim(num2lstr(IRangeGt))//" truncated. Truncation ratio is "//trim(num2lstr(LidWtRatio))//".", ErrStat, ErrMsg, RoutineName ) - !y%LidErr(IRangeGt) = 2 y%lidar%WtTrunc(IRangeGt) = LidWtRatio EXIT ENDIF - y%lidar%LidSpeed(IRangeGt) = y%lidar%LidSpeed(IRangeGt) + LidWt*DOT_PRODUCT(-1*LidDirUnVec,VelocityUVW(:,1) + VelocityUVW(:,2)) + y%lidar%LidSpeed(IRangeGt) = y%lidar%LidSpeed(IRangeGt) + LidWt*DOT_PRODUCT(-1*LidDirUnVec,VelocityUVW(:,1) + VelocityUVW(:,2)) WtFuncSum = WtFuncSum + 2*LidWt END DO @@ -613,9 +539,9 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMs y%lidar%LidSpeed(IRangeGt) = -1*y%lidar%LidSpeed(IRangeGt)/(LidDirUnVec(1)*WtFuncSum) ENDIF - END DO + END DO - END IF + END IF END SUBROUTINE Lidar_CalcOutput !---------------------------------------------------------------------------------------------------------------------------------- diff --git a/modules/inflowwind/src/Lidar.txt b/modules/inflowwind/src/Lidar.txt index 8f2defd9dd..14fdbe97e6 100644 --- a/modules/inflowwind/src/Lidar.txt +++ b/modules/inflowwind/src/Lidar.txt @@ -33,7 +33,6 @@ typedef ^ Lidar_ParameterType ReKi SpatialRes - - - "spatial samp typedef ^ Lidar_ParameterType IntKi SensorType - - - "SensorType_* parameter" - typedef ^ Lidar_ParameterType ReKi WtFnTrunc - - - "Percentage of the peak value at which to truncate weighting function" typedef ^ Lidar_ParameterType ReKi PulseRangeOne - - - "the range to the closest range gate" "m" -typedef ^ Lidar_ParameterType ReKi DeltaP - - - "the distance between range gates" "m" typedef ^ Lidar_ParameterType ReKi DeltaR - - - "the FWHM width of the pulse" typedef ^ Lidar_ParameterType ReKi r_p - - - typedef ^ Lidar_ParameterType LOGICAL LidRadialVel - - - "TRUE => return radial component, FALSE => return 'x' direction estimate" - @@ -44,28 +43,15 @@ typedef ^ Lidar_ParameterType IntKi NumBeam - - - "Numb typedef ^ Lidar_ParameterType ReKi FocalDistanceX : - - "LIDAR LOS focal distance co-ordinates in the x direction" "m" typedef ^ Lidar_ParameterType ReKi FocalDistanceY : - - "LIDAR LOS focal distance co-ordinates in the y direction" "m" typedef ^ Lidar_ParameterType ReKi FocalDistanceZ : - - "LIDAR LOS focal distance co-ordinates in the z direction" "m" -typedef ^ Lidar_ParameterType ReKi MsrPosition {:}{:} - - "Position of the desired wind measurement (was XMsrPt, YMsrPt, ZMsrPt)" "m" +typedef ^ Lidar_ParameterType ReKi MsrPosition {:}{:} - - "Position of the desired wind measurement, per beam (was XMsrPt, YMsrPt, ZMsrPt)" "m" typedef ^ Lidar_ParameterType ReKi PulseSpacing - - - "Distance between range gates" "m" typedef ^ Lidar_ParameterType ReKi URefLid - - - "Reference average wind speed for the lidar" "m/s" -typedef ^ Lidar_ParameterType IntKi ConsiderHubMotion - - - "Flag whether to consider the hub motion's impact on the Lidar measurement" - +typedef ^ Lidar_ParameterType LOGICAL ConsiderHubMotion - - - "Whether to consider the hub motion's impact on the Lidar measurement" - typedef ^ Lidar_ParameterType ReKi MeasurementInterval - - - "Time steps between lidar measurements" "s" typedef ^ Lidar_ParameterType ReKi LidPosition {3} - - "Position of the Lidar unit (was XLidPt, YLidPt, ZLidPt)" "m" +typedef ^ Lidar_ParameterType IntKi NumMeasurements - 0 - "Number of measurements output" - -# ..... States .................................................................................................................... -# Define continuous (differentiable) states here: -typedef ^ ContinuousStateType ReKi DummyContState - - - "Remove this variable if you have continuous states" - -# Define discrete (nondifferentiable) states here: -typedef ^ DiscreteStateType ReKi DummyDiscState - - - "Remove this variable if you have discrete states" - -# Define constraint states here: -typedef ^ ConstraintStateType ReKi DummyConstrState - - - "Remove this variable if you have constraint states" - -# Define "other" states (any data that are not considered actual states) here: -typedef ^ OtherStateType ReKi DummyOtherState - - - - -# ..... Misc/Optimization variables................................................................................................. -# Define any data that are used only for efficiency purposes (these variables are not associated with time): -# e.g. indices for searching in an array, large arrays that are local variables in any routine called multiple times, etc. -typedef ^ MiscVarType ReKi DummyMiscVar - - - "Remove this variable if you have misc variables" - # ..... LIDAR_InputType data ....................................................................................................... @@ -81,4 +67,3 @@ typedef ^ Lidar_OutputType ReKi WtTrunc {:} - - "Contains the frac typedef ^ Lidar_OutputType ReKi MsrPositionsX {:} - - "Lidar X direction measurement points" "m" typedef ^ Lidar_OutputType ReKi MsrPositionsY {:} - - "Lidar Y direction measurement points" "m" typedef ^ Lidar_OutputType ReKi MsrPositionsZ {:} - - "Lidar Z direction measurement points" "m" -#typedef ^ Lidar_OutputType IntKi LidErr {:} - - "Error code; THIS NEEDS TO GET FIXED (no integer outputs)" diff --git a/modules/inflowwind/src/Lidar_Types.f90 b/modules/inflowwind/src/Lidar_Types.f90 index 8277eb6a54..c4e0fa580b 100644 --- a/modules/inflowwind/src/Lidar_Types.f90 +++ b/modules/inflowwind/src/Lidar_Types.f90 @@ -61,7 +61,6 @@ MODULE Lidar_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< SensorType_* parameter [-] REAL(ReKi) :: WtFnTrunc = 0.0_ReKi !< Percentage of the peak value at which to truncate weighting function [-] REAL(ReKi) :: PulseRangeOne = 0.0_ReKi !< the range to the closest range gate [m] - REAL(ReKi) :: DeltaP = 0.0_ReKi !< the distance between range gates [m] REAL(ReKi) :: DeltaR = 0.0_ReKi !< the FWHM width of the pulse [-] REAL(ReKi) :: r_p = 0.0_ReKi LOGICAL :: LidRadialVel = .false. !< TRUE => return radial component, FALSE => return 'x' direction estimate [-] @@ -72,39 +71,15 @@ MODULE Lidar_Types REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: FocalDistanceX !< LIDAR LOS focal distance co-ordinates in the x direction [m] REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: FocalDistanceY !< LIDAR LOS focal distance co-ordinates in the y direction [m] REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: FocalDistanceZ !< LIDAR LOS focal distance co-ordinates in the z direction [m] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MsrPosition !< Position of the desired wind measurement (was XMsrPt, YMsrPt, ZMsrPt) [m] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MsrPosition !< Position of the desired wind measurement, per beam (was XMsrPt, YMsrPt, ZMsrPt) [m] REAL(ReKi) :: PulseSpacing = 0.0_ReKi !< Distance between range gates [m] REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] - INTEGER(IntKi) :: ConsiderHubMotion = 0_IntKi !< Flag whether to consider the hub motion's impact on the Lidar measurement [-] + LOGICAL :: ConsiderHubMotion = .false. !< Whether to consider the hub motion's impact on the Lidar measurement [-] REAL(ReKi) :: MeasurementInterval = 0.0_ReKi !< Time steps between lidar measurements [s] REAL(ReKi) , DIMENSION(1:3) :: LidPosition = 0.0_ReKi !< Position of the Lidar unit (was XLidPt, YLidPt, ZLidPt) [m] + INTEGER(IntKi) :: NumMeasurements = 0 !< Number of measurements output [-] END TYPE Lidar_ParameterType ! ======================= -! ========= Lidar_ContinuousStateType ======= - TYPE, PUBLIC :: Lidar_ContinuousStateType - REAL(ReKi) :: DummyContState = 0.0_ReKi !< Remove this variable if you have continuous states [-] - END TYPE Lidar_ContinuousStateType -! ======================= -! ========= Lidar_DiscreteStateType ======= - TYPE, PUBLIC :: Lidar_DiscreteStateType - REAL(ReKi) :: DummyDiscState = 0.0_ReKi !< Remove this variable if you have discrete states [-] - END TYPE Lidar_DiscreteStateType -! ======================= -! ========= Lidar_ConstraintStateType ======= - TYPE, PUBLIC :: Lidar_ConstraintStateType - REAL(ReKi) :: DummyConstrState = 0.0_ReKi !< Remove this variable if you have constraint states [-] - END TYPE Lidar_ConstraintStateType -! ======================= -! ========= Lidar_OtherStateType ======= - TYPE, PUBLIC :: Lidar_OtherStateType - REAL(ReKi) :: DummyOtherState = 0.0_ReKi - END TYPE Lidar_OtherStateType -! ======================= -! ========= Lidar_MiscVarType ======= - TYPE, PUBLIC :: Lidar_MiscVarType - REAL(ReKi) :: DummyMiscVar = 0.0_ReKi !< Remove this variable if you have misc variables [-] - END TYPE Lidar_MiscVarType -! ======================= ! ========= Lidar_InputType ======= TYPE, PUBLIC :: Lidar_InputType REAL(ReKi) :: PulseLidEl = 0.0_ReKi !< the angle off of the x axis that the lidar is aimed (0 would be staring directly upwind, pi/2 would be staring perpendicular to the x axis) [-] @@ -234,7 +209,6 @@ subroutine Lidar_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg DstParamData%SensorType = SrcParamData%SensorType DstParamData%WtFnTrunc = SrcParamData%WtFnTrunc DstParamData%PulseRangeOne = SrcParamData%PulseRangeOne - DstParamData%DeltaP = SrcParamData%DeltaP DstParamData%DeltaR = SrcParamData%DeltaR DstParamData%r_p = SrcParamData%r_p DstParamData%LidRadialVel = SrcParamData%LidRadialVel @@ -295,6 +269,7 @@ subroutine Lidar_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg DstParamData%ConsiderHubMotion = SrcParamData%ConsiderHubMotion DstParamData%MeasurementInterval = SrcParamData%MeasurementInterval DstParamData%LidPosition = SrcParamData%LidPosition + DstParamData%NumMeasurements = SrcParamData%NumMeasurements end subroutine subroutine Lidar_DestroyParam(ParamData, ErrStat, ErrMsg) @@ -330,7 +305,6 @@ subroutine Lidar_PackParam(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%WtFnTrunc) call RegPack(RF, InData%PulseRangeOne) - call RegPack(RF, InData%DeltaP) call RegPack(RF, InData%DeltaR) call RegPack(RF, InData%r_p) call RegPack(RF, InData%LidRadialVel) @@ -347,6 +321,7 @@ subroutine Lidar_PackParam(RF, Indata) call RegPack(RF, InData%ConsiderHubMotion) call RegPack(RF, InData%MeasurementInterval) call RegPack(RF, InData%LidPosition) + call RegPack(RF, InData%NumMeasurements) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -365,7 +340,6 @@ subroutine Lidar_UnPackParam(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%WtFnTrunc); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%PulseRangeOne); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%DeltaP); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%DeltaR); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%r_p); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%LidRadialVel); if (RegCheckErr(RF, RoutineName)) return @@ -382,196 +356,7 @@ subroutine Lidar_UnPackParam(RF, OutData) call RegUnpack(RF, OutData%ConsiderHubMotion); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%MeasurementInterval); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%LidPosition); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyContState(SrcContStateData, DstContStateData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_ContinuousStateType), intent(in) :: SrcContStateData - type(Lidar_ContinuousStateType), intent(inout) :: DstContStateData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyContState' - ErrStat = ErrID_None - ErrMsg = '' - DstContStateData%DummyContState = SrcContStateData%DummyContState -end subroutine - -subroutine Lidar_DestroyContState(ContStateData, ErrStat, ErrMsg) - type(Lidar_ContinuousStateType), intent(inout) :: ContStateData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyContState' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackContState(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_ContinuousStateType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackContState' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyContState) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackContState(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_ContinuousStateType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackContState' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyContState); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyDiscState(SrcDiscStateData, DstDiscStateData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_DiscreteStateType), intent(in) :: SrcDiscStateData - type(Lidar_DiscreteStateType), intent(inout) :: DstDiscStateData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyDiscState' - ErrStat = ErrID_None - ErrMsg = '' - DstDiscStateData%DummyDiscState = SrcDiscStateData%DummyDiscState -end subroutine - -subroutine Lidar_DestroyDiscState(DiscStateData, ErrStat, ErrMsg) - type(Lidar_DiscreteStateType), intent(inout) :: DiscStateData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyDiscState' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackDiscState(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_DiscreteStateType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackDiscState' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyDiscState) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackDiscState(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_DiscreteStateType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackDiscState' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyDiscState); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyConstrState(SrcConstrStateData, DstConstrStateData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_ConstraintStateType), intent(in) :: SrcConstrStateData - type(Lidar_ConstraintStateType), intent(inout) :: DstConstrStateData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyConstrState' - ErrStat = ErrID_None - ErrMsg = '' - DstConstrStateData%DummyConstrState = SrcConstrStateData%DummyConstrState -end subroutine - -subroutine Lidar_DestroyConstrState(ConstrStateData, ErrStat, ErrMsg) - type(Lidar_ConstraintStateType), intent(inout) :: ConstrStateData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyConstrState' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackConstrState(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_ConstraintStateType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackConstrState' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyConstrState) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackConstrState(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_ConstraintStateType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackConstrState' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyConstrState); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyOtherState(SrcOtherStateData, DstOtherStateData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_OtherStateType), intent(in) :: SrcOtherStateData - type(Lidar_OtherStateType), intent(inout) :: DstOtherStateData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyOtherState' - ErrStat = ErrID_None - ErrMsg = '' - DstOtherStateData%DummyOtherState = SrcOtherStateData%DummyOtherState -end subroutine - -subroutine Lidar_DestroyOtherState(OtherStateData, ErrStat, ErrMsg) - type(Lidar_OtherStateType), intent(inout) :: OtherStateData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyOtherState' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackOtherState(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_OtherStateType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackOtherState' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyOtherState) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackOtherState(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_OtherStateType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackOtherState' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyOtherState); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyMisc(SrcMiscData, DstMiscData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_MiscVarType), intent(in) :: SrcMiscData - type(Lidar_MiscVarType), intent(inout) :: DstMiscData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyMisc' - ErrStat = ErrID_None - ErrMsg = '' - DstMiscData%DummyMiscVar = SrcMiscData%DummyMiscVar -end subroutine - -subroutine Lidar_DestroyMisc(MiscData, ErrStat, ErrMsg) - type(Lidar_MiscVarType), intent(inout) :: MiscData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyMisc' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackMisc(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_MiscVarType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackMisc' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyMiscVar) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackMisc(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_MiscVarType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackMisc' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyMiscVar); if (RegCheckErr(RF, RoutineName)) return + call RegUnpack(RF, OutData%NumMeasurements); if (RegCheckErr(RF, RoutineName)) return end subroutine subroutine Lidar_CopyInput(SrcInputData, DstInputData, CtrlCode, ErrStat, ErrMsg) diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index 9d9ec54e55..f1a4ddb342 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -1507,7 +1507,7 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, SED, BD, S - IF ( p_FAST%CompInflow == Module_IfW ) THEN !assign the number of gates to ServD + IF ( p_FAST%CompInflow == Module_IfW ) THEN ! assign the number of gates to ServD if (allocated(IfW%y%lidar%LidSpeed)) then ! make sure we have the array allocated before setting it CALL AllocAry(Init%InData_SrvD%LidSpeed, size(IfW%y%lidar%LidSpeed), 'Init%InData_SrvD%LidSpeed', errStat2, ErrMsg2) CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) diff --git a/modules/servodyn/src/BladedInterface_EX.f90 b/modules/servodyn/src/BladedInterface_EX.f90 index 37e77d0978..7c50a2d99e 100644 --- a/modules/servodyn/src/BladedInterface_EX.f90 +++ b/modules/servodyn/src/BladedInterface_EX.f90 @@ -552,36 +552,24 @@ end subroutine SetEXavrSWAP_Sensors !> Set the Lidar related sensor inputs !! avrSWAP(2001:2500) subroutine SetEXavrSWAP_LidarSensors() + integer(IntKi) :: nPts + ! in case something got set wrong, don't try to write beyond array if (size(dll_data%avrswap) < (LidarMsr_StartIdx + LidarMsr_MaxChan - 1) ) return - if (p%NumBeam == 0) return ! Nothing to set - if (p%SensorType > 0) then ! Set these here rather than overwrite every loop step in SensorType 1 or 3 + if (p%SensorType > 0) then dll_data%avrswap(LidarMsr_StartIdx) = real(p%SensorType,SiKi) ! Sensor Type dll_data%avrswap(LidarMsr_StartIdx+1) = real(p%NumBeam,SiKi) ! Number of Beams dll_data%avrswap(LidarMsr_StartIdx+2) = real(p%NumPulseGate,SiKi) ! Number of Pulse Gates dll_data%avrswap(LidarMsr_StartIdx+3) = p%URefLid ! Reference average wind speed for the lidar - endif - if (p%SensorType == 1) THEN - do I=1,min(p%NumBeam,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group - J=LidarMsr_StartIdx + 4 + (I-1) - dll_data%avrswap(J) = u%LidSpeed(I) ! Lidar Measured Wind Speeds - dll_data%avrswap(J+p%NumBeam) = u%MsrPositionsX(I) ! Lidar Measurement Points X - dll_data%avrswap(J+(p%NumBeam*2)) = u%MsrPositionsY(I) ! Lidar Measurement Points Y - dll_data%avrswap(J+(p%NumBeam*3)) = u%MsrPositionsZ(I) ! Lidar Measurement Points Z - enddo - elseif (p%SensorType == 2) THEN - dll_data%avrswap(LidarMsr_StartIdx+4) = u%LidSpeed(1) ! Lidar Measured Wind Speeds - dll_data%avrswap(LidarMsr_StartIdx+5) = u%MsrPositionsX(1) ! Lidar Measurement Points X - dll_data%avrswap(LidarMsr_StartIdx+6) = u%MsrPositionsY(1) ! Lidar Measurement Points Y - dll_data%avrswap(LidarMsr_StartIdx+7) = u%MsrPositionsZ(1) ! Lidar Measurement Points Z - elseif (p%SensorType == 3) THEN - do I=1,min(p%NumPulseGate,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group + + nPts = SIZE(u%MsrPositionsX) + do I=1,min(nPts,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group J=LidarMsr_StartIdx + 4 + (I-1) - dll_data%avrswap(J) = u%LidSpeed(I) ! Lidar Measured Wind Speeds - dll_data%avrswap(J+p%NumPulseGate) = u%MsrPositionsX(I) ! Lidar Measurement Points X - dll_data%avrswap(J+(p%NumPulseGate*2)) = u%MsrPositionsY(I) ! Lidar Measurement Points Y - dll_data%avrswap(J+(p%NumPulseGate*3)) = u%MsrPositionsZ(I) ! Lidar Measurement Points Z + dll_data%avrswap(J) = u%LidSpeed(I) ! Lidar Measured Wind Speeds + dll_data%avrswap(J+nPts) = u%MsrPositionsX(I) ! Lidar Measurement Points X + dll_data%avrswap(J+(nPts*2)) = u%MsrPositionsY(I) ! Lidar Measurement Points Y + dll_data%avrswap(J+(nPts*3)) = u%MsrPositionsZ(I) ! Lidar Measurement Points Z enddo endif end subroutine SetEXavrSWAP_LidarSensors From 1cfd03ff07ce1a51e1f5c21fb2a579b2569a8f50 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Tue, 1 Oct 2024 09:22:09 -0600 Subject: [PATCH 03/63] lidar: more cleanup - move all lidar parameter initialization into lidar_init - remove unused lidar_initInput values and move the one that is used into InflowWind initInput - remove unused variables - check that lidar arrays are allocated before initializing them (before call to SrvD_Init and before reading from IfW file) - move logic to check number of beams allowed into lidar module and only make sure the value is at least 1 before allocating so beam focal distances can be read/parsed with valid arrays sizes - make ConsiderHubMotion an integer again since I don't want to change the input files --- modules/aerodyn/src/AeroDyn_Inflow.f90 | 5 + modules/inflowwind/src/InflowWind.f90 | 24 +--- modules/inflowwind/src/InflowWind.txt | 4 +- modules/inflowwind/src/InflowWind_Subs.f90 | 22 ++-- modules/inflowwind/src/InflowWind_Types.f90 | 14 +-- modules/inflowwind/src/Lidar.f90 | 112 +++++++++++------- modules/inflowwind/src/Lidar.txt | 12 +- modules/inflowwind/src/Lidar_Types.f90 | 108 +---------------- modules/openfast-library/src/FAST_Library.f90 | 4 - .../openfast-library/src/FAST_Registry.txt | 1 - modules/openfast-library/src/FAST_Subs.f90 | 32 +++-- modules/openfast-library/src/FAST_Types.f90 | 4 - modules/servodyn/src/ServoDyn.f90 | 3 +- modules/servodyn/src/ServoDyn_Registry.txt | 5 +- modules/servodyn/src/ServoDyn_Types.f90 | 14 +-- 15 files changed, 120 insertions(+), 244 deletions(-) diff --git a/modules/aerodyn/src/AeroDyn_Inflow.f90 b/modules/aerodyn/src/AeroDyn_Inflow.f90 index 3f212d78e3..8da6e10758 100644 --- a/modules/aerodyn/src/AeroDyn_Inflow.f90 +++ b/modules/aerodyn/src/AeroDyn_Inflow.f90 @@ -392,6 +392,11 @@ subroutine ADI_InitInflowWind(Root, i_IW, u_AD, o_AD, IW, dt, InitOutData, errSt ! the average values for the entire wind profile must be calculated and stored (we don't know if OLAF ! is used until after AD_Init below). InitInData%BoxExceedAllow = .true. + + !bjj: what about these initialization inputs? + ! InitInData%HubPosition + ! InitInData%RadAvg + CALL InflowWind_Init( InitInData, IW%u, IW%p, & IW%x, IW%xd, IW%z, IW%OtherSt, & IW%y, IW%m, dt, InitOutData, errStat2, errMsg2 ) diff --git a/modules/inflowwind/src/InflowWind.f90 b/modules/inflowwind/src/InflowWind.f90 index d4e82820d6..58f9d1d4a6 100644 --- a/modules/inflowwind/src/InflowWind.f90 +++ b/modules/inflowwind/src/InflowWind.f90 @@ -186,26 +186,8 @@ SUBROUTINE InflowWind_Init( InitInp, InputGuess, p, ContStates, DiscStates, Cons endif ! initialize sensor data: - p%lidar%SensorType = InputFileData%SensorType - IF (InputFileData%SensorType == SensorType_None) THEN - p%lidar%NumBeam = 0 - p%lidar%NumPulseGate = 0 - ELSE - p%lidar%NumBeam = InputFileData%NumBeam - p%lidar%RotorApexOffsetPos = InputFileData%RotorApexOffsetPos - p%lidar%LidRadialVel = InputFileData%LidRadialVel - p%lidar%NumPulseGate = InputFileData%NumPulseGate - call move_alloc(InputFileData%FocalDistanceX, p%lidar%FocalDistanceX) - call move_alloc(InputFileData%FocalDistanceY, p%lidar%FocalDistanceY) - call move_alloc(InputFileData%FocalDistanceZ, p%lidar%FocalDistanceZ) - p%lidar%MeasurementInterval= InputFileData%MeasurementInterval - p%lidar%PulseSpacing = InputFileData%PulseSpacing - p%lidar%URefLid = InputFileData%URefLid - p%lidar%ConsiderHubMotion = InputFileData%ConsiderHubMotion - - CALL Lidar_Init( InitInp, InputGuess, p, y, m, TimeInterval, InitOutData, TmpErrStat, TmpErrMsg ) - if (Failed()) return - endif + CALL Lidar_Init( InitInp, InputFileData, InputGuess, p, y, m, TimeInterval, TmpErrStat, TmpErrMsg ) + if (Failed()) return ! If a summary file was requested, open it. IF ( InputFileData%SumPrint ) THEN @@ -219,7 +201,7 @@ SUBROUTINE InflowWind_Init( InitInp, InputGuess, p, ContStates, DiscStates, Cons ! Allocate the array for passing points CALL AllocAry( InputGuess%PositionXYZ, 3, InitInp%NumWindPoints, "Array of positions at which to find wind velocities", TmpErrStat, TmpErrMsg ); if (Failed()) return InputGuess%PositionXYZ = 0.0_ReKi - InputGuess%HubPosition = 0.0_ReKi + InputGuess%HubPosition = InitInp%HubPosition CALL Eye(InputGuess%HubOrientation,TmpErrStat,TmpErrMsg); if (Failed()) return ! Allocate the array for passing velocities out diff --git a/modules/inflowwind/src/InflowWind.txt b/modules/inflowwind/src/InflowWind.txt index 16f4ee0c97..0d8e864446 100644 --- a/modules/inflowwind/src/InflowWind.txt +++ b/modules/inflowwind/src/InflowWind.txt @@ -76,7 +76,7 @@ typedef ^ ^ ReKi PulseSpacin typedef ^ ^ ReKi MeasurementInterval - - - "Time between each measurement" s typedef ^ ^ ReKi URefLid - - - "Reference average wind speed for the lidar" m/s typedef ^ ^ LOGICAL LidRadialVel - - - "TRUE => return radial component, FALSE => return 'x' direction estimate" - -typedef ^ ^ LOGICAL ConsiderHubMotion - - - "whether or not the hub motion's impact on the Lidar measurement will be considered" - +typedef ^ ^ IntKi ConsiderHubMotion - - - "whether or not the hub motion's impact on the Lidar measurement will be considered" - typedef ^ ^ Grid3D_InitInputType FF - - - "scaling data" - @@ -92,7 +92,6 @@ typedef ^ ^ IntKi FilePassing typedef ^ ^ FileInfoType PassedFileInfo - - - "If we don't use the input file, pass everything through this [FilePassingMethod = 1]" - typedef ^ ^ InflowWind_InputFile PassedFileData - - - "If we don't use the input file, pass everything through this [FilePassingMethod = 2]" - typedef ^ ^ LOGICAL OutputAccel - .FALSE. - "Flag to output wind acceleration" - -typedef ^ ^ Lidar_InitInputType lidar - - - "InitInput for lidar data" - typedef ^ ^ Grid4D_InitInputType FDext - - - "InitInput for 4D external wind data" - typedef ^ ^ ReKi RadAvg - - - "Radius (from hub) used for averaging wind speed" - typedef ^ ^ IntKi MHK - - - "MHK turbine type switch" - @@ -100,6 +99,7 @@ typedef ^ ^ ReKi WtrDpth typedef ^ ^ ReKi MSL2SWL - - - "Mean sea level to still water level" m typedef ^ ^ LOGICAL BoxExceedAllow - .FALSE. - "Flag to allow Extrapolation winds outside box starting at this index (for OLAF wakes and LidarSim)" - typedef ^ ^ LOGICAL LidarEnabled - .false. - "Enable LiDAR for this instance of InflowWind? (FAST.Farm, ADI, and InflowWind driver/library are not compatible)" - +typedef ^ ^ ReKi HubPosition {3} - - "initial position of the hub (lidar mounted on hub) [0,0,HubHeight]" "m" # Init Output diff --git a/modules/inflowwind/src/InflowWind_Subs.f90 b/modules/inflowwind/src/InflowWind_Subs.f90 index f0ba82f95c..0824d2ff08 100644 --- a/modules/inflowwind/src/InflowWind_Subs.f90 +++ b/modules/inflowwind/src/InflowWind_Subs.f90 @@ -504,18 +504,14 @@ SUBROUTINE InflowWind_ParseInputFileInfo( InputFileData, InFileInfo, PriPath, In CALL ParseVar( InFileInfo, CurLine, "NumBeam", InputFileData%NumBeam, TmpErrStat, TmpErrMsg, UnEc ) if (Failed()) return - ! Before proceeding, make sure that NumBeam makes sense - IF ((InputFileData%SensorType == 1) .and. (InputFileData%NumBeam < 1 .OR. InputFileData%NumBeam > 5)) THEN - CALL SetErrStat( ErrID_Fatal, 'NumBeam must be greater than or equal to one and less than 6.', & - ErrStat, ErrMsg, RoutineName ) - RETURN - ELSE - ! Allocate space for the output location arrays: - CALL AllocAry( InputFileData%FocalDistanceX, InputFileData%NumBeam, 'FocalDistanceX', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) - CALL AllocAry( InputFileData%FocalDistanceY, InputFileData%NumBeam, 'FocalDistanceY', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) - CALL AllocAry( InputFileData%FocalDistanceZ, InputFileData%NumBeam, 'FocalDistanceZ', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) - if (Failed()) return - ENDIF + ! Before proceeding, make sure that NumBeam makes sense for array allocation + InputFileData%NumBeam = MAX(InputFileData%NumBeam, 1) + + ! Allocate space for the output location arrays: + CALL AllocAry( InputFileData%FocalDistanceX, InputFileData%NumBeam, 'FocalDistanceX', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) + CALL AllocAry( InputFileData%FocalDistanceY, InputFileData%NumBeam, 'FocalDistanceY', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) + CALL AllocAry( InputFileData%FocalDistanceZ, InputFileData%NumBeam, 'FocalDistanceZ', TmpErrStat, TmpErrMsg ); CALL SetErrStat( TmpErrStat, TmpErrMsg, ErrStat, ErrMsg, RoutineName ) + if (Failed()) return ! Focal Distance X CALL ParseAry( InFileInfo, CurLine, 'FocalDistanceX', InputFileData%FocalDistanceX, InputFileData%NumBeam, TmpErrStat, TmpErrMsg, UnEc ) @@ -647,7 +643,7 @@ SUBROUTINE InflowWind_ValidateInput( InitInp, InputFileData, ErrStat, ErrMsg ) return end if - if (InitInp%lidar%SensorType /= SensorType_None) then + if (InputFileData%SensorType /= SensorType_None) then call SetErrStat(ErrID_Fatal, 'InflowWind can not perform linearization with the lidar module enabled.', ErrStat, ErrMsg, RoutineName) return end if diff --git a/modules/inflowwind/src/InflowWind_Types.f90 b/modules/inflowwind/src/InflowWind_Types.f90 index 7c0dcfeee7..58dd02a99e 100644 --- a/modules/inflowwind/src/InflowWind_Types.f90 +++ b/modules/inflowwind/src/InflowWind_Types.f90 @@ -94,7 +94,7 @@ MODULE InflowWind_Types REAL(ReKi) :: MeasurementInterval = 0.0_ReKi !< Time between each measurement [s] REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] LOGICAL :: LidRadialVel = .false. !< TRUE => return radial component, FALSE => return 'x' direction estimate [-] - LOGICAL :: ConsiderHubMotion = .false. !< whether or not the hub motion's impact on the Lidar measurement will be considered [-] + INTEGER(IntKi) :: ConsiderHubMotion = 0_IntKi !< whether or not the hub motion's impact on the Lidar measurement will be considered [-] TYPE(Grid3D_InitInputType) :: FF !< scaling data [-] END TYPE InflowWind_InputFile ! ======================= @@ -111,7 +111,6 @@ MODULE InflowWind_Types TYPE(FileInfoType) :: PassedFileInfo !< If we don't use the input file, pass everything through this [FilePassingMethod = 1] [-] TYPE(InflowWind_InputFile) :: PassedFileData !< If we don't use the input file, pass everything through this [FilePassingMethod = 2] [-] LOGICAL :: OutputAccel = .FALSE. !< Flag to output wind acceleration [-] - TYPE(Lidar_InitInputType) :: lidar !< InitInput for lidar data [-] TYPE(Grid4D_InitInputType) :: FDext !< InitInput for 4D external wind data [-] REAL(ReKi) :: RadAvg = 0.0_ReKi !< Radius (from hub) used for averaging wind speed [-] INTEGER(IntKi) :: MHK = 0_IntKi !< MHK turbine type switch [-] @@ -119,6 +118,7 @@ MODULE InflowWind_Types REAL(ReKi) :: MSL2SWL = 0.0_ReKi !< Mean sea level to still water level [m] LOGICAL :: BoxExceedAllow = .FALSE. !< Flag to allow Extrapolation winds outside box starting at this index (for OLAF wakes and LidarSim) [-] LOGICAL :: LidarEnabled = .false. !< Enable LiDAR for this instance of InflowWind? (FAST.Farm, ADI, and InflowWind driver/library are not compatible) [-] + REAL(ReKi) , DIMENSION(1:3) :: HubPosition = 0.0_ReKi !< initial position of the hub (lidar mounted on hub) [0,0,HubHeight] [m] END TYPE InflowWind_InitInputType ! ======================= ! ========= InflowWind_InitOutputType ======= @@ -511,9 +511,6 @@ subroutine InflowWind_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return DstInitInputData%OutputAccel = SrcInitInputData%OutputAccel - call Lidar_CopyInitInput(SrcInitInputData%lidar, DstInitInputData%lidar, CtrlCode, ErrStat2, ErrMsg2) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - if (ErrStat >= AbortErrLev) return call InflowWind_IO_CopyGrid4D_InitInputType(SrcInitInputData%FDext, DstInitInputData%FDext, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return @@ -523,6 +520,7 @@ subroutine InflowWind_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode DstInitInputData%MSL2SWL = SrcInitInputData%MSL2SWL DstInitInputData%BoxExceedAllow = SrcInitInputData%BoxExceedAllow DstInitInputData%LidarEnabled = SrcInitInputData%LidarEnabled + DstInitInputData%HubPosition = SrcInitInputData%HubPosition end subroutine subroutine InflowWind_DestroyInitInput(InitInputData, ErrStat, ErrMsg) @@ -540,6 +538,8 @@ subroutine InflowWind_DestroyInitInput(InitInputData, ErrStat, ErrMsg) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call Lidar_DestroyInitInput(InitInputData%lidar, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + call NWTC_Library_DestroyFileInfoType(InitInputData%WindType2Info, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call InflowWind_IO_DestroyGrid4D_InitInputType(InitInputData%FDext, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) end subroutine @@ -560,7 +560,6 @@ subroutine InflowWind_PackInitInput(RF, Indata) call NWTC_Library_PackFileInfoType(RF, InData%PassedFileInfo) call InflowWind_PackInputFile(RF, InData%PassedFileData) call RegPack(RF, InData%OutputAccel) - call Lidar_PackInitInput(RF, InData%lidar) call InflowWind_IO_PackGrid4D_InitInputType(RF, InData%FDext) call RegPack(RF, InData%RadAvg) call RegPack(RF, InData%MHK) @@ -568,6 +567,7 @@ subroutine InflowWind_PackInitInput(RF, Indata) call RegPack(RF, InData%MSL2SWL) call RegPack(RF, InData%BoxExceedAllow) call RegPack(RF, InData%LidarEnabled) + call RegPack(RF, InData%HubPosition) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -587,7 +587,6 @@ subroutine InflowWind_UnPackInitInput(RF, OutData) call NWTC_Library_UnpackFileInfoType(RF, OutData%PassedFileInfo) ! PassedFileInfo call InflowWind_UnpackInputFile(RF, OutData%PassedFileData) ! PassedFileData call RegUnpack(RF, OutData%OutputAccel); if (RegCheckErr(RF, RoutineName)) return - call Lidar_UnpackInitInput(RF, OutData%lidar) ! lidar call InflowWind_IO_UnpackGrid4D_InitInputType(RF, OutData%FDext) ! FDext call RegUnpack(RF, OutData%RadAvg); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%MHK); if (RegCheckErr(RF, RoutineName)) return @@ -595,6 +594,7 @@ subroutine InflowWind_UnPackInitInput(RF, OutData) call RegUnpack(RF, OutData%MSL2SWL); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%BoxExceedAllow); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%LidarEnabled); if (RegCheckErr(RF, RoutineName)) return + call RegUnpack(RF, OutData%HubPosition); if (RegCheckErr(RF, RoutineName)) return end subroutine subroutine InflowWind_CopyInitOutput(SrcInitOutputData, DstInitOutputData, CtrlCode, ErrStat, ErrMsg) diff --git a/modules/inflowwind/src/Lidar.f90 b/modules/inflowwind/src/Lidar.f90 index 35cd42d128..f0dd9a1e71 100644 --- a/modules/inflowwind/src/Lidar.f90 +++ b/modules/inflowwind/src/Lidar.f90 @@ -62,9 +62,10 @@ MODULE Lidar !! The parameters are set here and not changed during the simulation. !! The initial states and initial guess for the input are defined. !! note that we're calling this with the InflowWind data types, so that data is INOUT instead of OUT -SUBROUTINE Lidar_Init( InitInp, u, p, y, m, Interval, InitOut, ErrStat, ErrMsg ) +SUBROUTINE Lidar_Init( InitInp, InputFileData, u, p, y, m, Interval, ErrStat, ErrMsg ) TYPE(InflowWind_InitInputType), INTENT(IN ) :: InitInp !< Input data for initialization routine + TYPE(InflowWind_InputFile), INTENT(INOUT) :: InputFileData !< Data from input file TYPE(InflowWind_InputType), INTENT(INOUT) :: u !< An initial guess for the input; input mesh must be defined TYPE(InflowWind_ParameterType), INTENT(INOUT) :: p !< Parameters TYPE(InflowWind_MiscVarType), INTENT(INOUT) :: m !< Misc variables for optimization (not copied in glue code) @@ -76,16 +77,15 @@ SUBROUTINE Lidar_Init( InitInp, u, p, y, m, Interval, InitOut, ErrStat, ErrMsg ) !! Input is the suggested time from the glue code; !! Output is the actual coupling interval that will be used !! by the glue code. - TYPE(InflowWind_InitOutputType), INTENT(INOUT) :: InitOut !< Output for initialization routine INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None ! Temporary variables for error handling - INTEGER(IntKi) :: TmpErrStat !< temporary error message - CHARACTER(ErrMsgLen) :: TmpErrMsg + INTEGER(IntKi) :: TmpErrStat !< temporary error message + CHARACTER(ErrMsgLen) :: TmpErrMsg ! local variables - INTEGER(IntKi) :: IBeam + INTEGER(IntKi) :: IBeam INTEGER(IntKi) :: ErrStat2 ! temporary Error status of the operation CHARACTER(ErrMsgLen) :: ErrMsg2 ! temporary Error message if ErrStat /= ErrID_None @@ -98,56 +98,73 @@ SUBROUTINE Lidar_Init( InitInp, u, p, y, m, Interval, InitOut, ErrStat, ErrMsg ) ErrStat = ErrID_None ErrMsg = "" - if (p%lidar%SensorType == SensorType_None) then + p%lidar%SensorType = InputFileData%SensorType + if (p%lidar%SensorType == SensorType_None) then p%lidar%NumPulseGate = 0 p%lidar%NumBeam = 0 return - elseif (p%lidar%SensorType == SensorType_SinglePoint) then - p%lidar%NumPulseGate = 1 - - if (p%lidar%NumBeam < 1) then - call SetErrStat( ErrID_Fatal, 'NumBeam must be greater than 0 for single-point beams.', ErrStat, ErrMsg, RoutineName ) - return - end if else - - ! Make sure that multiple beams are only used when using single-point beams - if ( p%lidar%NumBeam > 1 ) then - call SetErrStat( ErrID_Fatal, 'Multiple beams can only be used with single point lidar', ErrStat, ErrMsg, RoutineName ) - return - endif - p%lidar%NumBeam = 1 - - ! variables for both pulsed and continuous-wave lidars - p%lidar%SpatialRes = 0.5_ReKi*p%lidar%URefLid*Interval - p%lidar%RayRangeSq = (Pi*(BeamRad**2)/LsrWavLen)**2 - - if (p%lidar%SensorType == SensorType_ContinuousLidar) then + p%lidar%NumBeam = InputFileData%NumBeam + p%lidar%RotorApexOffsetPos = InputFileData%RotorApexOffsetPos + p%lidar%LidRadialVel = InputFileData%LidRadialVel + p%lidar%NumPulseGate = InputFileData%NumPulseGate + call move_alloc(InputFileData%FocalDistanceX, p%lidar%FocalDistanceX) + call move_alloc(InputFileData%FocalDistanceY, p%lidar%FocalDistanceY) + call move_alloc(InputFileData%FocalDistanceZ, p%lidar%FocalDistanceZ) + p%lidar%MeasurementInterval= InputFileData%MeasurementInterval + p%lidar%PulseSpacing = InputFileData%PulseSpacing + p%lidar%URefLid = InputFileData%URefLid + p%lidar%ConsiderHubMotion = InputFileData%ConsiderHubMotion + + if (p%lidar%SensorType == SensorType_SinglePoint) then p%lidar%NumPulseGate = 1 - p%lidar%WtFnTrunc = 0.02_ReKi - elseif (p%lidar%SensorType == SensorType_PulsedLidar) then + + if ( (p%lidar%NumBeam < 1 .OR. p%lidar%NumBeam > 5) ) then + call SetErrStat( ErrID_Fatal, 'NumBeam must be greater than zero and less than 6.', ErrStat, ErrMsg, RoutineName ) + return + endif + + else - ! Make sure that NumPulseGate makes sense - if ( (p%lidar%NumPulseGate < 1 .OR. p%lidar%NumPulseGate > 5) ) then - call SetErrStat( ErrID_Fatal, 'NumPulseGate must be greater than zero and less than 6.', ErrStat, ErrMsg, RoutineName ) + ! Make sure that multiple beams are only used when using single-point beams + if ( p%lidar%NumBeam > 1 ) then + call SetErrStat( ErrID_Fatal, 'Multiple beams can only be used with single point lidar', ErrStat, ErrMsg, RoutineName ) return endif - p%lidar%WtFnTrunc = 0.01_ReKi + p%lidar%NumBeam = 1 + + ! variables for both pulsed and continuous-wave lidars + p%lidar%SpatialRes = 0.5_ReKi*p%lidar%URefLid*Interval + p%lidar%RayRangeSq = (Pi*(BeamRad**2)/LsrWavLen)**2 + + if (p%lidar%SensorType == SensorType_ContinuousLidar) then + p%lidar%NumPulseGate = 1 + p%lidar%WtFnTrunc = 0.02_ReKi + elseif (p%lidar%SensorType == SensorType_PulsedLidar) then + + ! Make sure that NumPulseGate makes sense + if ( (p%lidar%NumPulseGate < 1 .OR. p%lidar%NumPulseGate > 5) ) then + call SetErrStat( ErrID_Fatal, 'NumPulseGate must be greater than zero and less than 6.', ErrStat, ErrMsg, RoutineName ) + return + endif + p%lidar%WtFnTrunc = 0.01_ReKi - ! values for the WindCube - p%lidar%DeltaR = 30.0_ReKi - ! p%lidar%PulseRangeOne = 50.0 ReKi ! Replaced by the focal distance; bjj: it's used in an IF statement, so initializing below: - p%lidar%PulseRangeOne = 0.0_ReKi + ! values for the WindCube + p%lidar%DeltaR = 30.0_ReKi + ! p%lidar%PulseRangeOne = 50.0 ReKi ! Replaced by the focal distance; bjj: it's used in an IF statement, so initializing below: + p%lidar%PulseRangeOne = 0.0_ReKi - p%lidar%r_p = p%lidar%DeltaR/(2.0_ReKi*SQRT(LOG(2.0_ReKi))) + p%lidar%r_p = p%lidar%DeltaR/(2.0_ReKi*SQRT(LOG(2.0_ReKi))) - else - call SetErrStat(ErrID_Fatal, "Invalid sensor type.", ErrStat, ErrMsg, RoutineName) - return + else + call SetErrStat(ErrID_Fatal, "Invalid sensor type.", ErrStat, ErrMsg, RoutineName) + return + end if end if - endif + end if ! no lidar - p%lidar%LidPosition = InitInp%lidar%HubPosition + + p%lidar%LidPosition = InitInp%HubPosition p%lidar%NumMeasurements = MAX(p%lidar%NumBeam,p%lidar%NumPulseGate) !note, this is at least 1 for every case (except SensorType_None, which cannot get to this place) CALL AllocAry(p%lidar%MsrPosition , 3, p%lidar%NumBeam, 'Array for measurement coordinates (per beam)', TmpErrStat, TmpErrMsg ) @@ -306,7 +323,7 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, y, m, ErrStat, ErrMsg ) ENDIF LidPosition = p%lidar%LidPosition + p%lidar%RotorApexOffsetPos ! lidar offset-from-rotor-apex position - IF (p%lidar%ConsiderHubMotion) THEN + IF (p%lidar%ConsiderHubMotion /= 0) THEN LidPosition = LidPosition + (/ u%lidar%HubDisplacementX, u%lidar%HubDisplacementY, u%lidar%HubDisplacementZ /) ! rotor apex position (absolute) END IF @@ -452,21 +469,24 @@ SUBROUTINE Lidar_CalcOutput( t, u, p, y, m, ErrStat, ErrMsg ) ELSE !p%SensorType == SensorType_PulsedLidar IBeam = 1 + !bjj: note that u%lidar%PulseLidEl and u%lidar%PulseLidAz are not set in the calling code, so they are always 0 LidDirUnVec(1) = -1*COS(u%lidar%PulseLidEl) LidDirUnVec(2) = SIN(u%lidar%PulseLidEl)*SIN(u%lidar%PulseLidAz) LidDirUnVec(3) = SIN(u%lidar%PulseLidEl)*COS(u%lidar%PulseLidAz) DO IRangeGt = 1,p%lidar%NumPulseGate + !bjj: do the y- and z- components of PositionXYZ make sense here? It looks like they assume p%lidar%MsrPosition(2:3,IBeam) are zero + LidPosition(2) = LidPosition(2) + p%lidar%MsrPosition(2,IBeam) LidPosition(3) = LidPosition(3) + p%lidar%MsrPosition(3,IBeam) - !get lidar speed at the focal point to see if it is out of bounds - PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,IBeam) - (IRangeGt-1)*p%lidar%PulseSpacing) + !get lidar speed at the focal point to see if it is out of bounds; bjj: this equation looks strange to me. Note how the X component is used to modify Y and Z. + PositionXYZ(:,1) = LidPosition + LidDirUnVec*(-p%lidar%MsrPosition(1,IBeam) - (IRangeGt-1)*p%lidar%PulseSpacing) !bjj: I don't think this makes any sense in the Y and Z components. Will modify MsrPositionsY and MsrPositionsZ y%lidar%MsrPositionsX(IRangeGt) = PositionXYZ(1,1) - y%lidar%MsrPositionsY(IRangeGt) = PositionXYZ(2,1) ! was LidPosition(2) + p%lidar%MsrPosition(2,IBeam) + y%lidar%MsrPositionsY(IRangeGt) = PositionXYZ(2,1) ! was LidPosition(2) + p%lidar%MsrPosition(2,IBeam), adding p%lidar%MsrPosition(2,IBeam) to the position AGAIN y%lidar%MsrPositionsZ(IRangeGt) = PositionXYZ(3,1) ! was LidPosition(3) + p%lidar%MsrPosition(3,IBeam) CALL IfW_FlowField_GetVelAcc(p%FlowField, 0, t, PositionXYZ(:,1:1), VelocityUVW(:,1:1), AccelUVW, ErrStat2, ErrMsg2, BoxExceedAllow=.true.) diff --git a/modules/inflowwind/src/Lidar.txt b/modules/inflowwind/src/Lidar.txt index 14fdbe97e6..7bdc3d63c0 100644 --- a/modules/inflowwind/src/Lidar.txt +++ b/modules/inflowwind/src/Lidar.txt @@ -14,16 +14,6 @@ param Lidar - IntKi SensorType_SinglePoint - 1 - - param ^ - IntKi SensorType_ContinuousLidar - 2 - - param ^ - IntKi SensorType_PulsedLidar - 3 - - -# ..... LIDAR_InitInputType data ....................................................................................................... -typedef ^ Lidar_InitInputType IntKi SensorType - SensorType_None - "SensorType_* parameter" - -typedef ^ Lidar_InitInputType DbKi Tmax - - - "the length of the simulation" "s" -typedef ^ Lidar_InitInputType ReKi RotorApexOffsetPos {3} - - "position of the lidar unit relative to the rotor apex of rotation" "m" -typedef ^ Lidar_InitInputType ReKi HubPosition {3} - - "initial position of the hub (lidar mounted on hub) [0,0,HubHeight]" "m" -typedef ^ Lidar_InitInputType IntKi NumPulseGate - - - "the number of range gates to return wind speeds at" - -typedef ^ Lidar_InitInputType LOGICAL LidRadialVel - - - "TRUE => return radial component, FALSE => return 'x' direction estimate" - - -# ..... LIDAR_InitInputType data ....................................................................................................... -typedef ^ Lidar_InitOutputType ReKi DummyInitOut - # ..... LIDAR_ParameterType data ....................................................................................................... typedef ^ Lidar_ParameterType IntKi NumPulseGate - - - "the number of range gates to return wind speeds at; pulsed lidar only" - @@ -46,7 +36,7 @@ typedef ^ Lidar_ParameterType ReKi FocalDistanceZ : - - "LIDAR typedef ^ Lidar_ParameterType ReKi MsrPosition {:}{:} - - "Position of the desired wind measurement, per beam (was XMsrPt, YMsrPt, ZMsrPt)" "m" typedef ^ Lidar_ParameterType ReKi PulseSpacing - - - "Distance between range gates" "m" typedef ^ Lidar_ParameterType ReKi URefLid - - - "Reference average wind speed for the lidar" "m/s" -typedef ^ Lidar_ParameterType LOGICAL ConsiderHubMotion - - - "Whether to consider the hub motion's impact on the Lidar measurement" - +typedef ^ Lidar_ParameterType IntKi ConsiderHubMotion - - - "Whether to consider the hub motion's impact on the Lidar measurement" - typedef ^ Lidar_ParameterType ReKi MeasurementInterval - - - "Time steps between lidar measurements" "s" typedef ^ Lidar_ParameterType ReKi LidPosition {3} - - "Position of the Lidar unit (was XLidPt, YLidPt, ZLidPt)" "m" typedef ^ Lidar_ParameterType IntKi NumMeasurements - 0 - "Number of measurements output" - diff --git a/modules/inflowwind/src/Lidar_Types.f90 b/modules/inflowwind/src/Lidar_Types.f90 index c4e0fa580b..490316f137 100644 --- a/modules/inflowwind/src/Lidar_Types.f90 +++ b/modules/inflowwind/src/Lidar_Types.f90 @@ -37,21 +37,6 @@ MODULE Lidar_Types INTEGER(IntKi), PUBLIC, PARAMETER :: SensorType_SinglePoint = 1 INTEGER(IntKi), PUBLIC, PARAMETER :: SensorType_ContinuousLidar = 2 INTEGER(IntKi), PUBLIC, PARAMETER :: SensorType_PulsedLidar = 3 -! ========= Lidar_InitInputType ======= - TYPE, PUBLIC :: Lidar_InitInputType - INTEGER(IntKi) :: SensorType = SensorType_None !< SensorType_* parameter [-] - REAL(DbKi) :: Tmax = 0.0_R8Ki !< the length of the simulation [s] - REAL(ReKi) , DIMENSION(1:3) :: RotorApexOffsetPos = 0.0_ReKi !< position of the lidar unit relative to the rotor apex of rotation [m] - REAL(ReKi) , DIMENSION(1:3) :: HubPosition = 0.0_ReKi !< initial position of the hub (lidar mounted on hub) [0,0,HubHeight] [m] - INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< the number of range gates to return wind speeds at [-] - LOGICAL :: LidRadialVel = .false. !< TRUE => return radial component, FALSE => return 'x' direction estimate [-] - END TYPE Lidar_InitInputType -! ======================= -! ========= Lidar_InitOutputType ======= - TYPE, PUBLIC :: Lidar_InitOutputType - REAL(ReKi) :: DummyInitOut = 0.0_ReKi - END TYPE Lidar_InitOutputType -! ======================= ! ========= Lidar_ParameterType ======= TYPE, PUBLIC :: Lidar_ParameterType INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< the number of range gates to return wind speeds at; pulsed lidar only [-] @@ -74,7 +59,7 @@ MODULE Lidar_Types REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MsrPosition !< Position of the desired wind measurement, per beam (was XMsrPt, YMsrPt, ZMsrPt) [m] REAL(ReKi) :: PulseSpacing = 0.0_ReKi !< Distance between range gates [m] REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] - LOGICAL :: ConsiderHubMotion = .false. !< Whether to consider the hub motion's impact on the Lidar measurement [-] + INTEGER(IntKi) :: ConsiderHubMotion = 0_IntKi !< Whether to consider the hub motion's impact on the Lidar measurement [-] REAL(ReKi) :: MeasurementInterval = 0.0_ReKi !< Time steps between lidar measurements [s] REAL(ReKi) , DIMENSION(1:3) :: LidPosition = 0.0_ReKi !< Position of the Lidar unit (was XLidPt, YLidPt, ZLidPt) [m] INTEGER(IntKi) :: NumMeasurements = 0 !< Number of measurements output [-] @@ -100,97 +85,6 @@ MODULE Lidar_Types ! ======================= CONTAINS -subroutine Lidar_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_InitInputType), intent(in) :: SrcInitInputData - type(Lidar_InitInputType), intent(inout) :: DstInitInputData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyInitInput' - ErrStat = ErrID_None - ErrMsg = '' - DstInitInputData%SensorType = SrcInitInputData%SensorType - DstInitInputData%Tmax = SrcInitInputData%Tmax - DstInitInputData%RotorApexOffsetPos = SrcInitInputData%RotorApexOffsetPos - DstInitInputData%HubPosition = SrcInitInputData%HubPosition - DstInitInputData%NumPulseGate = SrcInitInputData%NumPulseGate - DstInitInputData%LidRadialVel = SrcInitInputData%LidRadialVel -end subroutine - -subroutine Lidar_DestroyInitInput(InitInputData, ErrStat, ErrMsg) - type(Lidar_InitInputType), intent(inout) :: InitInputData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyInitInput' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackInitInput(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_InitInputType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackInitInput' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%SensorType) - call RegPack(RF, InData%Tmax) - call RegPack(RF, InData%RotorApexOffsetPos) - call RegPack(RF, InData%HubPosition) - call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%LidRadialVel) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackInitInput(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_InitInputType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackInitInput' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%Tmax); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%RotorApexOffsetPos); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%HubPosition); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%LidRadialVel); if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_CopyInitOutput(SrcInitOutputData, DstInitOutputData, CtrlCode, ErrStat, ErrMsg) - type(Lidar_InitOutputType), intent(in) :: SrcInitOutputData - type(Lidar_InitOutputType), intent(inout) :: DstInitOutputData - integer(IntKi), intent(in ) :: CtrlCode - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_CopyInitOutput' - ErrStat = ErrID_None - ErrMsg = '' - DstInitOutputData%DummyInitOut = SrcInitOutputData%DummyInitOut -end subroutine - -subroutine Lidar_DestroyInitOutput(InitOutputData, ErrStat, ErrMsg) - type(Lidar_InitOutputType), intent(inout) :: InitOutputData - integer(IntKi), intent( out) :: ErrStat - character(*), intent( out) :: ErrMsg - character(*), parameter :: RoutineName = 'Lidar_DestroyInitOutput' - ErrStat = ErrID_None - ErrMsg = '' -end subroutine - -subroutine Lidar_PackInitOutput(RF, Indata) - type(RegFile), intent(inout) :: RF - type(Lidar_InitOutputType), intent(in) :: InData - character(*), parameter :: RoutineName = 'Lidar_PackInitOutput' - if (RF%ErrStat >= AbortErrLev) return - call RegPack(RF, InData%DummyInitOut) - if (RegCheckErr(RF, RoutineName)) return -end subroutine - -subroutine Lidar_UnPackInitOutput(RF, OutData) - type(RegFile), intent(inout) :: RF - type(Lidar_InitOutputType), intent(inout) :: OutData - character(*), parameter :: RoutineName = 'Lidar_UnPackInitOutput' - if (RF%ErrStat /= ErrID_None) return - call RegUnpack(RF, OutData%DummyInitOut); if (RegCheckErr(RF, RoutineName)) return -end subroutine - subroutine Lidar_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg) type(Lidar_ParameterType), intent(in) :: SrcParamData type(Lidar_ParameterType), intent(inout) :: DstParamData diff --git a/modules/openfast-library/src/FAST_Library.f90 b/modules/openfast-library/src/FAST_Library.f90 index 685a2adc03..e3ff240d7f 100644 --- a/modules/openfast-library/src/FAST_Library.f90 +++ b/modules/openfast-library/src/FAST_Library.f90 @@ -400,10 +400,6 @@ subroutine FAST_SetExternalInputs(iTurb, NumInputs_c, InputAry, m_FAST) m_FAST%ExternInput%CableDeltaL = InputAry(12:31) m_FAST%ExternInput%CableDeltaLdot = InputAry(32:51) - IF ( NumInputs_c > NumFixedInputs ) THEN ! NumFixedInputs is the fixed number of inputs - IF ( NumInputs_c == NumFixedInputs + 3 ) & - m_FAST%ExternInput%LidarFocus = InputAry(52:54) - END IF end subroutine FAST_SetExternalInputs !================================================================================================================================== diff --git a/modules/openfast-library/src/FAST_Registry.txt b/modules/openfast-library/src/FAST_Registry.txt index 7d1caaafc1..ddec6be1fb 100644 --- a/modules/openfast-library/src/FAST_Registry.txt +++ b/modules/openfast-library/src/FAST_Registry.txt @@ -801,7 +801,6 @@ typedef ^ FAST_ExternInputType ReKi YawRateCom - - - "yaw rate command from Simu typedef ^ FAST_ExternInputType ReKi BlPitchCom 3 - 2pi "blade pitch commands from Simulink/Labview" "rad" typedef ^ FAST_ExternInputType ReKi BlAirfoilCom 3 - - "blade airfoil commands from Simulink/Labview" "-" typedef ^ FAST_ExternInputType ReKi HSSBrFrac - - - "Fraction of full braking torque: 0 (off) <= HSSBrFrac <= 1 (full) from Simulink or LabVIEW" -typedef ^ FAST_ExternInputType ReKi LidarFocus 3 - - "lidar focus (relative to lidar location)" m typedef ^ FAST_ExternInputType ReKi CableDeltaL {20} - - "Cable control DeltaL" m typedef ^ FAST_ExternInputType ReKi CableDeltaLdot {20} - - "Cable control DeltaLdot" m/s diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index f1a4ddb342..afd4d27988 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -493,15 +493,14 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, SED, BD, S ! lidar Init%InData_IfW%LidarEnabled = .true. ! allowed with OF, but not FF - Init%InData_IfW%lidar%Tmax = p_FAST%TMax if (p_FAST%CompElast == Module_SED) then - Init%InData_IfW%lidar%HubPosition = SED%y%HubPtMotion%Position(:,1) + Init%InData_IfW%HubPosition = SED%y%HubPtMotion%Position(:,1) Init%InData_IfW%RadAvg = Init%OutData_SED%BladeLength elseif ( p_FAST%CompElast == Module_ED ) then - Init%InData_IfW%lidar%HubPosition = ED%y%HubPtMotion%Position(:,1) + Init%InData_IfW%HubPosition = ED%y%HubPtMotion%Position(:,1) Init%InData_IfW%RadAvg = Init%OutData_ED%BladeLength elseif ( p_FAST%CompElast == Module_BD ) then - Init%InData_IfW%lidar%HubPosition = ED%y%HubPtMotion%Position(:,1) + Init%InData_IfW%HubPosition = ED%y%HubPtMotion%Position(:,1) Init%InData_IfW%RadAvg = TwoNorm(BD%y(1)%BldMotion%Position(:,1) - BD%y(1)%BldMotion%Position(:,BD%y(1)%BldMotion%Nnodes)) end if @@ -1510,28 +1509,43 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, SED, BD, S IF ( p_FAST%CompInflow == Module_IfW ) THEN ! assign the number of gates to ServD if (allocated(IfW%y%lidar%LidSpeed)) then ! make sure we have the array allocated before setting it CALL AllocAry(Init%InData_SrvD%LidSpeed, size(IfW%y%lidar%LidSpeed), 'Init%InData_SrvD%LidSpeed', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + IF (ErrStat >= AbortErrLev) THEN + CALL Cleanup() + RETURN + END IF Init%InData_SrvD%LidSpeed = IfW%y%lidar%LidSpeed endif if (allocated(IfW%y%lidar%MsrPositionsX)) then ! make sure we have the array allocated before setting it CALL AllocAry(Init%InData_SrvD%MsrPositionsX, size(IfW%y%lidar%MsrPositionsX), 'Init%InData_SrvD%MsrPositionsX', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + IF (ErrStat >= AbortErrLev) THEN + CALL Cleanup() + RETURN + END IF Init%InData_SrvD%MsrPositionsX = IfW%y%lidar%MsrPositionsX endif if (allocated(IfW%y%lidar%MsrPositionsY)) then ! make sure we have the array allocated before setting it CALL AllocAry(Init%InData_SrvD%MsrPositionsY, size(IfW%y%lidar%MsrPositionsY), 'Init%InData_SrvD%MsrPositionsY', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + IF (ErrStat >= AbortErrLev) THEN + CALL Cleanup() + RETURN + END IF Init%InData_SrvD%MsrPositionsY = IfW%y%lidar%MsrPositionsY endif if (allocated(IfW%y%lidar%MsrPositionsZ)) then ! make sure we have the array allocated before setting it CALL AllocAry(Init%InData_SrvD%MsrPositionsZ, size(IfW%y%lidar%MsrPositionsZ), 'Init%InData_SrvD%MsrPositionsZ', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + IF (ErrStat >= AbortErrLev) THEN + CALL Cleanup() + RETURN + END IF Init%InData_SrvD%MsrPositionsZ = IfW%y%lidar%MsrPositionsZ endif Init%InData_SrvD%SensorType = IfW%p%lidar%SensorType Init%InData_SrvD%NumBeam = IfW%p%lidar%NumBeam Init%InData_SrvD%NumPulseGate = IfW%p%lidar%NumPulseGate - Init%InData_SrvD%PulseSpacing = IfW%p%lidar%PulseSpacing END IF diff --git a/modules/openfast-library/src/FAST_Types.f90 b/modules/openfast-library/src/FAST_Types.f90 index 5de2f68fc6..06061ca975 100644 --- a/modules/openfast-library/src/FAST_Types.f90 +++ b/modules/openfast-library/src/FAST_Types.f90 @@ -807,7 +807,6 @@ MODULE FAST_Types REAL(ReKi) , DIMENSION(1:3) :: BlPitchCom = 0.0_ReKi !< blade pitch commands from Simulink/Labview [rad] REAL(ReKi) , DIMENSION(1:3) :: BlAirfoilCom = 0.0_ReKi !< blade airfoil commands from Simulink/Labview [-] REAL(ReKi) :: HSSBrFrac = 0.0_ReKi !< Fraction of full braking torque: 0 (off) <= HSSBrFrac <= 1 (full) from Simulink or LabVIEW [-] - REAL(ReKi) , DIMENSION(1:3) :: LidarFocus = 0.0_ReKi !< lidar focus (relative to lidar location) [m] REAL(ReKi) , DIMENSION(1:20) :: CableDeltaL = 0.0_ReKi !< Cable control DeltaL [m] REAL(ReKi) , DIMENSION(1:20) :: CableDeltaLdot = 0.0_ReKi !< Cable control DeltaLdot [m/s] END TYPE FAST_ExternInputType @@ -14636,7 +14635,6 @@ subroutine FAST_CopyExternInputType(SrcExternInputTypeData, DstExternInputTypeDa DstExternInputTypeData%BlPitchCom = SrcExternInputTypeData%BlPitchCom DstExternInputTypeData%BlAirfoilCom = SrcExternInputTypeData%BlAirfoilCom DstExternInputTypeData%HSSBrFrac = SrcExternInputTypeData%HSSBrFrac - DstExternInputTypeData%LidarFocus = SrcExternInputTypeData%LidarFocus DstExternInputTypeData%CableDeltaL = SrcExternInputTypeData%CableDeltaL DstExternInputTypeData%CableDeltaLdot = SrcExternInputTypeData%CableDeltaLdot end subroutine @@ -14662,7 +14660,6 @@ subroutine FAST_PackExternInputType(RF, Indata) call RegPack(RF, InData%BlPitchCom) call RegPack(RF, InData%BlAirfoilCom) call RegPack(RF, InData%HSSBrFrac) - call RegPack(RF, InData%LidarFocus) call RegPack(RF, InData%CableDeltaL) call RegPack(RF, InData%CableDeltaLdot) if (RegCheckErr(RF, RoutineName)) return @@ -14680,7 +14677,6 @@ subroutine FAST_UnPackExternInputType(RF, OutData) call RegUnpack(RF, OutData%BlPitchCom); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%BlAirfoilCom); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%HSSBrFrac); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%LidarFocus); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%CableDeltaL); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%CableDeltaLdot); if (RegCheckErr(RF, RoutineName)) return end subroutine diff --git a/modules/servodyn/src/ServoDyn.f90 b/modules/servodyn/src/ServoDyn.f90 index 5b1e74ae94..8ac80a00ae 100644 --- a/modules/servodyn/src/ServoDyn.f90 +++ b/modules/servodyn/src/ServoDyn.f90 @@ -474,8 +474,7 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO p%SensorType = InitInp%SensorType p%NumBeam = InitInp%NumBeam p%NumPulseGate = InitInp%NumPulseGate - p%PulseSpacing = InitInp%PulseSpacing - p%URefLid = InitInp%URefLid + p%URefLid = InitInp%URefLid !bjj: not sure why you would need to store this variable in SeroDyn or why the controller would use it CALL BladedInterface_Init(u, p, m, xd, y, InputFileData, InitInp, StC_CtrlChanInitInfo, UnSum, ErrStat2, ErrMsg2 ) if (Failed()) return; diff --git a/modules/servodyn/src/ServoDyn_Registry.txt b/modules/servodyn/src/ServoDyn_Registry.txt index 0a6d8e7efe..04c45d371f 100644 --- a/modules/servodyn/src/ServoDyn_Registry.txt +++ b/modules/servodyn/src/ServoDyn_Registry.txt @@ -59,7 +59,6 @@ typedef ^ InitInputType ReKi MsrPositionsZ {:} - - "Lidar Z direction measureme typedef ^ InitInputType IntKi SensorType - - - "Lidar sensor type" - typedef ^ InitInputType IntKi NumBeam - - - "Number of beams" - typedef ^ InitInputType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ InitInputType ReKi PulseSpacing - - - "Distance between range gates" - typedef ^ InitInputType ReKi URefLid - - - "Reference average wind speed for the lidar" m/s # Define outputs from the initialization routine here: @@ -236,7 +235,6 @@ typedef ^ BladedDLLType ReKi MsrPositionsZ {:} - - "Lidar Z direction meas typedef ^ BladedDLLType IntKi SensorType - - - "Lidar sensor type" - typedef ^ BladedDLLType IntKi NumBeam - - - "Number of beams" - typedef ^ BladedDLLType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ BladedDLLType IntKi PulseSpacing - - - "Distance between range gates" - typedef ^ BladedDLLType IntKi URefLid - - - "Reference average wind speed for the lidar" m/s ## these are PARAMETERS sent to the DLL (THEIR VALUES SHOULD NOT CHANGE DURING SIMULATION): typedef ^ BladedDLLType DbKi DLL_DT - - - "interval for calling DLL (integer multiple number of DT)" s @@ -485,8 +483,7 @@ typedef ^ ParameterType Integer Jac_Idx_SStC_y {:}{:} - - "the start and typedef ^ ParameterType IntKi SensorType - - - "Lidar sensor type" - typedef ^ ParameterType IntKi NumBeam - - - "Number of beams" - typedef ^ ParameterType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ ParameterType ReKi PulseSpacing - - - "Distance between range gates" m -typedef ^ ParameterType ReKi URefLid - - - "Reference average wind speed for the lidar" m/s +typedef ^ ParameterType ReKi URefLid - - - "Reference average wind speed for the lidar - bjj: not sure why we have this variable" m/s diff --git a/modules/servodyn/src/ServoDyn_Types.f90 b/modules/servodyn/src/ServoDyn_Types.f90 index eb53b248ae..99bc08bdcb 100644 --- a/modules/servodyn/src/ServoDyn_Types.f90 +++ b/modules/servodyn/src/ServoDyn_Types.f90 @@ -76,7 +76,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - REAL(ReKi) :: PulseSpacing = 0.0_ReKi !< Distance between range gates [-] REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] END TYPE SrvD_InitInputType ! ======================= @@ -249,7 +248,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - INTEGER(IntKi) :: PulseSpacing = 0_IntKi !< Distance between range gates [-] INTEGER(IntKi) :: URefLid = 0_IntKi !< Reference average wind speed for the lidar [m/s] REAL(DbKi) :: DLL_DT = 0.0_R8Ki !< interval for calling DLL (integer multiple number of DT) [s] CHARACTER(1024) :: DLL_InFile !< Name of input file used in DLL [-] @@ -491,8 +489,7 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - REAL(ReKi) :: PulseSpacing = 0.0_ReKi !< Distance between range gates [m] - REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] + REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar - bjj: not sure why we have this variable [m/s] END TYPE SrvD_ParameterType ! ======================= ! ========= SrvD_InputType ======= @@ -733,7 +730,6 @@ subroutine SrvD_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode, ErrS DstInitInputData%SensorType = SrcInitInputData%SensorType DstInitInputData%NumBeam = SrcInitInputData%NumBeam DstInitInputData%NumPulseGate = SrcInitInputData%NumPulseGate - DstInitInputData%PulseSpacing = SrcInitInputData%PulseSpacing DstInitInputData%URefLid = SrcInitInputData%URefLid end subroutine @@ -825,7 +821,6 @@ subroutine SrvD_PackInitInput(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%PulseSpacing) call RegPack(RF, InData%URefLid) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -878,7 +873,6 @@ subroutine SrvD_UnPackInitInput(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%PulseSpacing); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -1671,7 +1665,6 @@ subroutine SrvD_CopyBladedDLLType(SrcBladedDLLTypeData, DstBladedDLLTypeData, Ct DstBladedDLLTypeData%SensorType = SrcBladedDLLTypeData%SensorType DstBladedDLLTypeData%NumBeam = SrcBladedDLLTypeData%NumBeam DstBladedDLLTypeData%NumPulseGate = SrcBladedDLLTypeData%NumPulseGate - DstBladedDLLTypeData%PulseSpacing = SrcBladedDLLTypeData%PulseSpacing DstBladedDLLTypeData%URefLid = SrcBladedDLLTypeData%URefLid DstBladedDLLTypeData%DLL_DT = SrcBladedDLLTypeData%DLL_DT DstBladedDLLTypeData%DLL_InFile = SrcBladedDLLTypeData%DLL_InFile @@ -2049,7 +2042,6 @@ subroutine SrvD_PackBladedDLLType(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%PulseSpacing) call RegPack(RF, InData%URefLid) call RegPack(RF, InData%DLL_DT) call RegPack(RF, InData%DLL_InFile) @@ -2167,7 +2159,6 @@ subroutine SrvD_UnPackBladedDLLType(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%PulseSpacing); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%DLL_DT); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%DLL_InFile); if (RegCheckErr(RF, RoutineName)) return @@ -4861,7 +4852,6 @@ subroutine SrvD_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg) DstParamData%SensorType = SrcParamData%SensorType DstParamData%NumBeam = SrcParamData%NumBeam DstParamData%NumPulseGate = SrcParamData%NumPulseGate - DstParamData%PulseSpacing = SrcParamData%PulseSpacing DstParamData%URefLid = SrcParamData%URefLid end subroutine @@ -5159,7 +5149,6 @@ subroutine SrvD_PackParam(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%PulseSpacing) call RegPack(RF, InData%URefLid) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -5354,7 +5343,6 @@ subroutine SrvD_UnPackParam(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%PulseSpacing); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return end subroutine From c95757707a4b8fdeed6d9670192294587b9f9f73 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Tue, 1 Oct 2024 10:25:00 -0600 Subject: [PATCH 04/63] Lidar + ServoDyn - remove unnecessary lidar allocatable arrays in SrvoDyn InitInp type - remove unused URefLid from ServoDyn InitInp; the value that is passed to the controller was never initialized and doesn't make sense for a controller to use anyway. - allocate lidar arrays for controller based on number of beams and pulse gates instead of type of lidar - initialize error status in BladedInterface_End routine --- modules/openfast-library/src/FAST_Subs.f90 | 40 ++---------- modules/servodyn/src/BladedInterface.f90 | 10 +-- modules/servodyn/src/BladedInterface_EX.f90 | 70 +++++++-------------- modules/servodyn/src/ServoDyn.f90 | 34 +++++----- modules/servodyn/src/ServoDyn_Registry.txt | 7 --- modules/servodyn/src/ServoDyn_Types.f90 | 12 ---- 6 files changed, 46 insertions(+), 127 deletions(-) diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index afd4d27988..c15e2ff892 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -1507,45 +1507,13 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, SED, BD, S IF ( p_FAST%CompInflow == Module_IfW ) THEN ! assign the number of gates to ServD - if (allocated(IfW%y%lidar%LidSpeed)) then ! make sure we have the array allocated before setting it - CALL AllocAry(Init%InData_SrvD%LidSpeed, size(IfW%y%lidar%LidSpeed), 'Init%InData_SrvD%LidSpeed', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) - IF (ErrStat >= AbortErrLev) THEN - CALL Cleanup() - RETURN - END IF - Init%InData_SrvD%LidSpeed = IfW%y%lidar%LidSpeed - endif - if (allocated(IfW%y%lidar%MsrPositionsX)) then ! make sure we have the array allocated before setting it - CALL AllocAry(Init%InData_SrvD%MsrPositionsX, size(IfW%y%lidar%MsrPositionsX), 'Init%InData_SrvD%MsrPositionsX', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) - IF (ErrStat >= AbortErrLev) THEN - CALL Cleanup() - RETURN - END IF - Init%InData_SrvD%MsrPositionsX = IfW%y%lidar%MsrPositionsX - endif - if (allocated(IfW%y%lidar%MsrPositionsY)) then ! make sure we have the array allocated before setting it - CALL AllocAry(Init%InData_SrvD%MsrPositionsY, size(IfW%y%lidar%MsrPositionsY), 'Init%InData_SrvD%MsrPositionsY', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) - IF (ErrStat >= AbortErrLev) THEN - CALL Cleanup() - RETURN - END IF - Init%InData_SrvD%MsrPositionsY = IfW%y%lidar%MsrPositionsY - endif - if (allocated(IfW%y%lidar%MsrPositionsZ)) then ! make sure we have the array allocated before setting it - CALL AllocAry(Init%InData_SrvD%MsrPositionsZ, size(IfW%y%lidar%MsrPositionsZ), 'Init%InData_SrvD%MsrPositionsZ', errStat2, ErrMsg2) - CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) - IF (ErrStat >= AbortErrLev) THEN - CALL Cleanup() - RETURN - END IF - Init%InData_SrvD%MsrPositionsZ = IfW%y%lidar%MsrPositionsZ - endif Init%InData_SrvD%SensorType = IfW%p%lidar%SensorType Init%InData_SrvD%NumBeam = IfW%p%lidar%NumBeam Init%InData_SrvD%NumPulseGate = IfW%p%lidar%NumPulseGate + else + Init%InData_SrvD%SensorType = 0 + Init%InData_SrvD%NumBeam = 0 + Init%InData_SrvD%NumPulseGate = 0 END IF diff --git a/modules/servodyn/src/BladedInterface.f90 b/modules/servodyn/src/BladedInterface.f90 index f58b9106b8..97172488e1 100644 --- a/modules/servodyn/src/BladedInterface.f90 +++ b/modules/servodyn/src/BladedInterface.f90 @@ -815,7 +815,10 @@ SUBROUTINE BladedInterface_End(u, p, m, xd, ErrStat, ErrMsg) INTEGER(IntKi) :: ErrStat2 ! The error status code CHARACTER(ErrMsgLen) :: ErrMsg2 ! The error message, if an error occurred - ! call DLL final time, but skip if we've never called it + ErrStat = ErrID_None + ErrMsg = "" + + ! call DLL final time, but skip if we've never called it if (allocated(m%dll_data%avrSWAP)) then IF ( m%dll_data%SimStatus /= GH_DISCON_STATUS_INITIALISING ) THEN m%dll_data%SimStatus = GH_DISCON_STATUS_FINALISING @@ -825,10 +828,7 @@ SUBROUTINE BladedInterface_End(u, p, m, xd, ErrStat, ErrMsg) end if CALL FreeDynamicLib( p%DLL_Trgt, ErrStat2, ErrMsg2 ) ! this doesn't do anything #ifdef STATIC_DLL_LOAD because p%DLL_Trgt is 0 (NULL) - IF (ErrStat2 /= ErrID_None) THEN - ErrStat = MAX(ErrStat, ErrStat2) - ErrMsg = TRIM(ErrMsg)//NewLine//TRIM(ErrMsg2) - END IF + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'BladedInterface_End') END SUBROUTINE BladedInterface_End !================================================================================================================================== diff --git a/modules/servodyn/src/BladedInterface_EX.f90 b/modules/servodyn/src/BladedInterface_EX.f90 index 7c50a2d99e..45fde31595 100644 --- a/modules/servodyn/src/BladedInterface_EX.f90 +++ b/modules/servodyn/src/BladedInterface_EX.f90 @@ -374,66 +374,40 @@ end subroutine InitStCCtrl subroutine InitLidarMeas() integer :: I,J - if (p%NumBeam == 0) return ! Nothing to set + integer :: nPts + + nPts = p%NumBeam * p%NumPulseGate + + if (nPts == 0) return ! Nothing to set ! Allocate arrays for inputs -- these may have been set in ServoDyn already - if (allocated(InitInp%LidSpeed)) then ! make sure we have the array allocated before setting it - if (.not. allocated(u%LidSpeed)) then - CALL AllocAry(u%LidSpeed, size(InitInp%LidSpeed), 'u%LidSpeed', errStat2, ErrMsg2) - if (Failed()) return - endif - u%LidSpeed = InitInp%LidSpeed + if (.not. allocated(u%LidSpeed)) then + CALL AllocAry(u%LidSpeed, nPts, 'u%LidSpeed', errStat2, ErrMsg2); if (Failed()) return endif - if (allocated(InitInp%MsrPositionsX)) then ! make sure we have the array allocated before setting it - if (.not. allocated(u%MsrPositionsX)) then - CALL AllocAry(u%MsrPositionsX, size(InitInp%MsrPositionsX), 'u%MsrPositionsX', errStat2, ErrMsg2) - if (Failed()) return - endif - u%MsrPositionsX = InitInp%MsrPositionsX + if (.not. allocated(u%MsrPositionsX)) then + CALL AllocAry(u%MsrPositionsX, nPts, 'u%MsrPositionsX', errStat2, ErrMsg2); if (Failed()) return endif - if (allocated(InitInp%MsrPositionsY)) then ! make sure we have the array allocated before setting it - if (.not. allocated(u%MsrPositionsY)) then - CALL AllocAry(u%MsrPositionsY, size(InitInp%MsrPositionsY), 'u%MsrPositionsY', errStat2, ErrMsg2) - if (Failed()) return - endif - u%MsrPositionsY = InitInp%MsrPositionsY + if (.not. allocated(u%MsrPositionsY)) then + CALL AllocAry(u%MsrPositionsY, nPts, 'u%MsrPositionsY', errStat2, ErrMsg2); if (Failed()) return endif - if (allocated(InitInp%MsrPositionsZ)) then ! make sure we have the array allocated before setting it - if (.not. allocated(u%MsrPositionsZ)) then - CALL AllocAry(u%MsrPositionsZ, size(InitInp%MsrPositionsZ), 'u%MsrPositionsZ', errStat2, ErrMsg2) - if (Failed()) return - endif - u%MsrPositionsZ = InitInp%MsrPositionsZ + if (.not. allocated(u%MsrPositionsZ)) then + CALL AllocAry(u%MsrPositionsZ, nPts, 'u%MsrPositionsZ', errStat2, ErrMsg2) + if (Failed()) return endif ! Write summary info to summary file if (UnSum > 0) then - if (p%SensorType > 0) then ! Set these here rather than overwrite every loop step in SensorType 1 or 3 + if (p%SensorType > 0) then J=LidarMsr_StartIdx call WrSumInfoRcvd( J+0, '','Lidar input: Sensor Type') call WrSumInfoRcvd( J+1, '','Lidar input: Number of Beams') call WrSumInfoRcvd( J+2, '','Lidar input: Number of Pulse Gates') call WrSumInfoRcvd( J+3, '','Lidar input: Reference average wind speed for the lidar') - endif - if (p%SensorType == 1) THEN - do I=1,min(p%NumBeam,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group - J=LidarMsr_StartIdx + 4 + (I-1) - call WrSumInfoRcvd( J+0, '','Lidar input: Measured Wind Speeds ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumBeam*1, '','Lidar input: Measurement Points X ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumBeam*2, '','Lidar input: Measurement Points Y ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumBeam*3, '','Lidar input: Measurement Points Z ('//trim(Num2LStr(I))//')') - enddo - elseif (p%SensorType == 2) THEN - J=LidarMsr_StartIdx - call WrSumInfoRcvd( J+4, '','Lidar input: Measured Wind Speeds') - call WrSumInfoRcvd( J+5, '','Lidar input: Measurement Points X') - call WrSumInfoRcvd( J+6, '','Lidar input: Measurement Points Y') - call WrSumInfoRcvd( J+7, '','Lidar input: Measurement Points Z') - elseif (p%SensorType == 3) THEN - do I=1,min(p%NumPulseGate,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group + + do I=1,min(nPts,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group J=LidarMsr_StartIdx + 4 + (I-1) - call WrSumInfoRcvd( J+0, '','Lidar input: Measured Wind Speeds ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumPulseGate*1, '','Lidar input: Measurement Points X ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumPulseGate*2, '','Lidar input: Measurement Points Y ('//trim(Num2LStr(I))//')') - call WrSumInfoRcvd( J+p%NumPulseGate*3, '','Lidar input: Measurement Points Z ('//trim(Num2LStr(I))//')') + call WrSumInfoRcvd( J+0, '','Lidar input: Measured Wind Speeds ('//trim(Num2LStr(I))//')') + call WrSumInfoRcvd( J+nPts*1, '','Lidar input: Measurement Points X ('//trim(Num2LStr(I))//')') + call WrSumInfoRcvd( J+nPts*2, '','Lidar input: Measurement Points Y ('//trim(Num2LStr(I))//')') + call WrSumInfoRcvd( J+nPts*3, '','Lidar input: Measurement Points Z ('//trim(Num2LStr(I))//')') enddo endif endif @@ -561,7 +535,7 @@ subroutine SetEXavrSWAP_LidarSensors() dll_data%avrswap(LidarMsr_StartIdx) = real(p%SensorType,SiKi) ! Sensor Type dll_data%avrswap(LidarMsr_StartIdx+1) = real(p%NumBeam,SiKi) ! Number of Beams dll_data%avrswap(LidarMsr_StartIdx+2) = real(p%NumPulseGate,SiKi) ! Number of Pulse Gates - dll_data%avrswap(LidarMsr_StartIdx+3) = p%URefLid ! Reference average wind speed for the lidar + dll_data%avrswap(LidarMsr_StartIdx+3) = 0.0_SiKi ! Reference average wind speed for the lidar (this was never set, plus it doesn't really make sense that the controller would need it) nPts = SIZE(u%MsrPositionsX) do I=1,min(nPts,(LidarMsr_MaxChan-4)/4) ! Don't overstep the end for the lidar measure group diff --git a/modules/servodyn/src/ServoDyn.f90 b/modules/servodyn/src/ServoDyn.f90 index 8ac80a00ae..c03b489997 100644 --- a/modules/servodyn/src/ServoDyn.f90 +++ b/modules/servodyn/src/ServoDyn.f90 @@ -134,14 +134,13 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO INTEGER(IntKi) :: i ! loop counter INTEGER(IntKi) :: j ! loop counter INTEGER(IntKi) :: K ! loop counter + INTEGER(IntKi) :: nPts ! number of linear wind-speed points INTEGER(IntKi) :: UnSum ! Summary file unit INTEGER(IntKi) :: ErrStat2 ! temporary Error status of the operation CHARACTER(ErrMsgLen) :: ErrMsg2 ! temporary Error message if ErrStat /= ErrID_None character(*), parameter :: RoutineName = 'SrvD_Init' - - ! Initialize variables ErrStat = ErrID_None @@ -322,6 +321,19 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO if (Failed()) return; + nPts = InitInp%NumBeam * InitInp%NumPulseGate + if (nPts > 0 .and. p%UseBladedInterface) then + CALL AllocAry( u%LidSpeed, nPts, 'u%LidSpeed', ErrStat2, ErrMsg2 ); if (Failed()) return; + CALL AllocAry( u%MsrPositionsX, nPts, 'u%MsrPositionsX', ErrStat2, ErrMsg2 ); if (Failed()) return; + CALL AllocAry( u%MsrPositionsY, nPts, 'u%MsrPositionsY', ErrStat2, ErrMsg2 ); if (Failed()) return; + CALL AllocAry( u%MsrPositionsZ, nPts, 'u%MsrPositionsZ', ErrStat2, ErrMsg2 ); if (Failed()) return; + + u%LidSpeed = 0.0_SiKi + u%MsrPositionsX = 0.0_ReKi + u%MsrPositionsY = 0.0_ReKi + u%MsrPositionsZ = 0.0_ReKi + end if + u%BlPitch = p%BlPitchInit(1:p%NumBl) u%Yaw = p%YawNeut @@ -362,22 +374,7 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO u%RotPwr = 0. u%HorWindV = 0. u%YawAngle = 0. - if (allocated(InitInp%LidSpeed)) then ! Must allocate - allocate(u%LidSpeed(size(InitInp%LidSpeed))) - u%LidSpeed = 0. - endif - if (allocated(InitInp%MsrPositionsX)) then - allocate(u%MsrPositionsX(size(InitInp%MsrPositionsX))) - u%MsrPositionsX = 0. - endif - if (allocated(InitInp%MsrPositionsY)) then - allocate(u%MsrPositionsY(size(InitInp%MsrPositionsY))) - u%MsrPositionsY = 0. - endif - if (allocated(InitInp%MsrPositionsZ)) then - allocate(u%MsrPositionsZ(size(InitInp%MsrPositionsZ))) - u%MsrPositionsZ = 0. - endif + m%dll_data%ElecPwr_prev = 0. m%dll_data%GenTrq_prev = 0. @@ -474,7 +471,6 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO p%SensorType = InitInp%SensorType p%NumBeam = InitInp%NumBeam p%NumPulseGate = InitInp%NumPulseGate - p%URefLid = InitInp%URefLid !bjj: not sure why you would need to store this variable in SeroDyn or why the controller would use it CALL BladedInterface_Init(u, p, m, xd, y, InputFileData, InitInp, StC_CtrlChanInitInfo, UnSum, ErrStat2, ErrMsg2 ) if (Failed()) return; diff --git a/modules/servodyn/src/ServoDyn_Registry.txt b/modules/servodyn/src/ServoDyn_Registry.txt index 04c45d371f..8160192355 100644 --- a/modules/servodyn/src/ServoDyn_Registry.txt +++ b/modules/servodyn/src/ServoDyn_Registry.txt @@ -52,14 +52,9 @@ typedef ^ InitInputType CHARACTER(64) CableControlRequestor {:} - - "Array with typedef ^ InitInputType IntKi InterpOrder - - - "Interpolation order from glue code -- required to set m%u_xStC sizes" - #ADD in the TMD submodule input file passing here #initial inputs of lidar parameters -typedef ^ InitInputType ReKi LidSpeed {:} - - "Number of Lidar measurement distances" - -typedef ^ InitInputType ReKi MsrPositionsX {:} - - "Lidar X direction measurement points" m -typedef ^ InitInputType ReKi MsrPositionsY {:} - - "Lidar Y direction measurement points" m -typedef ^ InitInputType ReKi MsrPositionsZ {:} - - "Lidar Z direction measurement points" m typedef ^ InitInputType IntKi SensorType - - - "Lidar sensor type" - typedef ^ InitInputType IntKi NumBeam - - - "Number of beams" - typedef ^ InitInputType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ InitInputType ReKi URefLid - - - "Reference average wind speed for the lidar" m/s # Define outputs from the initialization routine here: typedef ^ InitOutputType CHARACTER(ChanLen) WriteOutputHdr {:} - - "Names of the output-to-file channels" - @@ -235,7 +230,6 @@ typedef ^ BladedDLLType ReKi MsrPositionsZ {:} - - "Lidar Z direction meas typedef ^ BladedDLLType IntKi SensorType - - - "Lidar sensor type" - typedef ^ BladedDLLType IntKi NumBeam - - - "Number of beams" - typedef ^ BladedDLLType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ BladedDLLType IntKi URefLid - - - "Reference average wind speed for the lidar" m/s ## these are PARAMETERS sent to the DLL (THEIR VALUES SHOULD NOT CHANGE DURING SIMULATION): typedef ^ BladedDLLType DbKi DLL_DT - - - "interval for calling DLL (integer multiple number of DT)" s typedef ^ BladedDLLType CHARACTER(1024) DLL_InFile - - - "Name of input file used in DLL" - @@ -483,7 +477,6 @@ typedef ^ ParameterType Integer Jac_Idx_SStC_y {:}{:} - - "the start and typedef ^ ParameterType IntKi SensorType - - - "Lidar sensor type" - typedef ^ ParameterType IntKi NumBeam - - - "Number of beams" - typedef ^ ParameterType IntKi NumPulseGate - - - "Number of pulse gates" - -typedef ^ ParameterType ReKi URefLid - - - "Reference average wind speed for the lidar - bjj: not sure why we have this variable" m/s diff --git a/modules/servodyn/src/ServoDyn_Types.f90 b/modules/servodyn/src/ServoDyn_Types.f90 index 99bc08bdcb..58b2cae37a 100644 --- a/modules/servodyn/src/ServoDyn_Types.f90 +++ b/modules/servodyn/src/ServoDyn_Types.f90 @@ -76,7 +76,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar [m/s] END TYPE SrvD_InitInputType ! ======================= ! ========= SrvD_InitOutputType ======= @@ -248,7 +247,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - INTEGER(IntKi) :: URefLid = 0_IntKi !< Reference average wind speed for the lidar [m/s] REAL(DbKi) :: DLL_DT = 0.0_R8Ki !< interval for calling DLL (integer multiple number of DT) [s] CHARACTER(1024) :: DLL_InFile !< Name of input file used in DLL [-] CHARACTER(1024) :: RootName !< RootName for writing output files [-] @@ -489,7 +487,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] - REAL(ReKi) :: URefLid = 0.0_ReKi !< Reference average wind speed for the lidar - bjj: not sure why we have this variable [m/s] END TYPE SrvD_ParameterType ! ======================= ! ========= SrvD_InputType ======= @@ -730,7 +727,6 @@ subroutine SrvD_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode, ErrS DstInitInputData%SensorType = SrcInitInputData%SensorType DstInitInputData%NumBeam = SrcInitInputData%NumBeam DstInitInputData%NumPulseGate = SrcInitInputData%NumPulseGate - DstInitInputData%URefLid = SrcInitInputData%URefLid end subroutine subroutine SrvD_DestroyInitInput(InitInputData, ErrStat, ErrMsg) @@ -821,7 +817,6 @@ subroutine SrvD_PackInitInput(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%URefLid) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -873,7 +868,6 @@ subroutine SrvD_UnPackInitInput(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return end subroutine subroutine SrvD_CopyInitOutput(SrcInitOutputData, DstInitOutputData, CtrlCode, ErrStat, ErrMsg) @@ -1665,7 +1659,6 @@ subroutine SrvD_CopyBladedDLLType(SrcBladedDLLTypeData, DstBladedDLLTypeData, Ct DstBladedDLLTypeData%SensorType = SrcBladedDLLTypeData%SensorType DstBladedDLLTypeData%NumBeam = SrcBladedDLLTypeData%NumBeam DstBladedDLLTypeData%NumPulseGate = SrcBladedDLLTypeData%NumPulseGate - DstBladedDLLTypeData%URefLid = SrcBladedDLLTypeData%URefLid DstBladedDLLTypeData%DLL_DT = SrcBladedDLLTypeData%DLL_DT DstBladedDLLTypeData%DLL_InFile = SrcBladedDLLTypeData%DLL_InFile DstBladedDLLTypeData%RootName = SrcBladedDLLTypeData%RootName @@ -2042,7 +2035,6 @@ subroutine SrvD_PackBladedDLLType(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%URefLid) call RegPack(RF, InData%DLL_DT) call RegPack(RF, InData%DLL_InFile) call RegPack(RF, InData%RootName) @@ -2159,7 +2151,6 @@ subroutine SrvD_UnPackBladedDLLType(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%DLL_DT); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%DLL_InFile); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%RootName); if (RegCheckErr(RF, RoutineName)) return @@ -4852,7 +4843,6 @@ subroutine SrvD_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg) DstParamData%SensorType = SrcParamData%SensorType DstParamData%NumBeam = SrcParamData%NumBeam DstParamData%NumPulseGate = SrcParamData%NumPulseGate - DstParamData%URefLid = SrcParamData%URefLid end subroutine subroutine SrvD_DestroyParam(ParamData, ErrStat, ErrMsg) @@ -5149,7 +5139,6 @@ subroutine SrvD_PackParam(RF, Indata) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) - call RegPack(RF, InData%URefLid) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -5343,7 +5332,6 @@ subroutine SrvD_UnPackParam(RF, OutData) call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return - call RegUnpack(RF, OutData%URefLid); if (RegCheckErr(RF, RoutineName)) return end subroutine subroutine SrvD_CopyInput(SrcInputData, DstInputData, CtrlCode, ErrStat, ErrMsg) From 19c361908317b5af25794a4a85fe4899bde5fcd3 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Tue, 1 Oct 2024 11:07:08 -0600 Subject: [PATCH 05/63] FAST.Farm: fix lidar init inputs --- modules/awae/src/AWAE.f90 | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/modules/awae/src/AWAE.f90 b/modules/awae/src/AWAE.f90 index fd80cd6b9a..6dacb52f1f 100644 --- a/modules/awae/src/AWAE.f90 +++ b/modules/awae/src/AWAE.f90 @@ -909,9 +909,7 @@ subroutine AWAE_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO IfW_InitInp%RootName = TRIM(p%OutFileRoot)//'.IfW' IfW_InitInp%FilePassingMethod = 0_IntKi ! Read IfW input file from disk IfW_InitInp%InputFileName = InitInp%InputFileData%InflowFile - IfW_InitInp%lidar%Tmax = 0.0_ReKi - IfW_InitInp%lidar%HubPosition = 0.0_ReKi - IfW_InitInp%lidar%SensorType = SensorType_None + IfW_InitInp%HubPosition = 0.0_ReKi IfW_InitInp%Use4Dext = .false. IfW_InitInp%MHK = MHK_None IfW_InitInp%WtrDpth = 0.0_ReKi From af0d1e4d317e337d7fee5412f219a612e70c1a65 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Thu, 17 Apr 2025 11:41:40 -0600 Subject: [PATCH 06/63] fix types files --- modules/inflowwind/src/InflowWind_Types.f90 | 4 -- modules/servodyn/src/ServoDyn_Types.f90 | 72 --------------------- 2 files changed, 76 deletions(-) diff --git a/modules/inflowwind/src/InflowWind_Types.f90 b/modules/inflowwind/src/InflowWind_Types.f90 index 58dd02a99e..f820e6e9bf 100644 --- a/modules/inflowwind/src/InflowWind_Types.f90 +++ b/modules/inflowwind/src/InflowWind_Types.f90 @@ -536,10 +536,6 @@ subroutine InflowWind_DestroyInitInput(InitInputData, ErrStat, ErrMsg) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call InflowWind_DestroyInputFile(InitInputData%PassedFileData, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - call Lidar_DestroyInitInput(InitInputData%lidar, ErrStat2, ErrMsg2) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - call NWTC_Library_DestroyFileInfoType(InitInputData%WindType2Info, ErrStat2, ErrMsg2) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call InflowWind_IO_DestroyGrid4D_InitInputType(InitInputData%FDext, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) end subroutine diff --git a/modules/servodyn/src/ServoDyn_Types.f90 b/modules/servodyn/src/ServoDyn_Types.f90 index 58b2cae37a..da5d45358c 100644 --- a/modules/servodyn/src/ServoDyn_Types.f90 +++ b/modules/servodyn/src/ServoDyn_Types.f90 @@ -69,10 +69,6 @@ MODULE ServoDyn_Types INTEGER(IntKi) :: NumCableControl = 0_IntKi !< Number of cable control channels requested [-] CHARACTER(64) , DIMENSION(:), ALLOCATABLE :: CableControlRequestor !< Array with text info about which module requested the cable control channel (size of NumCableControl). This is just for diagnostics. [-] INTEGER(IntKi) :: InterpOrder = 0_IntKi !< Interpolation order from glue code -- required to set m%u_xStC sizes [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: LidSpeed !< Number of Lidar measurement distances [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: MsrPositionsX !< Lidar X direction measurement points [m] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: MsrPositionsY !< Lidar Y direction measurement points [m] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: MsrPositionsZ !< Lidar Z direction measurement points [m] INTEGER(IntKi) :: SensorType = 0_IntKi !< Lidar sensor type [-] INTEGER(IntKi) :: NumBeam = 0_IntKi !< Number of beams [-] INTEGER(IntKi) :: NumPulseGate = 0_IntKi !< Number of pulse gates [-] @@ -676,54 +672,6 @@ subroutine SrvD_CopyInitInput(SrcInitInputData, DstInitInputData, CtrlCode, ErrS DstInitInputData%CableControlRequestor = SrcInitInputData%CableControlRequestor end if DstInitInputData%InterpOrder = SrcInitInputData%InterpOrder - if (allocated(SrcInitInputData%LidSpeed)) then - LB(1:1) = lbound(SrcInitInputData%LidSpeed) - UB(1:1) = ubound(SrcInitInputData%LidSpeed) - if (.not. allocated(DstInitInputData%LidSpeed)) then - allocate(DstInitInputData%LidSpeed(LB(1):UB(1)), stat=ErrStat2) - if (ErrStat2 /= 0) then - call SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%LidSpeed.', ErrStat, ErrMsg, RoutineName) - return - end if - end if - DstInitInputData%LidSpeed = SrcInitInputData%LidSpeed - end if - if (allocated(SrcInitInputData%MsrPositionsX)) then - LB(1:1) = lbound(SrcInitInputData%MsrPositionsX) - UB(1:1) = ubound(SrcInitInputData%MsrPositionsX) - if (.not. allocated(DstInitInputData%MsrPositionsX)) then - allocate(DstInitInputData%MsrPositionsX(LB(1):UB(1)), stat=ErrStat2) - if (ErrStat2 /= 0) then - call SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%MsrPositionsX.', ErrStat, ErrMsg, RoutineName) - return - end if - end if - DstInitInputData%MsrPositionsX = SrcInitInputData%MsrPositionsX - end if - if (allocated(SrcInitInputData%MsrPositionsY)) then - LB(1:1) = lbound(SrcInitInputData%MsrPositionsY) - UB(1:1) = ubound(SrcInitInputData%MsrPositionsY) - if (.not. allocated(DstInitInputData%MsrPositionsY)) then - allocate(DstInitInputData%MsrPositionsY(LB(1):UB(1)), stat=ErrStat2) - if (ErrStat2 /= 0) then - call SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%MsrPositionsY.', ErrStat, ErrMsg, RoutineName) - return - end if - end if - DstInitInputData%MsrPositionsY = SrcInitInputData%MsrPositionsY - end if - if (allocated(SrcInitInputData%MsrPositionsZ)) then - LB(1:1) = lbound(SrcInitInputData%MsrPositionsZ) - UB(1:1) = ubound(SrcInitInputData%MsrPositionsZ) - if (.not. allocated(DstInitInputData%MsrPositionsZ)) then - allocate(DstInitInputData%MsrPositionsZ(LB(1):UB(1)), stat=ErrStat2) - if (ErrStat2 /= 0) then - call SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%MsrPositionsZ.', ErrStat, ErrMsg, RoutineName) - return - end if - end if - DstInitInputData%MsrPositionsZ = SrcInitInputData%MsrPositionsZ - end if DstInitInputData%SensorType = SrcInitInputData%SensorType DstInitInputData%NumBeam = SrcInitInputData%NumBeam DstInitInputData%NumPulseGate = SrcInitInputData%NumPulseGate @@ -758,18 +706,6 @@ subroutine SrvD_DestroyInitInput(InitInputData, ErrStat, ErrMsg) if (allocated(InitInputData%CableControlRequestor)) then deallocate(InitInputData%CableControlRequestor) end if - if (allocated(InitInputData%LidSpeed)) then - deallocate(InitInputData%LidSpeed) - end if - if (allocated(InitInputData%MsrPositionsX)) then - deallocate(InitInputData%MsrPositionsX) - end if - if (allocated(InitInputData%MsrPositionsY)) then - deallocate(InitInputData%MsrPositionsY) - end if - if (allocated(InitInputData%MsrPositionsZ)) then - deallocate(InitInputData%MsrPositionsZ) - end if end subroutine subroutine SrvD_PackInitInput(RF, Indata) @@ -810,10 +746,6 @@ subroutine SrvD_PackInitInput(RF, Indata) call RegPack(RF, InData%NumCableControl) call RegPackAlloc(RF, InData%CableControlRequestor) call RegPack(RF, InData%InterpOrder) - call RegPackAlloc(RF, InData%LidSpeed) - call RegPackAlloc(RF, InData%MsrPositionsX) - call RegPackAlloc(RF, InData%MsrPositionsY) - call RegPackAlloc(RF, InData%MsrPositionsZ) call RegPack(RF, InData%SensorType) call RegPack(RF, InData%NumBeam) call RegPack(RF, InData%NumPulseGate) @@ -861,10 +793,6 @@ subroutine SrvD_UnPackInitInput(RF, OutData) call RegUnpack(RF, OutData%NumCableControl); if (RegCheckErr(RF, RoutineName)) return call RegUnpackAlloc(RF, OutData%CableControlRequestor); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%InterpOrder); if (RegCheckErr(RF, RoutineName)) return - call RegUnpackAlloc(RF, OutData%LidSpeed); if (RegCheckErr(RF, RoutineName)) return - call RegUnpackAlloc(RF, OutData%MsrPositionsX); if (RegCheckErr(RF, RoutineName)) return - call RegUnpackAlloc(RF, OutData%MsrPositionsY); if (RegCheckErr(RF, RoutineName)) return - call RegUnpackAlloc(RF, OutData%MsrPositionsZ); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%SensorType); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumBeam); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%NumPulseGate); if (RegCheckErr(RF, RoutineName)) return From f6240e9e0ebefb3cb87f6393e2303e047915d69b Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Fri, 18 Apr 2025 13:34:57 -0600 Subject: [PATCH 07/63] MHK RM1: reduce HD resolution --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index feca071735..dd8fb93e5f 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit feca0717356672dcadfec1209acc3a9f098f8c0b +Subproject commit dd8fb93e5f92f0c2a5793a7293e188e36eca3b36 From e5dba5653ae1358c69fdd2f6dac27e8333a82559 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 21 Apr 2025 13:30:30 -0600 Subject: [PATCH 08/63] Update r-test pointer --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index dd8fb93e5f..1c111305ad 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit dd8fb93e5f92f0c2a5793a7293e188e36eca3b36 +Subproject commit 1c111305ad6a6f8bcf85e93d323673d0f988d2a6 From dc3ece561897328c0ffaa653787242bc9f2e5799 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 21 Apr 2025 14:13:16 -0600 Subject: [PATCH 09/63] Update GH conda-deploy action to use Ubuntu 24.04 20.04 was deprecated last week on GH --- .github/workflows/conda-deploy.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/conda-deploy.yml b/.github/workflows/conda-deploy.yml index 78083fc763..7e721419a7 100644 --- a/.github/workflows/conda-deploy.yml +++ b/.github/workflows/conda-deploy.yml @@ -15,7 +15,7 @@ on: jobs: update-dev: if: github.repository_owner == 'OpenFAST' - runs-on: ubuntu-20.04 + runs-on: ubuntu-24.04 steps: # - name: Echo path # run: | From 1a21479882ad314b473133ea861089bf04b53c7b Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Fri, 25 Apr 2025 11:18:31 -0600 Subject: [PATCH 10/63] Fix FAST_ExtInfw_Restart API The C++ function declaration had an extra argument InflowType, that is not present in the Fortran function definition. --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 1 - modules/openfast-library/src/FAST_Library.h | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index 33a534f8dc..b064c29bee 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -642,7 +642,6 @@ void fast::OpenFAST::init() { tmpRstFileRoot, &AbortErrLev, &turbineData[iTurb].dt, - &turbineData[iTurb].inflowType, &turbineData[iTurb].numBlades, &turbineData[iTurb].numVelPtsBlade, &turbineData[iTurb].numVelPtsTwr, diff --git a/modules/openfast-library/src/FAST_Library.h b/modules/openfast-library/src/FAST_Library.h index 4fc1e3124b..744d845063 100644 --- a/modules/openfast-library/src/FAST_Library.h +++ b/modules/openfast-library/src/FAST_Library.h @@ -16,7 +16,7 @@ EXTERNAL_ROUTINE void FAST_AllocateTurbines(int * iTurb, int *ErrStat, char *ErrMsg); EXTERNAL_ROUTINE void FAST_DeallocateTurbines(int *ErrStat, char *ErrMsg); -EXTERNAL_ROUTINE void FAST_ExtInfw_Restart(int * iTurb, const char *CheckpointRootName, int *AbortErrLev, double * dt, int * InflowType, +EXTERNAL_ROUTINE void FAST_ExtInfw_Restart(int * iTurb, const char *CheckpointRootName, int *AbortErrLev, double * dt, int * NumBl, int * NumBlElem, int * NumTwrElem, int * n_t_global, ExtInfw_InputType_t* ExtInfw_Input, ExtInfw_OutputType_t* ExtInfw_Output, SC_DX_InputType_t* SC_DX_Input, SC_DX_OutputType_t* SC_DX_Output, int *ErrStat, char *ErrMsg); From 9ee64edd91cdc16365cba99596cd4d25a83b4340 Mon Sep 17 00:00:00 2001 From: Mayank Chetan Date: Fri, 25 Apr 2025 11:48:15 -0600 Subject: [PATCH 11/63] bug fix #2762 --- openfast_io/openfast_io/FAST_reader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index c7a5db763c..829dce0894 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -3254,7 +3254,7 @@ def execute(self): bd_file1 = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['BDBldFile(1)'])) bd_file2 = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['BDBldFile(2)'])) bd_file3 = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['BDBldFile(3)'])) - if os.path.exists(bd_file1): + if os.path.isfile(bd_file1): # if the files are the same then we only need to read it once, need to handle the cases where we have a 2 or 1 bladed rotor # Check unique BeamDyn blade files and read only once if identical if bd_file1 == bd_file2 and bd_file1 == bd_file3: From 654230d5d52288302e9787cfbe8e7f317049714d Mon Sep 17 00:00:00 2001 From: Derek Slaughter Date: Fri, 25 Apr 2025 17:49:06 +0000 Subject: [PATCH 12/63] Backport of github action to build windows executables --- .github/scripts/build_windows_executables.bat | 42 ++++++++ .github/workflows/deploy.yml | 101 +++++++++++++++++- 2 files changed, 140 insertions(+), 3 deletions(-) create mode 100644 .github/scripts/build_windows_executables.bat diff --git a/.github/scripts/build_windows_executables.bat b/.github/scripts/build_windows_executables.bat new file mode 100644 index 0000000000..70257fcb69 --- /dev/null +++ b/.github/scripts/build_windows_executables.bat @@ -0,0 +1,42 @@ +@call "C:\Program Files (x86)\Intel\oneAPI\setvars-vcvarsall.bat" %VS_VER% + +for /f "tokens=* usebackq" %%f in (`dir /b "C:\Program Files (x86)\Intel\oneAPI\compiler\" ^| findstr /V latest ^| sort`) do @set "LATEST_VERSION=%%f" +@call "C:\Program Files (x86)\Intel\oneAPI\compiler\%LATEST_VERSION%\env\vars.bat" + +@REM Make the script that generates the git version description ignore dirty +@REM since building the Visual Studio projects modifies files +powershell -command "(Get-Content -Path '.\vs-build\CreateGitVersion.bat') -replace '--dirty', '' | Set-Content -Path '.\vs-build\CreateGitVersion.bat'" + +echo on + +@REM Build all solutions +devenv vs-build/AeroDisk/AeroDisk_Driver.sln /Build "Release|x64" +devenv vs-build/AeroDyn/AeroDyn_Driver.sln /Build "Release|x64" +devenv vs-build/AeroDyn/AeroDyn_Driver.sln /Build "Release_OpenMP|x64" +devenv vs-build/AeroDyn_Inflow_c_binding/AeroDyn_Inflow_c_binding.sln /Build "Release|x64" +devenv vs-build/AeroDyn_Inflow_c_binding/AeroDyn_Inflow_c_binding.sln /Build "Release_OpenMP|x64" +devenv vs-build/BeamDyn/BeamDyn-w-registry.sln /Build "Release|x64" +devenv vs-build/Discon/Discon.sln /Build "Release|x64" +devenv vs-build/FAST-farm/FAST-Farm.sln /Build "Release|x64" +devenv vs-build/FAST-farm/FAST-Farm.sln /Build "Release_OpenMP|x64" +devenv vs-build/HydroDyn/HydroDynDriver.sln /Build "Release|x64" +devenv vs-build/HydroDyn_c_binding/HydroDyn_c_binding.sln /Build "Release|x64" +devenv vs-build/InflowWind_c_binding/InflowWind_c_binding.sln /Build "Release|x64" +devenv vs-build/InflowWind/InflowWind_driver.sln /Build "Release|x64" +devenv vs-build/InflowWind/InflowWind_driver.sln /Build "Release_OpenMP|x64" +devenv vs-build/MoorDyn/MoorDynDriver.sln /Build "Release|x64" +devenv vs-build/MoorDyn_c_binding/MoorDyn_c_binding.sln /Build "Release|x64" +devenv vs-build/FAST/FAST.sln /Build "Release|x64" +devenv vs-build/SeaState/SeaStateDriver.sln /Build "Release|x64" +devenv vs-build/SimpleElastoDyn/SimpleElastoDyn_Driver.sln /Build "Release|x64" +devenv vs-build/SubDyn/SubDyn.sln /Build "Release|x64" +devenv vs-build/TurbSim/TurbSim.vfproj /Build "Release|x64" +devenv vs-build/UnsteadyAero/UnsteadyAero.sln /Build "Release|x64" + +@REM Build MATLAB solution last +devenv vs-build/FAST/FAST.sln /Build "Release_Matlab|x64" + +@REM Copy controllers to bin directory +xcopy .\reg_tests\r-test\glue-codes\openfast\5MW_Baseline\ServoData\*.dll .\build\bin\ /y + +exit /b %ERRORLEVEL% diff --git a/.github/workflows/deploy.yml b/.github/workflows/deploy.yml index 87240dbce4..adf3513704 100644 --- a/.github/workflows/deploy.yml +++ b/.github/workflows/deploy.yml @@ -11,11 +11,20 @@ on: types: - released + push: + paths-ignore: + - 'LICENSE' + - 'README.rst' + - 'docs/**' + - 'share/**' jobs: + + # Disabled as publish-to-pypi is working correctly publish-to-pypi-test: runs-on: ubuntu-latest - if: github.event_name == 'workflow_dispatch' + if: false + # if: github.event_name == 'workflow_dispatch' steps: - uses: actions/checkout@v3 @@ -44,7 +53,7 @@ jobs: publish-to-pypi: runs-on: ubuntu-latest - if: github.event_name == 'release' + if: github.event_name == 'release' steps: - uses: actions/checkout@v3 @@ -71,9 +80,11 @@ jobs: run: hatch publish working-directory: openfast_io + # Disabled as it fails due to huge memory requirements docker-build-and-push: runs-on: ubuntu-latest - if: github.event_name == 'release' + if: false + # if: github.event_name == 'release' timeout-minutes: 500 env: DOCKERFILE_PATH: share/docker/Dockerfile @@ -123,3 +134,87 @@ jobs: push: true cache-from: type=gha cache-to: type=gha,mode=max + + build-windows-executables: + runs-on: windows-2022 + if: github.event_name == 'workflow_dispatch' || github.event_name == 'release' + steps: + - name: Checkout + uses: actions/checkout@v4 + with: + submodules: true + fetch-depth: 0 + + - name: Install Intel oneAPI BaseKit (Windows) + shell: cmd + env: + URL: https://registrationcenter-download.intel.com/akdlm/IRC_NAS/7dff44ba-e3af-4448-841c-0d616c8da6e7/w_BaseKit_p_2024.1.0.595_offline.exe + COMPONENTS: intel.oneapi.win.mkl.devel + run: | + curl.exe --output %TEMP%\webimage.exe --url %URL% --retry 5 --retry-delay 5 + start /b /wait %TEMP%\webimage.exe -s -x -f webimage_extracted --log extract.log + del %TEMP%\webimage.exe + webimage_extracted\bootstrapper.exe -s --action install --components=%COMPONENTS% --eula=accept -p=NEED_VS2017_INTEGRATION=0 -p=NEED_VS2019_INTEGRATION=0 -p=NEED_VS2022_INTEGRATION=1 --log-dir=. + set installer_exit_code=%ERRORLEVEL% + rd /s/q "webimage_extracted" + exit /b %installer_exit_code% + + - name: Install Intel oneAPI HPCKit (Windows) + shell: cmd + env: + URL: https://registrationcenter-download.intel.com/akdlm/IRC_NAS/c95a3b26-fc45-496c-833b-df08b10297b9/w_HPCKit_p_2024.1.0.561_offline.exe + COMPONENTS: intel.oneapi.win.ifort-compiler + run: | + curl.exe --output %TEMP%\webimage.exe --url %URL% --retry 5 --retry-delay 5 + start /b /wait %TEMP%\webimage.exe -s -x -f webimage_extracted --log extract.log + del %TEMP%\webimage.exe + webimage_extracted\bootstrapper.exe -s --action install --components=%COMPONENTS% --eula=accept -p=NEED_VS2017_INTEGRATION=0 -p=NEED_VS2019_INTEGRATION=0 -p=NEED_VS2022_INTEGRATION=1 --log-dir=. + set installer_exit_code=%ERRORLEVEL% + rd /s/q "webimage_extracted" + exit /b %installer_exit_code% + + - name: Set up MATLAB + id: setup-matlab + uses: matlab-actions/setup-matlab@v2 + with: + products: Simulink + + - name: Build Executables + env: + MATLAB_ROOT: ${{ steps.setup-matlab.outputs.matlabroot }} + run: .github/scripts/build_windows_executables.bat + + - name: Test version output + run: | + build/bin/openfast_x64.exe -h + build/bin/TurbSim_x64.exe -h + build/bin/FAST.Farm_x64.exe -h + + - name: Build MATLAB Mex File + uses: matlab-actions/run-command@v2 + with: + command: | + mexname = 'FAST_SFunc'; + mex('-largeArrayDims', ... + '-v', ... + ['-L' fullfile('build','bin')], ... + ['-I' fullfile('modules','openfast-library','src')], ... % "FAST_Library.h" + ['-I' fullfile('modules','supercontroller','src')], ... % "SuperController_Types.h" + ['-I' fullfile('modules','externalinflow','src')], ... % "ExternalInflow_Types.h" + ['-I' fullfile('modules','extloads','src')], ... % "ExtLoadsDX_Types.h" + ['-I' fullfile(matlabroot,'simulink','include')], ... + ['-I' fullfile(matlabroot,'extern','include')], ... + ['COMPFLAGS=$COMPFLAGS -MT -DS_FUNCTION_NAME=' mexname], ... + '-lOpenFAST-Simulink_x64', ... + '-outdir', fullfile('build','bin'), ... + '-output', mexname, ... + fullfile('glue-codes','simulink','src','FAST_SFunc.c')); + + - name: Upload executables + uses: actions/upload-artifact@v4 + with: + name: openfast-binaries + path: | + build/bin/*.exe + build/bin/*.dll + build/bin/*.mexw64 From be0337e6aea4cb604e3bd5cdece35f6163454170 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 26 Feb 2025 12:44:51 -0700 Subject: [PATCH 13/63] IO: Updated OpenFAST_io for MoorDyn input files --- openfast_io/openfast_io/FAST_reader.py | 174 ++++++++++++++++++++----- openfast_io/openfast_io/FAST_writer.py | 85 ++++++++---- 2 files changed, 200 insertions(+), 59 deletions(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index c7a5db763c..76916b167c 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -31,6 +31,22 @@ def readline_filterComments(f): read = False return line +def readline_ignoreComments(f, char = '#'): # see line 64 in NWTC_IO.f90 + """ + returns line before comment character + + Args: + f: file handle + char: comment character + + Returns: + line: content of next line in the file before comment character + """ + + line = f.readline().strip().split(char) + + return line[0] + def read_array(f,len,split_val=None,array_type=str): """ Read an array of values from a line in a file @@ -2903,25 +2919,48 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Diam'] = [] self.fst_vt['MoorDyn']['MassDen'] = [] self.fst_vt['MoorDyn']['EA'] = [] + self.fst_vt['MoorDyn']['NonLinearEA'] = [] self.fst_vt['MoorDyn']['BA_zeta'] = [] self.fst_vt['MoorDyn']['EI'] = [] self.fst_vt['MoorDyn']['Cd'] = [] self.fst_vt['MoorDyn']['Ca'] = [] self.fst_vt['MoorDyn']['CdAx'] = [] self.fst_vt['MoorDyn']['CaAx'] = [] - data_line = f.readline().strip().split() - while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['Cl'] = [] + self.fst_vt['MoorDyn']['dF'] = [] + self.fst_vt['MoorDyn']['cF'] = [] + data_line = readline_filterComments(f).split() + while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same. self.fst_vt['MoorDyn']['Name'].append(str(data_line[0])) self.fst_vt['MoorDyn']['Diam'].append(float(data_line[1])) self.fst_vt['MoorDyn']['MassDen'].append(float(data_line[2])) - self.fst_vt['MoorDyn']['EA'].append(float(data_line[3])) - self.fst_vt['MoorDyn']['BA_zeta'].append(float(data_line[4])) + self.fst_vt['MoorDyn']['EA'].append([float_read(dl) for dl in data_line[3].split('|')]) + self.fst_vt['MoorDyn']['BA_zeta'].append([float(dl) for dl in data_line[4].split('|')]) self.fst_vt['MoorDyn']['EI'].append(float(data_line[5])) self.fst_vt['MoorDyn']['Cd'].append(float(data_line[6])) self.fst_vt['MoorDyn']['Ca'].append(float(data_line[7])) self.fst_vt['MoorDyn']['CdAx'].append(float(data_line[8])) self.fst_vt['MoorDyn']['CaAx'].append(float(data_line[9])) - data_line = f.readline().strip().split() + if len(data_line) == 10: + self.fst_vt['MoorDyn']['Cl'].append(None) + self.fst_vt['MoorDyn']['dF'].append(None) + self.fst_vt['MoorDyn']['cF'].append(None) + elif (len(data_line) == 11): + self.fst_vt['MoorDyn']['Cl'].append(float(data_line[10])) + self.fst_vt['MoorDyn']['dF'].append(None) + self.fst_vt['MoorDyn']['cF'].append(None) + elif (len(data_line) == 13): + self.fst_vt['MoorDyn']['Cl'].append(float(data_line[10])) + self.fst_vt['MoorDyn']['dF'].append(float(data_line[11])) + self.fst_vt['MoorDyn']['cF'].append(float(data_line[12])) + + if type(self.fst_vt['MoorDyn']['EA'][0]) is str: + EA_file = os.path.normpath(os.path.join(os.path.dirname(moordyn_file), self.fst_vt['MoorDyn']['EA'][0])) + self.fst_vt['MoorDyn']['NonLinearEA'].append(self.read_NonLinearEA(EA_file)) + else: + self.fst_vt['MoorDyn']['NonLinearEA'].append(None) # Empty to keep track of which non-linear EA files go with what line + + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join elif 'rodtypes' in data_line or 'roddictionary' in data_line: @@ -2935,7 +2974,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Rod_CdEnd'] = [] self.fst_vt['MoorDyn']['Rod_CaEnd'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Rod_Name'].append(data_line[0]) self.fst_vt['MoorDyn']['Rod_Diam'].append(float(data_line[1])) @@ -2944,7 +2983,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Rod_Ca'].append(float(data_line[4])) self.fst_vt['MoorDyn']['Rod_CdEnd'].append(float(data_line[5])) self.fst_vt['MoorDyn']['Rod_CaEnd'].append(float(data_line[6])) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly @@ -2967,7 +3006,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Body_CdA'] = [] self.fst_vt['MoorDyn']['Body_Ca'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Body_ID'].append(int(data_line[0])) self.fst_vt['MoorDyn']['Body_Attachment'].append(data_line[1]) @@ -2983,7 +3022,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Body_Volume'].append(float(data_line[11])) self.fst_vt['MoorDyn']['Body_CdA'].append([float(dl) for dl in data_line[12].split('|')]) self.fst_vt['MoorDyn']['Body_Ca'].append([float(dl) for dl in data_line[13].split('|')]) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly @@ -3002,7 +3041,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Rod_NumSegs'] = [] self.fst_vt['MoorDyn']['RodOutputs'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Rod_ID'].append(data_line[0]) self.fst_vt['MoorDyn']['Rod_Type'].append(data_line[1]) @@ -3015,7 +3054,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Zb'].append(float(data_line[8])) self.fst_vt['MoorDyn']['Rod_NumSegs'].append(int(data_line[9])) self.fst_vt['MoorDyn']['RodOutputs'].append(data_line[10]) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly elif 'points' in data_line or 'connectionproperties' in data_line or \ @@ -3033,7 +3072,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['V'] = [] self.fst_vt['MoorDyn']['CdA'] = [] self.fst_vt['MoorDyn']['CA'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Point_ID'].append(int(data_line[0])) self.fst_vt['MoorDyn']['Attachment'].append(str(data_line[1])) @@ -3044,7 +3083,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['V'].append(float(data_line[6])) self.fst_vt['MoorDyn']['CdA'].append(float(data_line[7])) self.fst_vt['MoorDyn']['CA'].append(float(data_line[8])) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly elif 'lines' in data_line or 'lineproperties' in data_line or 'linelist' in data_line: @@ -3059,7 +3098,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['UnstrLen'] = [] self.fst_vt['MoorDyn']['NumSegs'] = [] self.fst_vt['MoorDyn']['Outputs'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Line_ID'].append(int(data_line[0])) self.fst_vt['MoorDyn']['LineType'].append(str(data_line[1])) @@ -3068,8 +3107,27 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['UnstrLen'].append(float(data_line[4])) self.fst_vt['MoorDyn']['NumSegs'].append(int(data_line[5])) self.fst_vt['MoorDyn']['Outputs'].append(str(data_line[6])) - data_line = f.readline().strip().split() - data_line = ''.join(data_line) # re-join for reading next section uniformly + data_line = readline_filterComments(f).split() + data_line = ''.join(data_line) # re-join for reading next section uniformly + + elif 'failure' in data_line.lower(): + f.readline() + f.readline() + + self.fst_vt['MoorDyn']['Failure_ID'] = [] + self.fst_vt['MoorDyn']['Failure_Point'] = [] + self.fst_vt['MoorDyn']['Failure_Line(s)'] = [] + self.fst_vt['MoorDyn']['FailTime'] = [] + self.fst_vt['MoorDyn']['FailTen'] = [] + data_line = readline_filterComments(f).split() + while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['Failure_ID'].append(int(data_line[0])) + self.fst_vt['MoorDyn']['Failure_Point'].append(data_line[1]) + self.fst_vt['MoorDyn']['Failure_Line(s)'].append([int(dl) for dl in data_line[2].split(',')]) + self.fst_vt['MoorDyn']['FailTime'].append(float(data_line[3])) + self.fst_vt['MoorDyn']['FailTen'].append(float(data_line[4])) + data_line = readline_filterComments(f).split() + data_line = ''.join(data_line) # re-join for reading next section uniformly elif 'control' in data_line.lower(): f.readline() @@ -3079,7 +3137,7 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['ChannelID'] = [] self.fst_vt['MoorDyn']['Lines_Control'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['ChannelID'].append(int(data_line[0])) # Line(s) is a list of mooring lines, spaces are allowed between commas @@ -3093,31 +3151,58 @@ def read_MoorDyn(self, moordyn_file): control_lines.remove('') self.fst_vt['MoorDyn']['Lines_Control'].append(control_lines) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly + elif 'external' in data_line.lower(): + f.readline() + f.readline() + + self.fst_vt['MoorDyn']['External_ID'] = [] + self.fst_vt['MoorDyn']['Object'] = [] + self.fst_vt['MoorDyn']['Fext'] = [] + self.fst_vt['MoorDyn']['Blin'] = [] + self.fst_vt['MoorDyn']['Bquad'] = [] + self.fst_vt['MoorDyn']['CSys'] = [] + data_line = readline_filterComments(f).split() + while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['External_ID'].append(int(data_line[0])) + self.fst_vt['MoorDyn']['Object'].append(data_line[1]) + self.fst_vt['MoorDyn']['Fext'].append([float(dl) for dl in data_line[2].split('|')]) + self.fst_vt['MoorDyn']['Blin'].append([float(dl) for dl in data_line[3].split('|')]) + self.fst_vt['MoorDyn']['Bquad'].append([float(dl) for dl in data_line[4].split('|')]) + self.fst_vt['MoorDyn']['CSys'].append(data_line[5]) + data_line = readline_filterComments(f).split() + data_line = ''.join(data_line) # re-join for reading next section uniformly elif 'options' in data_line: # MoorDyn lets options be written in any order # Solver options - self.fst_vt['MoorDyn']['options'] = [] # keep list of MoorDyn options - - string_options = ['WaterKin'] + self.fst_vt['MoorDyn']['option_values'] = [] + self.fst_vt['MoorDyn']['option_names'] = [] # keep list of MoorDyn options + self.fst_vt['MoorDyn']['option_descriptions'] = [] - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same - raw_value = data_line[0] + option_value = data_line[0] option_name = data_line[1] - - self.fst_vt['MoorDyn']['options'].append(option_name) - if option_name in string_options: - self.fst_vt['MoorDyn'][option_name] = raw_value.strip('"') + if len(data_line) > 2: + option_description = ' '.join(data_line[2:]) else: - self.fst_vt['MoorDyn'][option_name] = float(raw_value) + option_description = '' + + if option_name.upper() == 'WATERKIN': + self.fst_vt['MoorDyn']['WaterKin'] = option_value.strip('"') + WaterKin_file = os.path.normpath(os.path.join(os.path.dirname(moordyn_file), self.fst_vt['MoorDyn']['WaterKin'])) + self.read_WaterKin(WaterKin_file) + + self.fst_vt['MoorDyn']['option_values'] = float_read(option_value.strip('"')) # some options values can be strings or floats + self.fst_vt['MoorDyn']['option_names'].append(option_name) + self.fst_vt['MoorDyn']['option_descriptions'].append(option_description) - data_line = f.readline().strip().split() + data_line = readline_filterComments(f).split() data_line = ''.join(data_line) # re-join for reading next section uniformly elif 'outputs' in data_line: @@ -3127,12 +3212,11 @@ def read_MoorDyn(self, moordyn_file): f.close() break - if 'WaterKin' in self.fst_vt['MoorDyn']['options']: - WaterKin_file = os.path.normpath(os.path.join(os.path.dirname(moordyn_file), self.fst_vt['MoorDyn']['WaterKin'])) - self.read_WaterKin(WaterKin_file) - def read_WaterKin(self,WaterKin_file): - print('here') + + self.fst_vt['WaterKin']['z-depth'] = [] + self.fst_vt['WaterKin']['x-current'] = [] + self.fst_vt['WaterKin']['x-current'] = [] f = open(WaterKin_file) f.readline() @@ -3152,7 +3236,29 @@ def read_WaterKin(self,WaterKin_file): self.fst_vt['WaterKin']['Z_Grid'] = read_array(f,None,split_val='-',array_type=float) f.readline() self.fst_vt['WaterKin']['CurrentMod'] = int_read(f.readline().split()[0]) + f.readline() + f.readline() + data_line = readline_filterComments(f).split() + while data_line: + self.fst_vt['WaterKin']['z-depth'].append(float(data_line[0])) + self.fst_vt['WaterKin']['x-current'].append(float(data_line[1])) + self.fst_vt['WaterKin']['y-current'].append(float(data_line[2])) + f.close() + + def read_NonLinearEA(self,Stiffness_file): # read and return the nonlinear line stiffness lookup table for a given line + + f = open(Stiffness_file) + f.readline() + f.readline() + f.readline() + NonLinearEA = {"Strain" : [], "Tension" : []} + data_line = readline_filterComments(f).split() + while data_line: + NonLinearEA['Strain'].append([float(data_line[0])]) + NonLinearEA['Tension'].append([float(data_line[1])]) + data_line = readline_filterComments(f).split() f.close() + return NonLinearEA def execute(self): diff --git a/openfast_io/openfast_io/FAST_writer.py b/openfast_io/openfast_io/FAST_writer.py index 98c6677ecd..5c908121de 100644 --- a/openfast_io/openfast_io/FAST_writer.py +++ b/openfast_io/openfast_io/FAST_writer.py @@ -236,7 +236,7 @@ def execute(self): self.write_MAP() elif self.fst_vt['Fst']['CompMooring'] == 3: self.write_MoorDyn() - if 'options' in self.fst_vt['MoorDyn'] and 'WaterKin' in self.fst_vt['MoorDyn']['options']: + if 'option_names' in self.fst_vt['MoorDyn'] and 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'].upper(): self.write_WaterKin(os.path.join(self.FAST_runDirectory,self.fst_vt['MoorDyn']['WaterKin_file'])) # # look at if the the self.fst_vt['BeamDyn'] is an array, if so, loop through the array @@ -2343,14 +2343,18 @@ def write_MoorDyn(self): ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Name'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Diam'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['MassDen'][i])) - ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['EA'][i])) - ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['BA_zeta'][i])) + ln.append('|'.join([float_default_out(a) for a in self.fst_vt['MoorDyn']['EA'][i]])) + ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['BA_zeta'][i]])) ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['EI'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Cd'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Ca'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CdAx'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CaAx'][i])) f.write(" ".join(ln) + '\n') + + if self.fst_vt['MoorDyn']['NonLinearEA'][i] != None: + self.write_NonLinearEA(self.fst_vt['MoorDyn']['EA'][i][0], self.fst_vt['MoorDyn']['Name'][i], self.fst_vt['MoorDyn']['NonLinearEA'][i]) + if 'Rod_Name' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['Rod_Name']: f.write('----------------------- ROD TYPES ------------------------------------------\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['TypeName', 'Diam', 'Mass/m', 'Cd', 'Ca', 'CdEnd', 'CaEnd']])+'\n') @@ -2438,6 +2442,19 @@ def write_MoorDyn(self): ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Outputs'][i])) f.write(" ".join(ln) + '\n') + if 'Failure_ID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['Failure_ID']: # there are failure inputs + f.write('---------------------- FAILURE ----------------------\n') + f.write('FailureID Point Line(s) FailTime FailTen\n') + f.write('() () (,) (s or 0) (N or 0)\n') + for i_line in range(len(self.fst_vt['MoorDyn']['Failure_ID'])): + ln = [] + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Failure_ID'][i_line])) + ln.append('{:^11s}'.format(self.fst_vt['MoorDyn']['Failure_Point'][i_line])) + ln.append(','.join(['{:^11d}'.format(a) for a in self.fst_vt['MoorDyn']['Failure_Line(s)'][i_line]])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['FailTime'][i_line])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['FailTen'][i_line])) + f.write(" ".join(ln) + '\n') + if 'ChannelID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['ChannelID']: # There are control inputs f.write('---------------------- CONTROL ---------------------------------------\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['ChannelID', 'Line(s)']])+'\n') @@ -2448,31 +2465,35 @@ def write_MoorDyn(self): ln.append(','.join(self.fst_vt['MoorDyn']['Lines_Control'][i_line])) f.write(" ".join(ln) + '\n') - f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['dtM'], 'dtM', '- time step to use in mooring integration (s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['kbot'], 'kbot', '- bottom stiffness (Pa/m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['cbot'], 'cbot', '- bottom damping (Pa-s/m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['dtIC'], 'dtIC', '- time interval for analyzing convergence during IC gen (s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['TmaxIC'], 'TmaxIC', '- max time for ic gen (s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['CdScaleIC'], 'CdScaleIC', '- factor by which to scale drag coefficients during dynamic relaxation (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['threshIC'], 'threshIC', '- threshold for IC convergence (-)\n')) - if 'options' in self.fst_vt['MoorDyn']: - if 'inertialF' in self.fst_vt['MoorDyn']['options']: - f.write('{:<22d} {:<11} {:}'.format(int(self.fst_vt['MoorDyn']['inertialF']), 'inertialF', '- Compute the inertial forces (0: no, 1: yes). Switch to 0 if you get: Warning: extreme pitch moment from body-attached Rod.\n')) - - if 'WaterKin' in self.fst_vt['MoorDyn']['options']: + if 'External_ID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['External_ID']: # there are external load outputs + f.write('---------------------- EXTERNAL LOADS --------------------------------\n') + f.write('ID Object Fext Blin Bquad CSys\n') + f.write('(#) (name) (N) (Ns/m) (Ns^2/m^2) (-)\n') + for i_line in range(len(self.fst_vt['MoorDyn']['External_ID'])): + ln = [] + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['External_ID'][i_line])) + ln.append('{:^11s}'.format(self.fst_vt['MoorDyn']['Object'][i_line])) + ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['Fext'][i_line]])) + ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['Blin'][i_line]])) + ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['Bquad'][i_line]])) + ln.append('{:^11s}'.format(self.fst_vt['MoorDyn']['CSys'][i_line])) + f.write(" ".join(ln) + '\n') + + f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') + for i in range(len(self.fst_vt['MoorDyn']['option_values'])): + + if 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'][i].upper(): self.fst_vt['MoorDyn']['WaterKin_file'] = self.FAST_namingOut + '_WaterKin.dat' - f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['MoorDyn']['WaterKin_file']+'"', 'WaterKin', '- WaterKin input file\n')) + f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['MoorDyn']['WaterKin_file']+'"', self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_description'][i]+'\n')) + else: # if not waterkin handle normally + f.write('{:<22d} {:<11} {:}'.format(float_default_out(self.fst_vt['MoorDyn']['option_values'][i]), self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_description'][i]+'\n')) - - # f.write('{:^11s} {:<11} {:}'.format(self.fst_vt['MoorDyn']['WaterKin'], 'WaterKin', 'Handling of water motion (0=off, 1=on)\n')) f.write('------------------------ OUTPUTS --------------------------------------------\n') outlist = self.get_outlist(self.fst_vt['outlist'], ['MoorDyn']) for channel_list in outlist: for i in range(len(channel_list)): - f.write('"' + channel_list[i] + '"\n') - f.write('END\n') - f.write('------------------------- need this line --------------------------------------\n') + f.write(channel_list[i] + '\n') + f.write('------------------------- END --------------------------------------\n') f.flush() os.fsync(f) @@ -2481,8 +2502,8 @@ def write_MoorDyn(self): def write_WaterKin(self,WaterKin_file): f = open(WaterKin_file, 'w') - f.write('MoorDyn v2 (Feb 2022) Waves and Currents input file set up for USFLOWT\n') - f.write('Wave kinematics that will have an impact over the cans and the mooring lines.\n') + f.write('MoorDyn v2 Waves and Currents input file set up\n') + f.write('This file was written by FAST_writer.py, comments from seed file have been dropped.\n') f.write('--------------------------- WAVES -------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['WaterKin']['WaveKinMod'], 'WaveKinMod', '- type of wave input {0 no waves; 3 set up grid of wave data based on time series}\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['WaterKin']['WaveKinFile'], 'WaveKinFile', '- file containing wave elevation time series at 0,0,0\n')) @@ -2495,16 +2516,30 @@ def write_WaterKin(self,WaterKin_file): f.write('{:<22} {:}'.format(self.fst_vt['WaterKin']['Z_Type'], '- Z wave input type (0: not used; 1: list values in ascending order; 2: uniform specified by -Zlim, Zlim, num)\n')) f.write('{:<22} {:}'.format(', '.join(['{:.3f}'.format(i) for i in self.fst_vt['WaterKin']['Z_Grid']]), '- Z wave grid point data separated by commas\n')) f.write('--------------------------- CURRENT -------------------------------------\n') - f.write('0 CurrentMod - type of current input {0 no current; 1 steady current profile described below} \n') + f.write('{:} CurrentMod - type of current input {0 no current; 1 steady current profile described below} \n'.format(self.fst_vt['WaterKin']['CurrentMod'])) f.write('z-depth x-current y-current\n') f.write('(m) (m/s) (m/s)\n') + if self.fst_vt['WaterKin']['z-depth']: + for i in range(len(self.fst_vt['WaterKin']['z-depth'])): + f.write('{:.3f} {:.3f} {:.3f}'.format(self.fst_vt['WaterKin']['z-depth'][i], self.fst_vt['WaterKin']['x-current'][i], self.fst_vt['WaterKin']['y-current'][i])) f.write('--------------------- need this line ------------------\n') f.flush() os.fsync(f) f.close() + def write_NonLinearEA(self,Stiffness_file, Linetype, NonLinearEA): + f = open(Stiffness_file, 'w') + + f.write('---{:}---\n'.format(Linetype)) + f.write('Strain Tension\n') + f.write('(-) (N)\n') + for i in range(len(NonLinearEA["Strain"])): + f.write('{:.3f} {:.3f}'.format(NonLinearEA["Strain"][i], NonLinearEA["Tension"][i])) + f.flush() + os.fsync(f) + f.close() def write_StC(self,StC_vt,StC_filename): From eb50dce751cbfb50cfc4368912473cf397f64949 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 26 Feb 2025 15:19:42 -0700 Subject: [PATCH 14/63] IO: clean up openfast_io for MD after testing, fix *** error in MD output files --- modules/moordyn/src/MoorDyn_IO.f90 | 8 +-- openfast_io/openfast_io/FAST_reader.py | 17 +++-- openfast_io/openfast_io/FAST_vars_out.py | 5 +- openfast_io/openfast_io/FAST_writer.py | 89 ++++++++++++++---------- 4 files changed, 67 insertions(+), 52 deletions(-) diff --git a/modules/moordyn/src/MoorDyn_IO.f90 b/modules/moordyn/src/MoorDyn_IO.f90 index 4eb8a6e2a0..f3473b61a3 100644 --- a/modules/moordyn/src/MoorDyn_IO.f90 +++ b/modules/moordyn/src/MoorDyn_IO.f90 @@ -1583,7 +1583,7 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) if ( p%NumOuts > 0_IntKi .and. p%MDUnOut > 0 ) then ! Write the output parameters to the file - Frmt = '(F10.4,'//TRIM(Int2LStr(p%NumOuts))//'(A1,ES15.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(p%NumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? WRITE(p%MDUnOut,Frmt) Time, ( p%Delim, y%WriteOutput(I), I=1,p%NumOuts ) END IF @@ -1605,9 +1605,9 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) + m%LineList(I)%N*SUM(m%LineList(I)%OutFlagList(10:18)) if (m%LineList(I)%OutFlagList(2) == 1) THEN ! if node positions are included, make them using a float format for higher precision - Frmt = '(F10.4,'//TRIM(Int2LStr(3*(m%LineList(I)%N + 1)))//'(A1,ES15.7E2),'//TRIM(Int2LStr(LineNumOuts - 3*(m%LineList(I)%N - 1)))//'(A1,ES15.7E2))' + Frmt = '(F10.4,'//TRIM(Int2LStr(3*(m%LineList(I)%N + 1)))//'(A1,ES25.7E2),'//TRIM(Int2LStr(LineNumOuts - 3*(m%LineList(I)%N - 1)))//'(A1,ES25.7E2))' else - Frmt = '(F10.4,'//TRIM(Int2LStr(LineNumOuts))//'(A1,ES15.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(LineNumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? end if L = 1 ! start of index of line output file at first entry 12345.7890 @@ -1755,7 +1755,7 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) + m%RodList(I)%N*SUM(m%RodList(I)%OutFlagList(12:18)) - Frmt = '(F10.4,'//TRIM(Int2LStr(RodNumOuts))//'(A1,ES15.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(RodNumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? L = 1 ! start of index of line output file at first entry diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index 76916b167c..88a73ece70 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -2895,8 +2895,6 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Rod_Name'] = [] self.fst_vt['MoorDyn']['Body_ID'] = [] self.fst_vt['MoorDyn']['Rod_ID'] = [] - self.fst_vt['MoorDyn']['ChannelID'] = [] - # MoorDyn f.readline() @@ -3186,19 +3184,19 @@ def read_MoorDyn(self, moordyn_file): data_line = readline_filterComments(f).split() while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same - option_value = data_line[0] - option_name = data_line[1] + option_value = data_line[0].upper() # MD is case insensitive + option_name = data_line[1].upper() # MD is case insensitive if len(data_line) > 2: option_description = ' '.join(data_line[2:]) else: - option_description = '' + option_description = '-' if option_name.upper() == 'WATERKIN': self.fst_vt['MoorDyn']['WaterKin'] = option_value.strip('"') WaterKin_file = os.path.normpath(os.path.join(os.path.dirname(moordyn_file), self.fst_vt['MoorDyn']['WaterKin'])) self.read_WaterKin(WaterKin_file) - self.fst_vt['MoorDyn']['option_values'] = float_read(option_value.strip('"')) # some options values can be strings or floats + self.fst_vt['MoorDyn']['option_values'].append(float_read(option_value.strip('"'))) # some options values can be strings or floats self.fst_vt['MoorDyn']['option_names'].append(option_name) self.fst_vt['MoorDyn']['option_descriptions'].append(option_description) @@ -3216,7 +3214,7 @@ def read_WaterKin(self,WaterKin_file): self.fst_vt['WaterKin']['z-depth'] = [] self.fst_vt['WaterKin']['x-current'] = [] - self.fst_vt['WaterKin']['x-current'] = [] + self.fst_vt['WaterKin']['y-current'] = [] f = open(WaterKin_file) f.readline() @@ -3239,10 +3237,11 @@ def read_WaterKin(self,WaterKin_file): f.readline() f.readline() data_line = readline_filterComments(f).split() - while data_line: + while data_line[0] and data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['WaterKin']['z-depth'].append(float(data_line[0])) self.fst_vt['WaterKin']['x-current'].append(float(data_line[1])) - self.fst_vt['WaterKin']['y-current'].append(float(data_line[2])) + self.fst_vt['WaterKin']['y-current'].append(float(data_line[2])) + data_line = readline_filterComments(f).split() f.close() def read_NonLinearEA(self,Stiffness_file): # read and return the nonlinear line stiffness lookup table for a given line diff --git a/openfast_io/openfast_io/FAST_vars_out.py b/openfast_io/openfast_io/FAST_vars_out.py index f1c9fea3be..e08e2e78d9 100644 --- a/openfast_io/openfast_io/FAST_vars_out.py +++ b/openfast_io/openfast_io/FAST_vars_out.py @@ -9577,10 +9577,11 @@ """ MoorDyn """ # THIS IS NOT A COMPLETE LIST! # the "flexible naming system" discussed on page 7-8 of the documentation is not included -# http://www.matt-hall.ca/files/MoorDyn-Users-Guide-2017-08-16.pdf +# https://moordyn.readthedocs.io/en/latest/inputs.html#id5 # also assuming that like other OpenFAST variables, it is limited to 9 output locations per veriable, i.e. FairTen1-FairTen9 -# TODO: Handle the flexible outputs for moordyn. This will require a different approach than the current dictionary structure. +# TODO: Handle the flexible outputs for moordyn. This will require a different approach than the current dictionary structure. +# Update the message in FAST_writer.write_MoorDyn() when this is finished MoorDyn = {} MoorDyn['FairTen1'] = False # (); ; diff --git a/openfast_io/openfast_io/FAST_writer.py b/openfast_io/openfast_io/FAST_writer.py index 5c908121de..1201165dc7 100644 --- a/openfast_io/openfast_io/FAST_writer.py +++ b/openfast_io/openfast_io/FAST_writer.py @@ -30,35 +30,49 @@ def auto_format(f, var): elif isinstance(var, float): f.write('{: 2.15e}\n'.format(var)) -def float_default_out(val): +def float_default_out(val, trim = False): """ Formatted float output when 'default' is an option args: val: value to be formatted + trim: trim the whitespace from the returned value returns: formatted value """ if type(val) is float: - return '{: 22f}'.format(val) + if trim: + return '{:.4f}'.format(val) + else: + return '{: 22f}'.format(val) else: - return '{:<22}'.format(val) + if trim: + return '{:}'.format(val) + else: + return '{:<22}'.format(val) -def int_default_out(val): +def int_default_out(val, trim = False): """ Formatted int output when 'default' is an option args: val: value to be formatted + trim: trim the whitespace from the returned value returns: formatted value """ if type(val) is float: - return '{:<22d}'.format(val) + if trim: + return '{:d}'.format(val) + else: + return '{:<22d}'.format(val) else: - return '{:<22}'.format(val) + if trim: + return '{:}'.format(val) + else: + return '{:<22}'.format(val) def get_dict(vartree, branch): """ @@ -236,7 +250,7 @@ def execute(self): self.write_MAP() elif self.fst_vt['Fst']['CompMooring'] == 3: self.write_MoorDyn() - if 'option_names' in self.fst_vt['MoorDyn'] and 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'].upper(): + if 'option_names' in self.fst_vt['MoorDyn'] and 'WATERKIN' in self.fst_vt['MoorDyn']['option_names']: self.write_WaterKin(os.path.join(self.FAST_runDirectory,self.fst_vt['MoorDyn']['WaterKin_file'])) # # look at if the the self.fst_vt['BeamDyn'] is an array, if so, loop through the array @@ -2334,16 +2348,17 @@ def write_MoorDyn(self): f.write('--------------------- MoorDyn Input File ------------------------------------\n') f.write('Generated with OpenFAST_IO\n') + f.write('comments from seed file have been dropped. Output Channels are not yet fully supported\n') f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['Echo'], 'Echo', '- echo the input file data (flag)\n')) f.write('----------------------- LINE TYPES ------------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['Name', 'Diam', 'MassDen', 'EA', 'BA/-zeta', 'EI', 'Cd', 'Ca', 'CdAx', 'CaAx']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(m)', '(kg/m)', '(N)', '(N-s/-)', '(-)', '(-)', '(-)', '(-)', '(-)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['Name', 'Diam', 'MassDen', 'EA', 'BA/-zeta', 'EI', 'Cd', 'Ca', 'CdAx', 'CaAx', 'Cl (optional)', 'dF (optional)', 'cF (optional)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(-)', '(m)', '(kg/m)', '(N)', '(N-s/-)', '(N-m^2)', '(-)', '(-)', '(-)', '(-)', '(-)', '(-)', '(-)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Name'])): ln = [] - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Name'][i])) + ln.append('{:<11}'.format(self.fst_vt['MoorDyn']['Name'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Diam'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['MassDen'][i])) - ln.append('|'.join([float_default_out(a) for a in self.fst_vt['MoorDyn']['EA'][i]])) + ln.append('|'.join([float_default_out(a, trim=True) for a in self.fst_vt['MoorDyn']['EA'][i]])) ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['BA_zeta'][i]])) ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['EI'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Cd'][i])) @@ -2357,11 +2372,11 @@ def write_MoorDyn(self): if 'Rod_Name' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['Rod_Name']: f.write('----------------------- ROD TYPES ------------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['TypeName', 'Diam', 'Mass/m', 'Cd', 'Ca', 'CdEnd', 'CaEnd']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(name)', '(m)', '(kg/m)', '(-)', '(-)', '(-)', '(-)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['TypeName', 'Diam', 'Mass/m', 'Cd', 'Ca', 'CdEnd', 'CaEnd']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(name)', '(m)', '(kg/m)', '(-)', '(-)', '(-)', '(-)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Rod_Name'])): ln = [] - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Rod_Name'][i])) + ln.append('{:<11}'.format(self.fst_vt['MoorDyn']['Rod_Name'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Rod_Diam'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Rod_MassDen'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Rod_Cd'][i])) @@ -2373,11 +2388,11 @@ def write_MoorDyn(self): if 'Body_ID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['Body_ID']: f.write('----------------------- BODIES ------------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['ID', 'Attachement', 'X0', 'Y0', 'Z0', 'r0', 'p0','y0','Mass','CG*','I*','Volume','CdA*','Ca*']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(#)', '(word)', '(m)', '(m)', '(m)', '(deg)', '(deg)','(deg)','(kg)','(m)','(kg-m^2)','(m^3)','m^2','(kg/m^3)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['ID', 'Attachement', 'X0', 'Y0', 'Z0', 'r0', 'p0','y0','Mass','CG*','I*','Volume','CdA*','Ca*']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(#)', '(word)', '(m)', '(m)', '(m)', '(deg)', '(deg)','(deg)','(kg)','(m)','(kg-m^2)','(m^3)','m^2','(kg/m^3)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Body_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Body_ID'][i])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['Body_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Body_Attachment'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['X0'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Y0'][i])) @@ -2395,11 +2410,11 @@ def write_MoorDyn(self): if 'Rod_ID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['Rod_ID']: f.write('----------------------- RODS ------------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['ID', 'RodType', 'Attachment', 'Xa', 'Ya', 'Za', 'Xb','Yb','Zb','NumSegs','RodOutputs']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(#)', '(name)', '(word/ID)', '(m)', '(m)', '(m)', '(m)','(m)','(m)','(-)','(-)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['ID', 'RodType', 'Attachment', 'Xa', 'Ya', 'Za', 'Xb','Yb','Zb','NumSegs','RodOutputs']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(#)', '(name)', '(word/ID)', '(m)', '(m)', '(m)', '(m)','(m)','(m)','(-)','(-)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Rod_ID'])): ln = [] - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Rod_ID'][i])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['Rod_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Rod_Type'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Rod_Attachment'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Xa'][i])) @@ -2414,11 +2429,11 @@ def write_MoorDyn(self): f.write('---------------------- POINTS --------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['ID', 'Attachment', 'X', 'Y', 'Z', 'M', 'V', 'CdA', 'CA']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(m)', '(m)', '(m)', '(kg)', '(m^3)', '(m^2)', '(-)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['ID', 'Attachment', 'X', 'Y', 'Z', 'M', 'V', 'CdA', 'CA']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(-)', '(-)', '(m)', '(m)', '(m)', '(kg)', '(m^3)', '(m^2)', '(-)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Point_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Point_ID'][i])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['Point_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Attachment'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['X'][i])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Y'][i])) @@ -2429,11 +2444,11 @@ def write_MoorDyn(self): ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CA'][i])) f.write(" ".join(ln) + '\n') f.write('---------------------- LINES --------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['Line', 'LineType', 'AttachA', 'AttachB', 'UnstrLen', 'NumSegs', 'Outputs']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(-)', '(-)', '(m)', '(-)', '(-)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['Line', 'LineType', 'AttachA', 'AttachB', 'UnstrLen', 'NumSegs', 'Outputs']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['(-)', '(-)', '(-)', '(-)', '(m)', '(-)', '(-)']])+'\n') for i in range(len(self.fst_vt['MoorDyn']['Line_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Line_ID'][i])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['Line_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['LineType'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['AttachA'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['AttachB'][i])) @@ -2448,20 +2463,20 @@ def write_MoorDyn(self): f.write('() () (,) (s or 0) (N or 0)\n') for i_line in range(len(self.fst_vt['MoorDyn']['Failure_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Failure_ID'][i_line])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['Failure_ID'][i_line])) ln.append('{:^11s}'.format(self.fst_vt['MoorDyn']['Failure_Point'][i_line])) - ln.append(','.join(['{:^11d}'.format(a) for a in self.fst_vt['MoorDyn']['Failure_Line(s)'][i_line]])) + ln.append('{:^11s}'.format(','.join(['{:^d}'.format(a) for a in self.fst_vt['MoorDyn']['Failure_Line(s)'][i_line]]))) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['FailTime'][i_line])) ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['FailTen'][i_line])) f.write(" ".join(ln) + '\n') if 'ChannelID' in self.fst_vt['MoorDyn'] and self.fst_vt['MoorDyn']['ChannelID']: # There are control inputs f.write('---------------------- CONTROL ---------------------------------------\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['ChannelID', 'Line(s)']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['()', '(,)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['ChannelID', 'Line(s)']])+'\n') + f.write(" ".join(['{:<11s}'.format(i) for i in ['()', '(,)']])+'\n') for i_line in range(len(self.fst_vt['MoorDyn']['ChannelID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['ChannelID'][i_line])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['ChannelID'][i_line])) ln.append(','.join(self.fst_vt['MoorDyn']['Lines_Control'][i_line])) f.write(" ".join(ln) + '\n') @@ -2471,7 +2486,7 @@ def write_MoorDyn(self): f.write('(#) (name) (N) (Ns/m) (Ns^2/m^2) (-)\n') for i_line in range(len(self.fst_vt['MoorDyn']['External_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['External_ID'][i_line])) + ln.append('{:<7d}'.format(self.fst_vt['MoorDyn']['External_ID'][i_line])) ln.append('{:^11s}'.format(self.fst_vt['MoorDyn']['Object'][i_line])) ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['Fext'][i_line]])) ln.append('|'.join(['{:^.4f}'.format(a) for a in self.fst_vt['MoorDyn']['Blin'][i_line]])) @@ -2482,11 +2497,11 @@ def write_MoorDyn(self): f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') for i in range(len(self.fst_vt['MoorDyn']['option_values'])): - if 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'][i].upper(): + if 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'][i]: self.fst_vt['MoorDyn']['WaterKin_file'] = self.FAST_namingOut + '_WaterKin.dat' - f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['MoorDyn']['WaterKin_file']+'"', self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_description'][i]+'\n')) + f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['MoorDyn']['WaterKin_file']+'"', self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_descriptions'][i]+'\n')) else: # if not waterkin handle normally - f.write('{:<22d} {:<11} {:}'.format(float_default_out(self.fst_vt['MoorDyn']['option_values'][i]), self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_description'][i]+'\n')) + f.write('{:<22} {:<11} {:}'.format(float_default_out(self.fst_vt['MoorDyn']['option_values'][i]), self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_descriptions'][i]+'\n')) f.write('------------------------ OUTPUTS --------------------------------------------\n') outlist = self.get_outlist(self.fst_vt['outlist'], ['MoorDyn']) @@ -2516,7 +2531,7 @@ def write_WaterKin(self,WaterKin_file): f.write('{:<22} {:}'.format(self.fst_vt['WaterKin']['Z_Type'], '- Z wave input type (0: not used; 1: list values in ascending order; 2: uniform specified by -Zlim, Zlim, num)\n')) f.write('{:<22} {:}'.format(', '.join(['{:.3f}'.format(i) for i in self.fst_vt['WaterKin']['Z_Grid']]), '- Z wave grid point data separated by commas\n')) f.write('--------------------------- CURRENT -------------------------------------\n') - f.write('{:} CurrentMod - type of current input {0 no current; 1 steady current profile described below} \n'.format(self.fst_vt['WaterKin']['CurrentMod'])) + f.write('{:} CurrentMod - type of current input (0 no current; 1 steady current profile described below) \n'.format(self.fst_vt['WaterKin']['CurrentMod'])) f.write('z-depth x-current y-current\n') f.write('(m) (m/s) (m/s)\n') if self.fst_vt['WaterKin']['z-depth']: @@ -2666,7 +2681,7 @@ def write_StC(self,StC_vt,StC_filename): 'glue-codes', 'openfast', '5MW_Land_BD_DLL_WTurb') # Path to fst directory files - check_rtest_cloned(os.path.join(fast.FAST_directory, fast.FAST_InputFile)) + check_rtest_cloned(os.path.join(fast.FAST_directory)) fast.execute() From 45ed316cef6be3c0fb647349bf02dff7956a7056 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Thu, 27 Feb 2025 08:33:47 -0700 Subject: [PATCH 15/63] MD: update version --- modules/moordyn/src/MoorDyn.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/moordyn/src/MoorDyn.f90 b/modules/moordyn/src/MoorDyn.f90 index 80d21a7810..0e1f1ae812 100644 --- a/modules/moordyn/src/MoorDyn.f90 +++ b/modules/moordyn/src/MoorDyn.f90 @@ -34,7 +34,7 @@ MODULE MoorDyn PRIVATE - TYPE(ProgDesc), PARAMETER :: MD_ProgDesc = ProgDesc( 'MoorDyn', 'v2.2.2', '2024-01-16' ) + TYPE(ProgDesc), PARAMETER :: MD_ProgDesc = ProgDesc( 'MoorDyn', 'v2.3.8', '2025-02-27' ) INTEGER(IntKi), PARAMETER :: wordy = 0 ! verbosity level. >1 = more console output From 27faafeb8bd6369d007cdf94c8a4615ae0c1d509 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 28 Feb 2025 13:58:26 -0700 Subject: [PATCH 16/63] MD: IO output format fix --- modules/moordyn/src/MoorDyn_IO.f90 | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/moordyn/src/MoorDyn_IO.f90 b/modules/moordyn/src/MoorDyn_IO.f90 index f3473b61a3..4b32b2a898 100644 --- a/modules/moordyn/src/MoorDyn_IO.f90 +++ b/modules/moordyn/src/MoorDyn_IO.f90 @@ -1583,7 +1583,7 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) if ( p%NumOuts > 0_IntKi .and. p%MDUnOut > 0 ) then ! Write the output parameters to the file - Frmt = '(F10.4,'//TRIM(Int2LStr(p%NumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(p%NumOuts))//'(A1,ES15.7))' ! should evenutally use user specified format? WRITE(p%MDUnOut,Frmt) Time, ( p%Delim, y%WriteOutput(I), I=1,p%NumOuts ) END IF @@ -1605,9 +1605,9 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) + m%LineList(I)%N*SUM(m%LineList(I)%OutFlagList(10:18)) if (m%LineList(I)%OutFlagList(2) == 1) THEN ! if node positions are included, make them using a float format for higher precision - Frmt = '(F10.4,'//TRIM(Int2LStr(3*(m%LineList(I)%N + 1)))//'(A1,ES25.7E2),'//TRIM(Int2LStr(LineNumOuts - 3*(m%LineList(I)%N - 1)))//'(A1,ES25.7E2))' + Frmt = '(F10.4,'//TRIM(Int2LStr(3*(m%LineList(I)%N + 1)))//'(A1,ES15.7),'//TRIM(Int2LStr(LineNumOuts - 3*(m%LineList(I)%N - 1)))//'(A1,ES15.7))' else - Frmt = '(F10.4,'//TRIM(Int2LStr(LineNumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(LineNumOuts))//'(A1,ES15.7))' ! should evenutally use user specified format? end if L = 1 ! start of index of line output file at first entry 12345.7890 @@ -1755,7 +1755,7 @@ SUBROUTINE MDIO_WriteOutputs( Time, p, m, y, ErrStat, ErrMsg ) + m%RodList(I)%N*SUM(m%RodList(I)%OutFlagList(12:18)) - Frmt = '(F10.4,'//TRIM(Int2LStr(RodNumOuts))//'(A1,ES25.7E2))' ! should evenutally use user specified format? + Frmt = '(F10.4,'//TRIM(Int2LStr(RodNumOuts))//'(A1,ES15.7))' ! should evenutally use user specified format? L = 1 ! start of index of line output file at first entry From 5dbf3a3141cd76beb7f33d191601de9d40243015 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 3 Mar 2025 13:07:02 -0700 Subject: [PATCH 17/63] IO: Fix MoorDyn outlist handling, remove MoorDyn echo file reading --- openfast_io/openfast_io/FAST_reader.py | 20 ++++++++++++++++---- openfast_io/openfast_io/FAST_vars_out.py | 3 ++- openfast_io/openfast_io/FAST_writer.py | 4 ++-- 3 files changed, 20 insertions(+), 7 deletions(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index 88a73ece70..649df08f36 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -2897,9 +2897,6 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Rod_ID'] = [] # MoorDyn - f.readline() - f.readline() - self.fst_vt['MoorDyn']['Echo'] = bool_read(f.readline().split()[0]) data_line = f.readline() while data_line: @@ -3205,11 +3202,26 @@ def read_MoorDyn(self, moordyn_file): elif 'outputs' in data_line: - self.read_outlist_freeForm(f,'MoorDyn') + data_line = readline_filterComments(f) + + while (data_line[0] and data_line[0][:3] != '---') and not ('END' in data_line): # OpenFAST searches for --- and END, so we'll do the same + + if '"' in data_line: + pattern = r'"?(.*?)"?' # grab only the text between quotes + data_line = re.findall(pattern, data_line)[0] + + channels = data_line.split(',') # split on commas + channels = [c.strip() for c in channels] # strip whitespace + for c in channels: + self.fst_vt['outlist']['MoorDyn'][c] = True + data_line = readline_filterComments(f) f.close() break + else: # we must be in the header section, unlimited lines of text allowed here so skip until we hit the first line w/ keywords 'Line Types' or 'Line Dictionary' + data_line = f.readline() + def read_WaterKin(self,WaterKin_file): self.fst_vt['WaterKin']['z-depth'] = [] diff --git a/openfast_io/openfast_io/FAST_vars_out.py b/openfast_io/openfast_io/FAST_vars_out.py index e08e2e78d9..ea11689d3b 100644 --- a/openfast_io/openfast_io/FAST_vars_out.py +++ b/openfast_io/openfast_io/FAST_vars_out.py @@ -9580,7 +9580,8 @@ # https://moordyn.readthedocs.io/en/latest/inputs.html#id5 # also assuming that like other OpenFAST variables, it is limited to 9 output locations per veriable, i.e. FairTen1-FairTen9 -# TODO: Handle the flexible outputs for moordyn. This will require a different approach than the current dictionary structure. +# TODO: Handle the flexible outputs for moordyn. This will require a different approach than the current dictionary structure. +# Right now a hackish way is used in the reader # Update the message in FAST_writer.write_MoorDyn() when this is finished MoorDyn = {} diff --git a/openfast_io/openfast_io/FAST_writer.py b/openfast_io/openfast_io/FAST_writer.py index 1201165dc7..89917a8af5 100644 --- a/openfast_io/openfast_io/FAST_writer.py +++ b/openfast_io/openfast_io/FAST_writer.py @@ -2348,8 +2348,8 @@ def write_MoorDyn(self): f.write('--------------------- MoorDyn Input File ------------------------------------\n') f.write('Generated with OpenFAST_IO\n') - f.write('comments from seed file have been dropped. Output Channels are not yet fully supported\n') - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['Echo'], 'Echo', '- echo the input file data (flag)\n')) + f.write('Comments from seed file have been dropped. Output Channels are not yet fully supported\n') + f.write('NOTE: MoorDyn does not use ECHO, instead use WriteLog of 0, 1, 2, or 3 in the options list \n') f.write('----------------------- LINE TYPES ------------------------------------------\n') f.write(" ".join(['{:<11s}'.format(i) for i in ['Name', 'Diam', 'MassDen', 'EA', 'BA/-zeta', 'EI', 'Cd', 'Ca', 'CdAx', 'CaAx', 'Cl (optional)', 'dF (optional)', 'cF (optional)']])+'\n') f.write(" ".join(['{:<11s}'.format(i) for i in ['(-)', '(m)', '(kg/m)', '(N)', '(N-s/-)', '(N-m^2)', '(-)', '(-)', '(-)', '(-)', '(-)', '(-)', '(-)']])+'\n') From d689a1e98d9dbf9274a997d169c4b24933ee9e2f Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Mon, 17 Mar 2025 12:06:16 -0600 Subject: [PATCH 18/63] bug fix: Adjust steady-state solver small angle assumptions was using log maps in the steady-state solver for differencing, but the perturbation function assumed they were angles when it adjusted them later --- .../openfast-library/src/FAST_SS_Solver.f90 | 22 ++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/modules/openfast-library/src/FAST_SS_Solver.f90 b/modules/openfast-library/src/FAST_SS_Solver.f90 index f4ea398e61..ffd64c979a 100644 --- a/modules/openfast-library/src/FAST_SS_Solver.f90 +++ b/modules/openfast-library/src/FAST_SS_Solver.f90 @@ -586,8 +586,11 @@ SUBROUTINE SteadyStateSolve_Residual(caseData, p_FAST, y_FAST, m_FAST, ED, BD, A INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*) , INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None + REAL(R8Ki) :: Orientation(3,3) + INTEGER(IntKi) :: k, node INTEGER(IntKi) :: ErrStat2 INTEGER(IntKi) :: Indx_u_start + INTEGER(IntKi) :: Indx_u_angle_start(p_FAST%NumBl_Lin) CHARACTER(ErrMsgLen) :: ErrMsg2 CHARACTER(*), PARAMETER :: RoutineName = 'SteadyStateSolve_Residual' @@ -608,12 +611,23 @@ SUBROUTINE SteadyStateSolve_Residual(caseData, p_FAST, y_FAST, m_FAST, ED, BD, A !.................. ! Pack the output "residual vector" with these state derivatives and new inputs: !.................. - CALL Create_SS_Vector( p_FAST, y_FAST, U_Resid, AD, ED, BD, InputIndex, STATE_PRED ) + CALL Create_SS_Vector( p_FAST, y_FAST, U_Resid, AD, ED, BD, InputIndex, STATE_PRED, Indx_u_angle_start ) ! Make the inputs a residual (subtract from previous inputs) Indx_u_start = y_FAST%Lin%Glue%SizeLin(LIN_ContSTATE_COL) + 1 U_Resid(Indx_u_start : ) = u_in(Indx_u_start : ) - U_Resid(Indx_u_start : ) + ! we need to make a special case for the orientation matrices + do k=1,p_FAST%NumBl_Lin + Indx_u_start = Indx_u_angle_start(k) + do node=1, AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%NNodes + Orientation = EulerConstruct( u_in( Indx_u_start:Indx_u_start+2 ) ) + Orientation = MATMUL(TRANSPOSE( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node)), Orientation) + U_Resid(Indx_u_start:Indx_u_start+2) = EulerExtract(Orientation) + Indx_u_start = Indx_u_start + 3 + end do + end do + END SUBROUTINE SteadyStateSolve_Residual !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine saves the current states so they can be used to compute the residual. @@ -794,7 +808,7 @@ END SUBROUTINE Precondition_Jmat !---------------------------------------------------------------------------------------------------------------------------------- !> This routine basically packs the relevant parts of the modules' inputs and states for use in the steady-state solver. -SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateIndex ) +SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateIndex, IndxOrientStart ) !.................................................................................................................................. TYPE(FAST_ParameterType) , INTENT(IN ) :: p_FAST !< Glue-code simulation parameters TYPE(FAST_OutputFileType), INTENT(IN ) :: y_FAST !< Output variables for the glue code @@ -804,6 +818,7 @@ SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateInd TYPE(AeroDyn_Data), INTENT(INOUT) :: AD !< AeroDyn data INTEGER(IntKi), INTENT(IN ) :: InputIndex INTEGER(IntKi), INTENT(IN ) :: StateIndex + INTEGER(IntKi), optional, INTENT( OUT) :: IndxOrientStart(p_FAST%NumBl_Lin) ! local variables: INTEGER :: n @@ -904,8 +919,9 @@ SUBROUTINE Create_SS_Vector( p_FAST, y_FAST, u, AD, ED, BD, InputIndex, StateInd end do end do + if (PRESENT(IndxOrientStart)) IndxOrientStart(k) = n ! keep track of index for AD orientation do node = 1, AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%NNodes - CALL DCM_LogMap( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node), u(n:n+2), ErrStat2, ErrMsg2 ) + u(n:n+2) = EulerExtract( AD%Input(InputIndex)%rotors(1)%BladeMotion(k)%Orientation(:,:,node) ) n = n+3 end do From 92a2e94db824446c66ed387f4835c84f433fc273 Mon Sep 17 00:00:00 2001 From: Derek Slaughter Date: Fri, 25 Apr 2025 19:37:44 +0000 Subject: [PATCH 19/63] Use MATLAB_ROOT environment variable to define MATLAB install directory --- vs-build/OpenFAST-Simulink/OpenFAST-Simulink.vfproj | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/vs-build/OpenFAST-Simulink/OpenFAST-Simulink.vfproj b/vs-build/OpenFAST-Simulink/OpenFAST-Simulink.vfproj index 1b7110e1d7..655b2435a6 100644 --- a/vs-build/OpenFAST-Simulink/OpenFAST-Simulink.vfproj +++ b/vs-build/OpenFAST-Simulink/OpenFAST-Simulink.vfproj @@ -16,7 +16,7 @@ - + @@ -36,7 +36,7 @@ - + From 16ac8cbbd10a56690f2db77fcd07c2c08322eab8 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Thu, 13 Mar 2025 12:14:28 -0600 Subject: [PATCH 20/63] Avoid ending program when called as a shared library When running from Simulink, Matlab would end (instead of the DLL). This PR fixes the problem. --- modules/openfast-library/src/FAST_Subs.f90 | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index f8d11cb72a..1b0050734c 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -9615,12 +9615,16 @@ SUBROUTINE ExitThisProgram( p_FAST, y_FAST, m_FAST, ED, SED, BD, SrvD, AD, ADsk, SimMsg = TRIM(FAST_Ver%Name)//' encountered an error '//TRIM(SimMsg)//'.'//NewLine//' Simulation error level: '//TRIM(GetErrStr(ErrorLevel)) +#if (defined COMPILE_SIMULINK || defined COMPILE_LABVIEW) + ! When built as a shared library/dll, don't end the program. + CALL WrScr(trim(SimMsg)) +#else if (StopTheProgram) then CALL ProgAbort( trim(SimMsg), TrapErrors=.FALSE., TimeWait=3._ReKi ) ! wait 3 seconds (in case they double-clicked and got an error) else CALL WrScr(trim(SimMsg)) end if - +#endif END IF !............................................................................................................................ From c08ddba86ac9c764680292a85e4a38d27d3bcf89 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 28 Apr 2025 13:30:06 -0600 Subject: [PATCH 21/63] Update version info --- docs/changelogs/v4.0.4.md | 93 +++++++++++++++++++++++++++++++++ docs/conf.py | 2 +- docs/source/user/api_change.rst | 6 +++ openfast_io/pyproject.toml | 2 +- 4 files changed, 101 insertions(+), 2 deletions(-) create mode 100644 docs/changelogs/v4.0.4.md diff --git a/docs/changelogs/v4.0.4.md b/docs/changelogs/v4.0.4.md new file mode 100644 index 0000000000..8fb1d0a71a --- /dev/null +++ b/docs/changelogs/v4.0.4.md @@ -0,0 +1,93 @@ +**Feature or improvement description** +Pull request to merge `rc-4.0.4` into `main` and create a tagged release for v4.0.4 + +See the milestone and project pages for additional information + + https://github.com/OpenFAST/openfast/milestone/20 + +Test results, if applicable +See GitHub Actions + +### Release checklist: +- [ ] Update the documentation version in docs/conf.py +- [ ] Update the versions in docs/source/user/api\_change.rst +- [ ] Update version info in openfast\_io/pyproject.toml +- [ ] Verify readthedocs builds correctly +- [ ] Create an annotated tag in OpenFAST during merge (mark as most recent if necessary) +- [ ] Create a merge commit in r-test and add a corresponding annotated tag +- [ ] Compile executables for Windows builds + - [ ] `AeroDisk_Driver_x64.exe` + - [ ] `AeroDyn_Driver_x64.exe` + - [ ] `AeroDyn_Driver_x64_OpenMP.exe` + - [ ] `AeroDyn_Inflow_c_binding_x64.dll` + - [ ] `AeroDyn_Inflow_c_binding_x64_OpenMP.dll` + - [ ] `BeamDyn_Driver_x64.exe` + - [ ] `DISCON.dll (x64)` + - [ ] `DISCON_ITIBarge.dll (x64)` + - [ ] `DISCON_OC3Hywind.dll (x64)` + - [ ] `DISCON_SC.dll (x64)` + - [ ] `FAST.Farm_x64.exe` + - [ ] `FAST.Farm_x64_OMP.exe` + - [ ] `FAST_SFunc.mexw64` + - [ ] `HydroDynDriver_x64.exe` + - [ ] `HydroDyn_C_Binding_x64.dll` + - [ ] `IinflowWind_c_binding_x64.dll` + - [ ] `InflowWind_Driver_x64.exe` + - [ ] `InflowWind_Driver_x64_OpenMP.exe` + - [ ] `MoorDyn_Driver_x64.exe` + - [ ] `MoorDyn_c_binding_x64.dll` + - [ ] `OpenFAST-Simulink_x64.dll` + - [ ] `openfast_x64.exe` + - [ ] `SeaStateDriver_x64.exe` + - [ ] `SimpleElastoDyn_x64.exe` + - [ ] `SubDyn_x64.exe` + - [ ] `Turbsim_x64.exe` + - [ ] `UnsteadyAero_x64.exe` + +# Changelog + +## Overview + +This release includes several bug fixes and improvements for _OpenFAST_, GitHub actions, and _openfast\_io_. + +## General + +### CMake build system + +### GitHub actions + +#2778 Backport of GitHub Action to build windows executables on releaseCompiler (@deslaughter) -- backport of #2636 + + +### openfast_io + +#2779 MD: Backport of PR #2658 -- openfast\_IO MoorDyn compatibility (@RyanDavies19) + +#2777 bug fix #2762 (@mayankchetan) + +#2658 openfast\_IO MoorDyn compatibilityModule (@RyanDavies19) + + + +## Solvers + +### Simulink + +#2785 Avoid ending program when called as a shared library (@bjonkman) -- backport of #2671 + + + +## Module changes + +### OpenFAST library + +#2780 backport of #2760: bug-fix: Adjust steady-state solver small angle assumptions (@bjonkman) + +#2776 Fix FAST\_ExtInfw\_Restart APIC++ API (@marchdf) + + + +## Input file changes + +No input file changes since v4.0.0 + diff --git a/docs/conf.py b/docs/conf.py index bb9d65f674..6e5c983e0f 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -138,7 +138,7 @@ def runDoxygen(sourcfile, doxyfileIn, doxyfileOut): # The short X.Y version. version = u'4.0' # The full version, including alpha/beta/rc tags. -release = u'v4.0.3' +release = u'v4.0.4' # The language for content autogenerated by Sphinx. Refer to documentation # for a list of supported languages. diff --git a/docs/source/user/api_change.rst b/docs/source/user/api_change.rst index 06492245a2..054ac176ea 100644 --- a/docs/source/user/api_change.rst +++ b/docs/source/user/api_change.rst @@ -10,6 +10,12 @@ The line number corresponds to the resulting line number after all changes are i Thus, be sure to implement each in order so that subsequent line numbers are correct. +OpenFAST v4.0.3 to OpenFAST v4.0.4 +---------------------------------- + +No input file changes were made. + + OpenFAST v4.0.2 to OpenFAST v4.0.3 ---------------------------------- diff --git a/openfast_io/pyproject.toml b/openfast_io/pyproject.toml index 7595361ef7..6eb3e86f8d 100644 --- a/openfast_io/pyproject.toml +++ b/openfast_io/pyproject.toml @@ -5,7 +5,7 @@ build-backend = "hatchling.build" [project] name = "openfast_io" # dynamic = ["version"] -version = "4.0.3" +version = "4.0.4" description = "Readers and writers for OpenFAST files." license = {file = "../LICENSE"} authors = [ From e9cec2dd2f6bedddec7f2bb92a49fe78f96e078d Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 28 Apr 2025 13:41:29 -0600 Subject: [PATCH 22/63] Update v4.0.4.md --- docs/changelogs/v4.0.4.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/changelogs/v4.0.4.md b/docs/changelogs/v4.0.4.md index 8fb1d0a71a..a428eb131a 100644 --- a/docs/changelogs/v4.0.4.md +++ b/docs/changelogs/v4.0.4.md @@ -15,6 +15,7 @@ See GitHub Actions - [ ] Verify readthedocs builds correctly - [ ] Create an annotated tag in OpenFAST during merge (mark as most recent if necessary) - [ ] Create a merge commit in r-test and add a corresponding annotated tag +- [ ] Upload Docker image - [ ] Compile executables for Windows builds - [ ] `AeroDisk_Driver_x64.exe` - [ ] `AeroDyn_Driver_x64.exe` From db6012fdcdab0eb60b97134562dc3bdbfd2f99db Mon Sep 17 00:00:00 2001 From: Andy Platt Date: Mon, 28 Apr 2025 14:11:33 -0600 Subject: [PATCH 23/63] Update docs/changelogs/v4.0.4.md Co-authored-by: Derek Slaughter --- docs/changelogs/v4.0.4.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/changelogs/v4.0.4.md b/docs/changelogs/v4.0.4.md index a428eb131a..6dcc91776b 100644 --- a/docs/changelogs/v4.0.4.md +++ b/docs/changelogs/v4.0.4.md @@ -57,7 +57,7 @@ This release includes several bug fixes and improvements for _OpenFAST_, GitHub ### GitHub actions -#2778 Backport of GitHub Action to build windows executables on releaseCompiler (@deslaughter) -- backport of #2636 +#2778 Backport of GitHub Action to build windows executables on release (@deslaughter) -- backport of #2636 ### openfast_io From a0a85e7fe5fdd8289cb4885cf27e911136f0b98e Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 28 Apr 2025 15:56:00 -0600 Subject: [PATCH 24/63] update r-test pointer after merging 4.0.4 --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index 1c111305ad..f1f723b37c 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit 1c111305ad6a6f8bcf85e93d323673d0f988d2a6 +Subproject commit f1f723b37cb9beecd2d7578936bb0ef6b5ab7044 From 82103e2b7a1409b8a86e90aa3dd73e301ea5adf2 Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Thu, 1 May 2025 11:48:04 -0400 Subject: [PATCH 25/63] Fix restart parsing of file name --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index b064c29bee..b214af9fd0 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -94,8 +94,15 @@ void fast::OpenFAST::findRestartFile(int iTurbLoc) { check_nc_error(ierr, "nc_get_vara_double - getting latest time"); tStart = latest_time; - char tmpOutFileRoot[INTERFACE_STRING_LENGTH]; + char *tmpOutFileRoot; + size_t len; + ierr = nc_inq_attlen(ncid, NC_GLOBAL, "out_file_root", &len); + check_nc_error(ierr, "nc_inq_attlen - getting out_file_root length"); + + tmpOutFileRoot = (char*) malloc(len + 1); ierr = nc_get_att_text(ncid, NC_GLOBAL, "out_file_root", tmpOutFileRoot); + check_nc_error(ierr, "nc_get_att_text - getting out_file_root"); + tmpOutFileRoot[len] = '\0'; turbineData[iTurbLoc].outFileRoot.assign(tmpOutFileRoot); ierr = nc_get_att_double(ncid, NC_GLOBAL, "dt_fast", &dtFAST); From 617b279fcd857ba491560625f9366b6a91a4bd9a Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Fri, 2 May 2025 09:37:01 -0600 Subject: [PATCH 26/63] Free tmpOutFileRoot char pointer in openfast cpp --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index 9a103f430e..e79ad7f53b 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -122,7 +122,7 @@ void fast::OpenFAST::findRestartFile(int iTurbLoc) { std::cout << "Restarting from time " << latest_time << " at time step " << tstep << " from file name " << turbineData[iTurbLoc].FASTRestartFileName << std::endl ; nc_close(ncid); - + free(tmpOutFileRoot); } void fast::OpenFAST::prepareRestartFile(int iTurbLoc) { From f95b251dfb8da95cf2b1e70983c98dc0c566e6dd Mon Sep 17 00:00:00 2001 From: Garrett Barter Date: Tue, 6 May 2025 08:26:38 -0600 Subject: [PATCH 27/63] adding weto stack section in readme --- README.rst | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/README.rst b/README.rst index dff299384a..4115bae371 100644 --- a/README.rst +++ b/README.rst @@ -25,6 +25,18 @@ tag. **OpenFAST is under active development**. + + +Part of the WETO Stack +-------------------------- + +WISDEM is primarily developed with the support of the U.S. Department of Energy and is part of the `WETO Software Stack `_. For more information and other integrated modeling software, see: + +* `Portfolio Overview `_ +* `Entry Guide `_ +* `OpenFAST Workshop `_ + + FAST v8 - OpenFAST ------------------ The transition from FAST v8 to OpenFAST represents the effort to better From 4d20aa3fb3ed8d18b31b5c60177c658d3ed28de0 Mon Sep 17 00:00:00 2001 From: Garrett Barter Date: Tue, 6 May 2025 10:31:17 -0600 Subject: [PATCH 28/63] Update README.rst Co-authored-by: Andy Platt --- README.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.rst b/README.rst index 4115bae371..015c4afe2e 100644 --- a/README.rst +++ b/README.rst @@ -28,7 +28,7 @@ tag. Part of the WETO Stack --------------------------- +---------------------- WISDEM is primarily developed with the support of the U.S. Department of Energy and is part of the `WETO Software Stack `_. For more information and other integrated modeling software, see: From e835937ccf31515afc91080d90eaa7f938854f4c Mon Sep 17 00:00:00 2001 From: Garrett Barter Date: Tue, 6 May 2025 10:41:07 -0600 Subject: [PATCH 29/63] changing to openfast --- README.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.rst b/README.rst index 4115bae371..2367544d94 100644 --- a/README.rst +++ b/README.rst @@ -30,7 +30,7 @@ tag. Part of the WETO Stack -------------------------- -WISDEM is primarily developed with the support of the U.S. Department of Energy and is part of the `WETO Software Stack `_. For more information and other integrated modeling software, see: +OpenFAST is primarily developed with the support of the U.S. Department of Energy and is part of the `WETO Software Stack `_. For more information and other integrated modeling software, see: * `Portfolio Overview `_ * `Entry Guide `_ From c596f81aaaca571fd5ef1fdee208d6ba40022f6a Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 6 May 2025 11:19:18 -0600 Subject: [PATCH 30/63] Docs: correct Bladed Interface channel 63 description --- docs/source/user/servodyn/SrvD--Ex.sum | 2 +- modules/servodyn/src/BladedInterface.f90 | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/docs/source/user/servodyn/SrvD--Ex.sum b/docs/source/user/servodyn/SrvD--Ex.sum index 1ff9fb6191..83efae8dbc 100644 --- a/docs/source/user/servodyn/SrvD--Ex.sum +++ b/docs/source/user/servodyn/SrvD--Ex.sum @@ -56,7 +56,7 @@ 60 --> Rotor azimuth angle (rad) [SrvD input] 61 --> Number of blades (-) [SrvD NumBl parameter] 62 --> Maximum number of values which can be returned for logging (-) [set to 300] - 63 <-- Number logging channels + 63 --> Record number for start of logging output (-) [set to ###] 64 --> Maximum number of characters which can be returned in "OUTNAME" (-) [set to 12601 (including the C NULL CHARACTER)] 65 <-- Number of variables returned for logging [anything greater than MaxLoggingChannels is an error] 69 --> Blade 1 root in-plane bending moment (Nm) [SrvD input] diff --git a/modules/servodyn/src/BladedInterface.f90 b/modules/servodyn/src/BladedInterface.f90 index 97172488e1..b4bc4d4e1d 100644 --- a/modules/servodyn/src/BladedInterface.f90 +++ b/modules/servodyn/src/BladedInterface.f90 @@ -579,7 +579,6 @@ subroutine WrLegacyChannelInfoToSummaryFile(u,p,dll_data,UnSum,ErrStat,ErrMsg) call WrSumInfoRcvd(120, 'Airfoil command, blade 1') call WrSumInfoRcvd(121, 'Airfoil command, blade 2') call WrSumInfoRcvd(122, 'Airfoil command, blade 3') - call WrSumInfoRcvd(63,'Number logging channels') ! Write to summary file From 16e3d852e469cef01c31390b58fc5445d86434e9 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Thu, 8 May 2025 16:27:38 -0600 Subject: [PATCH 31/63] BD: add outputs channels for all loads mapped to root - only setup of channel handling, no calculations yet. --- docs/OtherSupporting/OutListParameters.xlsx | Bin 621621 -> 622662 bytes modules/beamdyn/src/BeamDyn_IO.f90 | 1120 ++++++++++--------- modules/beamdyn/src/BeamDyn_Types.f90 | 28 + modules/beamdyn/src/Registry_BeamDyn.txt | 4 + 4 files changed, 636 insertions(+), 516 deletions(-) diff --git a/docs/OtherSupporting/OutListParameters.xlsx b/docs/OtherSupporting/OutListParameters.xlsx index 8d622a50d76a07a91ba43b42403b34f9d11c2d13..5cd51e87ac6269e5797b9e09449df0dc3b4843a4 100644 GIT binary patch delta 23574 zcmaI6by!v17cERm2`Gq2qoj0mXaVUEq#Goq58ay->5>wpB_*UADe02#?(T-W55B+p zp6}j2&U4nDYmK?aoNLapH-}wuLG|048ec&M5$PG+BREtzIJlQ^NNBp*m+)|KaX;}X z5P$?li)of;0rM!=*y6<$s$Z;hxR*}Sr}aw;1Du53L=_u8)xfEhj=#Cqq5nugA!m-0 zpi4}wvF@Sf@&q@Bxq$NcPS z^u%i!9%IVt=Lf6MJKXhL%?--9e!uUrzXJey@mfrbz3-ac$Om069?h|3Pc4btb^ZFX zQ`4j9aYL9buH0nU#^dnDr`O#If~EGuRM~K7fs#`pYKn0VP2t^`g?Q}bw^Bl%#cA>6>NNy^&@o+^OtjVFHI0z*I6LDkt)EUK_t>pZdK%O@!g*q2J% z*YJvCY|?i+{mmX_Veasffpt^rbQDiHIXjh?Ws46-md{RK+SOzBQ>aYBwMuyHgx&5% z(Y!=eZ0#Y=LrL}cJ&3T|(OZZI zKCprn0YxmMMj}K2hWn%uS)afy)GhG&&(uv834L~$4najmj=F*yHge+T=<=r=J=>Kl z5X0Z1n=p*-T1g^cOSJl7Q2Zi;TJ0FBX!l7z`cF~eWzUkAL#u}D!m}54>c@=Yf=MZ< zaw$V^y5m3OcpCA9gmCV^KdKUWJDDD!9w`z3ju8F%d)-f}ED`U$!vBy+T z*INFXK@k%~%hJ>9Qm7`N9SI!=RSI50&`3j)cf95K6HQr8HOkZ@rx}T78h!0hg;T^% za{}7;G3ZjN3d3eK^ksBn8mIJlf8K=hqU`XQ=?7&qyYkzTIhopz4@R2ZoIm$0*^?|{ ztaUI#PdyNAQ=>TqF8?WpgN;?9YjAAIlDH0r_eOC@l`dvOD^B>`tF+iH7YRKOj<$ctOGc`$AyL!~TzOG+#nf%+RZHbPeX2RPx z`UCu4Jci~MOwH%1i17w@nt0;9r3mCE9N(7;AB|QpoY64zEW5;sOjwKzjS=7RUr0RH z-uaDFZ=Tp~)~nIAwuF<`7dBjY5oP=eaESDEkyHEGIV6TJc1tr@hE+b7yz9+=3x!tHt#5%v zJ)LiG_Q7+FBCE}{)9`+5ZJADDwLBMuSKJ5WW_6XjQc~oX0Yz^bJ%nJiZ61KX%Ajmj=@NrWn(i zF%G80C7G7g2dP|J*bh`c8OZ3NT=_&~hDE&ecyiB?%=bvgrHopO??`%b?b0b z`il3O$GBf{_cY?PW%1-SI_tnlTl3F~`GMMFl4yObzW33}vm_FuAEOr7BcKV#a_Di`+EnGIg)n(l zC9+bTr?+o*JKlbPaEVXG3`82&sbwSFS>s8h)zkSMT7@1{h&{DisD9By~@H3 zudFt&37oemQ~M9^FYI5j(}j4K{Aziz#^+kF9xSL(ScF^pJXIR%2_QSaD5NDW5YE9@ zm!IdFc@pp`3^W#!z21Znu=^-Pz$d4)m@+s?v093MmBrw*b%P=s;ur zr|HqzC6BTa#wx$&UVyj@QNQ3;&sXWi<$Jqq+Y68Eg}&R_VI6_nZ;yZZ&$Mt%7)@Dv z3F_Ws{QJHV@5Y3JQO1Rx9fI*EYNctE77p%G7(PZA`$f$CS5zQ;isi|tefm=phWQu@ zq|e?eb@WrQZi=TayAa%x&&wlRG%B9w;c}>wlJriQl*{!y<)W^R3P{r)seEQf^y&mA6rf*=ifRl+FOyJScnqD(7yC9@w z_c2dzj+Oq{#oz^OshDYE{y32@#fqWr7U_B``p#c_zEwem3c~-oF?MhQ_pN9j!xp#2 z&{uZ3BX`^A&Av(!TPm%$&oZ8$ZKQvZOc5$3{H~#BI2Y*B3E?rT$MyJQ|3V1Bl|nCy zRgA@qBu?R&&lbYWdATgG$#q}Ha>z1Lf@_V)oV#Kby`(q*NHdk3gq8dVtg+klpzr3n zC2|~xv)a)eB5%<>$UL4Bs!fPRaGo$0<50H0df6}ZecAt0NaB8)9>Uq0xhw;HqbTMK zf_TvDpZT{4v7Y|5;`q_yfWS^Ox(M=i~TxJ>$+6ZddM47wBq#`-TRqT$;07wGQi{hZv3{Y$?N*) zasapm)^mh_TMmz_&5rxqvjMVApy@}d*VS^do{-#fPU;K&KY)zRg-_R4-uZ*l5-W!^gqlH2q6oB^Tx>z?&gKtHb>7)o7-})m;Mi6!BeEi&2L`L-(6re8CM7%OaB_%1?e>d%M!&dCok>d7L%Q`;j8(3+Ju!Hw<% zUhs#7qs);^^*x^C@rq5quHjEHlH+^1bnAD8mta6Icy@k%+Rj@9<)&-o2d97jsZ{gOP&iHpG3UZAeIkM;D)?>D>UMF%MdhIE{uX+koduY$j5rbRK?gb=En#dHs z??lQAhYKK&PPCr`Dmw!tJ2jyn0HHKm%Yk`6r0Z*VmF`dtY;?Pw*SWu$8jC*wHIY?z zKl-#{2>f*C{REH3yxy!Zx-S@DdsM7nP-ErV2=VLK)Q%S_So57`CVjCN%219cv~f~s zp&jQ^SguZ1%NE~K&@XOfQsMYxS#*2-bW~(&;Cm*2bn(wnz^F~}t#Tt)ohqy3+IbV1 zB4gIAHY25;AwixfYXer6f=Q08)Xt106QqAsNt3mq*xT80gIBygxzI6f_7LM z>va}1?Kj)|z-(6%Nzq;t*+!U~NHZV89!Zi{tB&M~Y($E7LK%;v>#APi*|D!*Npm)S z5wA~8?mxDO)@$6B$P3N+5#ke2}2}FqL&=W(O8Mlph6j%l34`&I3wzB*`!}` zeclh6e!L{kHWMh&O|F60rdYHr9LBsZnYlmdKGK?ip>fKhb!z*TGZNDMN-<0! zKRLBV>Q`%EazyK^KR!mx^k`KG`_Qd05aaj3j7=^t(ky9oYwyNY*Jj87YaMm?a(t0k zQ4@*>eZyD|egD$u*m55T&DMeEfJ)N35JyvsC6j)SRI6HvHN-W)Bi8H)_NVwU%FB_b z*v6yMav?+bv~0<`Dx4HmmEJX5AZL0E3VG>co6ImVDIZ`9FOhmZsl(?kXtU(s*8Dbx zpnZ&Iv>7>BS<;D%-Z5JsUW<5`hD<`epp5gm=t-v&ogW6o{HFn+y$cc8b*&G=#X;`q z^8L1}jErx4g1u#ppDhr`4HfZSfM`5fS4P6O9f|f%?w-M$E?;*KSsv5rAVg(h?;VPX$4y*i0cy6`>{z*MB%DmD!eXJa zV1jwHuDjxr97zX}f8MsKh+HOk{vlrBXx-Zoe?PortioOluU8h*os$CI4=kE2^hz7E977pb(>+B1xhC?L#?I21)BAZ|C&z76 z3rDU5>K7ppfqeb3{Dn!(kz91uK-~ApHEi4(x)0l`B3oxO0$8Fxt!R0^%SJz=cE>W& z?Osk!?)064UM6>5%|0F5u#`}Kk|TjP)2r=6l6$;9$P3#yJO&x+rra!7fWT+qK9DM5 zD+1)h5)4~dPN%-p=XghKyVElBbZpDABte0A()uAF*AA?aX{pS- zgtJROE=^6@>HFpM-g&Y~Jz6AzY6!MI`aUE2{=_KO(wX zJK?5=A~EGhXfsPwT7d;Pk#!^X{bsW(yyfy36^#x+ZTN!^ir%bcPm|@0!Uvr z=OMg%a6)+{Ms>B>wH9;36FEUe^w@9i`-ATbvDJ%zTu3o=Jm7h}6nVVdO6^~OZvV@s z;Y_G4n7$$~+2z+Crn$w1!sD)$rM(6f_Xh?lfxdk2n4WyxfrlXj*BSLj_eZX^{urR-aWkV;wlI`zq zRY^tr{}b~l&)i;c)A|4fb3;JmO^OXy2NnIMQR7)Di@h&qJflrrn-@&6u=DBMH z=F%@EC(HT|o#++=^{j4kh z(zG5pCoZ?!=P@!i4redZTNq6AEVUOMNSLI#hPwp2MD6I9ts`-q*>lQG zSSlKch-_{>C7Y*WrYDo(b(i)+du~{oan9p4`9FH$FYEi#k87r-?|m<4><8WIA9%`g zVOzy`4qeXdrVgZvx=+MzgK}LAqnhGzmjNy}ND+##1^I+42m+g3>ot+p{j-%vyIFU< z&bv>$*Yiv5+<}voWBhLev${t&JmrD2*0%l?QxsnY^cLhBJil#w>^W(H)v>z>IV+!E zLR~$^uYPA^zu~c0scu7qY3qOFDmW=Y!*otxEdw)K>p=II69&Eoc0C<4k5CXKOIe_9 zKr4;KQM>A+JHIV2lBy@^QN1lrC1j{=EUoLs?QI88^c^&tcm|?(%bzAFd>}j8oD#5f z@!h+>6CuB3H?XVX(<9r5_Qj!nKVL*MSwUpsZLY&Cy#DCfGr<>qUQI1a+kyR# zmRbD6S?W=)foE|EOdw$pK)fMW5_#A zd$RRq?q0?OqG`hCU(vDXpfA{7l*x{LV!H(BnlSFMxecJQbJq;2Z|!GLANjBZDO7S! zhu%2hme7X<66&-1U1*g?J76Y4SpQ*Q2VakH2_xg<3D^>UGRlY!S-q*NP}B_5*33*3&8j z-uS66z0U%w(QV@Oc`Okai>00gor_kX>W;Ael7Wsi!W{nL2qa5itvDNOC7^L}CdlmR zw>}j65<4xC=DFyBH^($-pMa;SYk?+^4E2qF&ixrbRTED4bHRbr>&({7!K162YgXY` zE+7B+yBtnFS_r6S+c#lz;khRr^N$0@R|cyVL-|~P?pTh?lVw;o2o1xCUTqyPme_YU-Rq{@}gF(sxK_(}@mj8(_;;xqNr~WE6}{iu{xgl>kyLP-r3YfRmj3{z;!k5e8QfsW)%&BC6t;AF z6N2rnzMMbONCqb2GB9-b-A?N+6w^ zX|td&{*aAXQ&fJeaoq~C+<(?y`m5(GM%P9``|@g5n;b;?(TqKX9JbuxUCHCXNIv8U zy^o5<;zP8Hu%5x>q#(uF6XWgM#J{=N5aiJy3v0tT{@)B`W_3x7b-z6HZEPuRBN|b2 z02;xAZxp%j?%I1NRnGzh7@J=I(BB#m_7sDHC+ivTC_d)2QWE4`!f^QL6z^LxSbW8U z@b;zDBw(FffA(m*>h7y5>!DuBl({lzud7dqI4PYCac@F(Gm{^aq;S;KtUTUd?lf5M z);v@pRvKSXW}=GQ)t#|`R1Vh~1AN};#(dt2r+5aP0%Z-BIlJsM+dz~qkAII7=_5=I zfzYDj$HSb3Uv3!&;u62DcX;n5mN|~N)OT!-8i24^gIW$br?M|Bd$+0^-=tXTHa@oG zUUjqR_=*vk_K*FcaAZ$D^@*EY{>ri?oX#d2PdHSWSjK+;VvyUua*Qw!NE-6v8|)kL z6ERL;%1f7HH(meAnr1=WJm|*pj3gfa+w_%>d5kOT5-YotZ_h$7(o*gUz1 zVNpKw=ITz~r4Je2egr*5)!!J>@eX?J-RE~?$34uIc&uMFkGT;e#fYl}SKDaUU?fo9T9KRIP?A{01y7=x?-)`ui0O-$cmz2EB&U0rUv6W#G;HdR=WJ_A*4N zo7cq(bCD&AqF7T0PveB5j|jUOJbb2M@QiF|)Y)(_8xwMx z9JtGU)F%^dNuRi&zQ0@9!%flHJITL9Ar>l~13 zE&H94fTde?^e4L*J&5dw?`Kf!pQ){ZVry2)qs8alh7n=^th-i#+j0f1KFhot)LJAG zK2r;#NS8%uxQNC;NJI|;b32}E*I5~(`e2ED%G7t!eG$xchbUj{*6A6W^Q zT8RDws?zQpOaCQvl-E05apFUoURFUbS$_bLNdK|k-eK$$zXT%eDK;p1wY2S~&qNJHZ191uo`D!M9p34AK~Op9zBq;>TSlPox=ZOsAKM18!%~Ye;5QAf7 z3YJZ)1o#s!J=69q(nREF74vVr;`u(&Q@iVo<1I@oG92cO0uhaC5mm*?l!yZlFecA{ zyB}qapI~}~ZY%%_;o>Ejf~zgt82FOsK-~%6RYU)n-mCvm(Qbkr5*RTCpB6@N8^%?> z!q_pWV=2X8N;?DYejYDXcBDW*c!*oA?P8Q*Z4Jb)6?4%~Y%jC-3%j}p4@amT*l9Qe z{<@WIuz34R$6cXRz0*p`jTOH5JtEhjFSq5mYy0sVJm6}q|4i=p<`uH13hnk@1WPz9 zt2k#>_&chD^G>?6XI<=jmh<3ohd_UYK-GYrjBx` z`?YB**#^^QcmsITG}CTl3Ry;C-pp=qXo}fBVCGnW{8W;x8Ng0D-F4Lc%C5PibZ2ut zS%m^DBQwW4PSXt4#k)Z7wmj-v4}2TZ%b7oZZ5PB%1@98+&de3eTlD9_go=S4I2D~3 zS9HH*rc8el!7@#Ma-lQh&LyVd3Lw=(0F@PFPrL;xxw5HUq#*pY;z5iA7pUhG7ezfh zSA#nc_tm5Vd!9x&p-E&wf2sXcctH&CR9Oi)ZH8n1m^#`R&H=kyxnUIVk$lgv%oJL_ zQHjDoQSpxF=rccOd?+ws+4^ch)ZLJ){9k<0M9>&#W@B#s!n4=++)vM=BBYIXr}H8G z>lESitMgHhLlEn;KC0HmQXF1g(nDoWhDZ03U2KUDGaBhCnS1q+U8E?0LMOksOQ*+b zOX`03>&4o@+HveONFCt;`HlPm`J*{x+wYgVm|oaQDDeW-ZrPLoMbP**=<=wxD&CIx z)HJz??rfdZlan;1!_CXCf{zuacwFs!>6xoZIK>?OmHA9)WbqvH&i9!MOKt;7-Qr?t zuo7kU4ljZ3ahr%n!ZPGCb}HT7wJ&Ykrz&|r8ibZ0=JPO|Wpr^BnEtv|ibFR~s_?w+ z@#Cc%yihf@lTk_WexF11)7aVCXqSdYoDRZzR?qfz`m=TZm7D6BMy=Ptt!7=zVJP3J zO8Sr4b((I~Q}&Kn*Tu^Mr|S%o6Z7-9`Y?R}g)uzu?6f{BY2m7U|2?eibNb3|`kiRR zmykW%jd!y%0%@ns^gQnJzX05=YumR3;EvWYu*!%%*_yMa@8)u02A@V8E_q=*gQ&nh z5=k;$3hUDg;zc-CTQ-^S_y#+`Di7EJno-Gt2e@(kG^N<%_N-SA2s1-znDP_=8y;lo ziNQE7ygV9vSpa3XY@BP%E#9$C1RD^&FiY*cNK>&AdJB^YgJVbC5jCewS&(9Y>L1uc ziA$p$u%|&rJcQ*|LG<~r2sk%+Lq}4}x4Gtf?~lF>{5e#|?)ZZBTq z_Z%z`klqcG*c=nz25hS;z4vXvx7!+pu|n)plJX|9wrV!mgPqL!=x#i5GnOW?((d*i z%1^8psjNl4ut&H*t`+V}bN_O7DtyEAps!$VrkQzsNy;H(3z%Er7XKeBwd?L&D@unV z@cXnmdTyfkOR=C34;YU5c^mNk?lDYXXUTq&aD=MGpNyJhdwj!BZL+(jl6WA!3+B#@ zS!ZuR2P^{^X*(o7GpOug?KN_x->0+o%YqNU9w^pl^-}`SJR!e_8;Y=Jz&d>uEEv%Z zSTF;SbZ%R#p}jJxWffRzqN;k7-QEsti~_sy&!99m=|Aeo+8_^cx^ERM#ye2mM9t_- zpJSNOH%tjc*ervO`iGN@b>l}byT{g359_|TzVmbp_{+0nI9>DLg9a>ghi0bZl&dXt z<|6Fc+vw$w9~fO~e$?r`LA2Z&s1{TwOyv&T6u8%21hwxve{Cey0JuYMC|0W*XFFYA zxWW4!JAIzqRNDf|jdjzCi>5)y*=lK{r{A`pS(VP3z3m1)E$=D00YlT*kxREv4NBQ@bEAKbq`ap^^W=8Zi|@4OM_x9# zk$aR1X%^o)h%-^S0zW(#I|U~T>H^v!wMZ%fACa$*2k!5VF4yOW=Y{T1Q<+nTg@kS| zw{xIn1lmETN#t@E`vPo*!6k(MIfX5uSV<61yM4(IA& zT1Ktf!GQc`oNjD67A(~|E32DtfoxdTwxDCt#ygp^drh8&iN>O#RL#T79~@HY7$Bqg zOTp2^;(Xhk3~fORRBnF^5k5_4ETe~{@gYFmvMTqJWFeG~)=Zt*{h=e1$^m%E_ET%! zF+ElM&m*2L=a%K6(?fIyw2AgD7ZYlm(2a~@NU90=5aku{%&vFPv3frv*_P8ix$c|S z3M{>~%qe(pijj|Cm8SFiCCV;WICQX*uVJ5p&&-`T)XzdfO}%+D23q|L?G#c59dfcs zC5j2J#s|1dBftRT9m=DekWrr7BS19qs<{WlcCs)b!YXNn<@AsP23a_XJl`aDl-bXp zCb`eE*~2sYv*~^;I0#55?-spNu`P4Y8di9-P3w=VZ8L{J~G*?Rw4EW^6nBWGPF~RVDJtA%LOyvCoec4{N$pde`2TX$5K9%_!)Mm$VZWbEG?_&p&ZT02oFjv0 z6k;5-jAE{g?2VgDKlo2Z#N!~=$nb?Rd5*sMZ`9O(zqDViqysv?BZa$*&VCN>;65ki zc%T9v)O+N~V)dnJA41G9G#ZFn8vWl8B^aPHmbNchB)4NF#KX|?h{vO z!%wowfAZ89L={eyJJgV1>uZk;7ODKWw(uGH-#q*OI|e`{lF<(q#Kvn6duA7+N%t4L zN%?!{c%TOJ+kn%tO5$+SFiDaM7XO>F z&A)kf-;^fiR>+)WT0~m^S0OPvK9s|V_P-R&xL~tK0omu)sUakKmcvPBL zNFkFB?r&9nW_Ki*v*pb$MBqN?tJ)a?5Dd11PHgydYrd-lI#1ru0xvG-LC}M zUy~*qjFc1hPZwi*^&rFJ{^twO9j4Zi$q%r?X?@tpD;DCEHisYrVO0UE|1Si~ffM*tgfCQrBUm#;;)F+@bZ>L`h4>eAn%kK-`7NG|MpYq3nK`2 z=#C8?RC`VsaU^M$KOUChTyzTn)?3r@4`yAZK3C`V}*x&;jF9)eDMjnKqVIz;@duW^D!hwo>NFC!C2sUs)~r>|ih(AUtn5> zDFEvlWiUWc%XT3TO*8IlKdqmWR=oZkp8%apsJBOn45nI$oKu$ny`xn2gOX)P{U?~6 z*w?l*)T;nmABT-K5ktq20{P!8Swca|Z^B3u{6Xzd_$SfB4-9s>{)+)79aZ=MA4F}z z=~P}=qL*>+hwW4B-Qbm}FN(BNtg`PhpIV6ih{QkJc)i<%R3I8JR|S!PIKWpb=L|xr&@i{-cD2!<=f7 z4P+1PXAc_x-G0}SLCZ&2R|<18ToY)^h{9MX84$oU z#8ebULX(WiI_BtEx#Y~!D~co*31R?zpKv9Hef2#~2j<9zx+J8z21L|2g15OdqQ9kq z20NI4xkiPRMxaExuBZ-p!f4B8M#Fe<&{}1mGcJ(ZDw+TWOw;x07?vIK00b+}>WM10 z`J6tsAwgC#ut5G!JlOHMXo$PdLZ-8N!RG@|##^QjS~{}}AK_nnEnWMk1bE|~aLx4N z6XbH^w)Et`(ZXc%18}=W z+x!B6X(I#6EhPX}ZY+3lTI z+a=OGvsa%2C41hyALuVuB6M;P*mz~{sT6pUwP(WQ(onWrb@9H2isAm(o`DXnO}l+E zr+o@KRD6<}LvLT(p*w*~qGj9C-2|wzwBFl2;Ik~-T`z;C^o?s7@}0KC7MQ;~j_aG9 zCs_-$s=W2E;?lDT+kJ+uHsNHI_T1FY^!TGWwq+|c*```Re*X8D8+mGj&o1zL2dw3o z>wB@`)zn%q`+o{I*t_Dlni#rV`ttQ+GbYtRd6%Xv>*~#%q;so&JIM=Zf2;y@L|<^- z`)@8Lm^GD2Ek)!#F+J)UKZlIc^dPR9*t#^#I;HDR&b)D*psAcZJD!9LtZf%QrcRn( zbgb0jROjMWAk_{2H^n})s0sfbg9I}a>1*krYX_vt#k0gO zZJOGn@?tBmSU zdCoMRr4It{|5PbkkhZ+hIuGn?JFo)=RRel9tow(Epg*6#-qgyM!Z;^PN(F8XZ?E;v z=kKm|d+rhajG6dk)AYqv5ISb#8Wu9HkWuGIuyeAH}+`A z@jDnOj{)$dKX#;7`pEFGcm7law23-iK8Gext(D|o?R`t2Bv*V{j$?q+F@HbcLOmQ` zMmrSsy3d%iwQ<>?jgF38ch}^iR*$TkY9|ApP``GW@g}iP2Xd}Z7J3lYW;nN+g-1D8d0N9T0H5a zFj7mD&KdKr*X^|CB+3EQJ#+fH-@%aPxnxv6W|^tW>WJd)}zG1cUB@JDn%%o<){CHh#Z7cD|K^_Oo9n7Sr^54STvPA(bG zMzPA;VEcH9fp%L?*+%c$w*`;ZS4PzKzLwMue3w299}W%^eEHAC zlG)zD)za9W$;HaDSKTUNiR;OoZr=UN?(;}|9LXnLA6oud#!0D}ToNJTCK%K2YO_ZEz_Y0$ULF%_yIHg1T z6a$8jqGo=)ojGqDC!77-ggJ8AqZQ&v;-Gaa14@48NJ@H< zN_D=N#R}krs|Hy|xt)yi@<<^uyHcZgTO2V^pm{L@*7}dArLiQvJxHQ=6XWc&+^LG* z+R6Foea?6nkxgJ)I)c+^%r+uHp3By}l6Y9mpc>)5=%mWQ*z}S4bIa$#q#=&QFBozN zj`}rj{^`Wr>}#K+W68}mKiP>m_myNmGOwI=<$<3r5LW6MlEjr$GautCRFM`=Ido^5 zpj)G_0BnqZ8d}VvR4i)!P)jH6P`#}QL+3oFihM`ATl0baiJZZJG=uu%cNLYl<@CSS zU--xWc3v35HZ4Y;nhbZo!=TEcRB3EVITs*l`9^78_G0W8)K8zka@2GOMKqwn+!Qx% z2|cGIXU457<$3q?K-7gl+!I|Q_#e#>RD^lb%SM2#T6EfR`_@qcP4md~=haz-=PKSB z=82UsK6a0>htc%0YC+gz>x!jU0mJzrP`YGJ(V;I(vIwTWKe)H_jzm~Hzx#hCl~eK^ zOMaQ(qI51k4L5Ecux(Y=Y{84(6fvfMu1`W{ z)JP1d6_nm0gHVfVgh6;pJ|%uWzwi@TMKNi1&A21p7@z#*BYJ$a54@ z>&jTB-?ihawSPj@t_H$%czn`)leSkoAP1`e!cF<~oQx?XOTOLn{8RY8C*{~=(uORB z-j7~vq-rBI@K)h9#~V8B*C4RA59MfzXNVuRa~{@q@IBc<>bu7@b&g%N>)*5fYQf{q z=j4pPk(4r070%M3w&&dFZdFY_PfnOe)YRR3f=lq`8-uXhNKbP(TZt#r_dF5F-1{P6 zE9jZDmKASSVWqza`t7$J43^<7NUEQgTD&xb^7MzLg<71n)IxZu#*}i^mQN;~6iXmm zSFYZC{_$PrOtsATbQV|m`ts$GQP-~@?TSt0`N}FiyePBV*n$a5kFD}Nri31!ie7Uk zM_ZBZnBEHOR{wY@ayxjJf%Bp6Iq|a_;Jt`3)?Gy*dHUVC9T(Q~o(WbDi#4LXC+^}4 zea}Cw_nU@@5vzxD-sh|jelpCV-%G) z+vjsju?*WON?BR2o@4G%^ljT)e|r_eUn{067VmqG8lcGb2W^HGJ$n3wC<|=#$S4cf zC5)Av;@dBaQ1~vsm+uWdND5d#k?;FUf@W75)aaz|;AqgU>{;GlTqNIb*i?<-GZ3r$ zJD%?X^%&kUp7|1$6vKswQ0;jvP8vfqb<_iMz@ zTEDQZA0+akgt2_@<)Qub+PGhsRra+#RxoVgg>1a%HR=n(?0#X2e;fY`EvOW~c!i3O zkeU~70Di*{#4mu$UzlzYbF_ed(_UnM;X!GC@cfAO)~f2s4Qd|(f(Jv@{2l5F0>FIU zKHsQOe>u&4+?>?3dCxRg4!9n4@Y35pHW-?BZN%!FzHB$-OJn>NJ}?cxyY1jHw|9B# z(MVtI-Y9}XcGDbUpL(@4!+pI(oMr85S+)9eHm*Y#ZU_07F1cmY`E$RniLS=MH`lld z1PJjA2Z>0$q4}-3yxv>uhf9QXEw66mCm5#+x>`PcwcGVW4YkA`xWBubwGt%7 z7o~y%fMCMAK)ax@;KPjmc|eHg8|TF|!bZJCQ$5+vS?8%O&xYyc*lN@)=JTq=8^^eJ zIb~h9`p=38&m(DHzZ3XQ#g`eS#&N_L<{?2bKirAUar9MOw@4d5F-3`x=l^F)P~kg= zoj66Y*@_n7Ww>}_P86BhN=1aW>~l6%cQzn5c+!@IskFfq z>U3dey1lj(WDM5K)nNUS4KNPtt8W{yXfjzJFWR0aSV8%;`tjZ7qq)wh+fPr^a)9?v zcz0J5d_=;R_&%1rw)lrkZ%a4d@(L4+%PAM!S9pXrc3ve(Y=tnyH@?6-0zxMBJz_i= zKgFb+6!Kx8Bi1nAD-ls=bKL|9CW`%O;Y+U9yN{@g33!5kdq;Q8n{ciiBXeiXrrY~S zttZWib@Fn1$Bm1?N`CKyeR{QZK{LSC#CW8^)vJcwfODUxHc*T0WZy|4MnsOUbuv)v zysuYTyyrZ0PSen3#!Ik`%shTJYFFC5nz~BG5gRyX$FFY0hHky05!I7c-ShiO(jiuL zQAnwSfJGz@< z+@rer@zo2v^C*?6!`RT&&|;$-BM+)&nq_(dAp*Uwi>?dl-|v2_v3apIMjyr;o|atS zxJmNG3nQc90sk`(Y2>ZAT{O$U3$@hqOJIX1Hh7Ku>t!4`Fa!s}uz@i+Fn|qAU*ksl zsGbYE9=wr>_kLXNfY$l{8Wdc&@w=pbmwEF@vlhwd--GxRWVEM%by|bxBSnH4(073hyUP zs{qGjlYnjXd26rrr89Gxsd1q@OaGqnk%_9jI={0`xId3yYmFMFolw?#WsU*+wY{8M_N=nC33p9|5wJ4Mb=Hl2^JL_vE6n7)=+B_N6gzrGtEW*#xD=9V*f zDW`n@i!A#G8TS`C@IG9+XGvmJqg(N##!W823=bV6My|(puEV~XkYh=RhX)0-%*J(B zNA1KTwx=}HZ>X0{h&taATOlTXF0dlUg;ru3z1pkvk!@S#iVUir`H~3!p;ZN5?t+() zIS?}r!+3z085T9$SOc z=HN8FJBQ~?Q+5VTHaHK>&)c{yK^L1;K52^qZQ>lDEfvJ9%8I@7SQ|Ql+9w95K)RJr zywn4h%t03?Uk>034vnfrBA%@LDc` z+C+Xh$A_8|T(1favS9;Vn1u@*n7}OH;Dhx?#?fA@QhWs7n^8ZC_fKP{{pmh9BuR<^ zz1FySpBJrO;juQzWxe`c6{OsD!xa_$Vj(MUiMkrRLgkJMPFSRV|5SA5E!~G;5EBXo zAw1R~q!WZt^L)&&R)k&kfLEVtf|R{bd$bUOtYmknrcB;HJ)U`sf`d2Kb-7QM;&?cgE@czsBWsYtz8F}m?m@7_j0yAFgb8ST<=K?sBn8@n!o7Uh1w)80G0 zfm$Smrd~`M-L$n)FVpmM5(xb)0H-Cu>ClgCUQ6OJhqxGS{J@MeIBmjC&_t$pboVBB zU1q23hyP6$YSItjvyUw3%aG0M176Hw-J#>pNUAhoPR=nYGt6w=wPoAd)L zt?laS(aFRqN=NsaH~O*gjIJ4%NvNjX3zyIxfmKUxwq7+VvN_I2YPi3B69eeqqQ>_IMhx>PD<;mQdctzRG#z!i2WY zTc;;ZETsONYDbLri)77a$ojQv>0 zm-I|Srn~x#7*g|W&d9WE`lu+3sjqbyTjoqH7|WJw69RUJvSWPajebnuRTG~Bw|DMM z5yl}L(?97fLn@_k)(4DOrDxsbz+Z&}A~t)5zX*gdO%o6m&1q0)lEBHYX+F9$X&YwBKb3T-c%!{VRB5kvSW?Z&Lya_^X)c~*KEC67h$FQ+ z7v_&CM8OE;;>W%OMha#lg^*RXyq(F*kK+VhI0ZEo%O)jn?8J?028&CHwpfo3D4r4K zOZ4~X^!F_D2<_W>34T)IqPq2M+djmdCgBzpIFzkjx^B7&v~){~NZsd(SHwgk1ZsOz zx-zo;P$sFl$OPXFEncq<_62k2P-q8nRyZ6b&Bov^WZsCMh3IS{+&D6S&?Ev^qR|F5)G_v?8HxQ~f1% zntSqQC^n3`cKQfoG9#UaRPJ}}L`BKu2}50sPTKma?@dqMn_!PGn>Lb{tPp^-(!S)r z`)*0I;d^JFz2p7kVC{mcXElixLIJPFw;08&i*DYfcUHK`L?sE_DAC##&H?XN*68n_ z{ar`!=U?mO&;GRz`3|=3?%;cM&rx8rSxq(GbUN3{q&|OqvF{2H+-0|y(p4Df<9mZh zpwMM4zD+~n^1LW*+VZ-Yws&M|D|J4n_oSN ziaLXLmJ^&576cmJf(BZ&8N9eO(2(>?=g_uj$%Nvytr|adLG|PW`V1cS4?1hMsV#n1 zrsr--`q-hro{&k4ze&MOfx8h$0~pC8P~O3L;UFO#DIXyH@V1Cma;3MQTDA6NknDe3ZY?$VM2KB z$2Y!HZ`r!To-wI1IN3c!Dd4k_wawuJM*nY@2lr{6h9eVm>&b+rYsE))GSZ^Ieze1 zt1SYV)1l0BLYJK5B4i_pa%Nalu@v}`_&_x^ENbYIR(!Jg2E&_ckAreXgG~Ti8^i;# z1)8jTLKT%%&Ef82U!v9;)o{4uEN$|gUi#*8{yP2&C?b+7q6XQe>aXuFVF?jt5Yheu z*%jdn5lRqo2_h(}kzMU5h~R+;4v0{Fj!dM@>w25_1UH!s{WoOj`(}*2Bu&2|@zwqP zPMvKUnOLCZL>;=>uT6K>btcWw1!e@*97*BhDo}l59;Z!_1l8|W>P2LlP~BuN7=#r< zbtm^9?Ot1{G^`A&Hd4QhWS=+%M0_#ePpJ;&UZo_?QGVU`8P(o@tHZI*BML0M{2+7R zZ*_1oDt;}OK!bL&0J3LfM(w28PoG2crziL*i3L%hwO8)g`S`b(%9hI|ZF5I{NL=SH z2gbD$cfb@vDG(qiQP=;fIMrUfrRnQ?ybO0TMby=`#b%!^`!_qtJl_PK!U&Dk$?=tK zJAXwMS~p>zwWJ>QXFlwlD5l|huGAlR>x8Ja(6lo~ZJmM|z$@tRs$xjeI9Z0Hig1>M0VRuC6$BhV$ets`j+Iou8sBKwLY2}!oJx;k26<$-vyNQ(O<=q z!DP%Wpa?>^vAS}Vt{`In(!etQlL#9-;Y{@FNwm4_rRy8iE|WO*s4w&EX!m+Lg~iUb z-JkCQQ8K52yS*{{fvrE$v@Pjq3Pcuu_Gs+xLZq$QOk#*X$9J6dI3m?^uD;(*I}pExv~@|H_HCw7NtNElxrS)0?WwlHFcZl8xsjw zC-X?)lWFX-^@)IXng{l8%4M>m`^{X3-^S#{MLnG~9%UbPCJt%s0WQG-Uqi{dxiPB9 zU87M`qQ@Nj*U!lMZjN@r#aGK)&bZJJ zi68PnV%Q5sbgN}(;`6N@=MdY8Zp4$y!GU%lnzqq&-?NctQAX_J%?z>mkOlYaah`L} z9YDg~EY(gzOi0z0(wfr@UM9?ww`QWuU)4?Ys5cx|!Wsh$?@#@y_$QE5q4e;dU z-nnP9;p}wFfp+7{$Hw=CMz#{$5~%zYswl!PaNct_S>1A7E;gR;nCPC0YHFTdOfVc~ z1-`V_Vr^gDD%kjlUnSrt9tLGR(_c54%$)1H2rp)7 z4U4lqp}SFuFup3In7Mjmc*CA^uR|;>|3{5+on>TV3z}{p^ch>dr!pdsw3>=AERrLWjE_aLq6WUWb)C2V8fNo1vhK6Itu1BM;aYS?h&ee~SzCj<#9gR71#q z<3wN?qIcy7XcExn;@_%le#};VmU;c`@@j25-&EBna3uQ779DYOtTW%Vm%q&`4G8

?QwI3A^%VhYD$XtI;TqV`b+O(i3PEic;KHy>JET)m20Ze>36mi8nZ*AX61HgFd}DP`SKo@_yqgiuM5FMtZQNcw zPrCI5!niVOTiV^Eh51@_Fm5w)dDL;9S15hrC$RpB@j*Ud%=<{_-R<3r4wG^-Qt*|R zpPAqaKUGHMN?a~E>G~iS%3Tt0Y->3hqjJ1!Ui0J*3)w|W*%#g?=TsNVmHQ}N>q7jf zOX(Jh&mQO&VcpJ9Zz)J#b(y1LMeCk>a%w{GnovTi5u0I=Y`(Vl)%36Tg*#80#y~9^ zCV)`gM%I6Ba@mtdFN;^iQhi79Vofe@e~-sJQV3CSS9j7LM3omKCloqelRY|ii(daw zyrZw2aZu6k9V{68i}stQdGfE&f1UdojwZh!%!}fjfpVReZ+%+{-fqQ z1lS5w91!I~)cGjz!RB&M*cSDh_7{!dGvkRx5ly-eHm?FR{fWYX)GJJdRL+%l3fCGj zhKi9})Poc+7}be7qLFT1t?!Idilt<_Tm*{0$U?fMruW`s(Jr!j7)qB*o<7Kzn!2hjpel5+mb++b?bY$&l8v9-fFAjSyCe1deG0ccB2YXJwgxNTQeH4)UE$b6{vnWT&c;swRpU5ag840~kqcl4ulnxDG zrwYJkrAqSS+z`5P?%7s z`#b?gYKD%~5=aJ-PJI=bqVyE$$yIHca4^3qB-=j#AfkgZ2KOoy^cov`b1zD{y#KY- z@y({BG(Str?ORt)zh|PBf55c( z4GlBt^_g=u)pL%i4S->CKUiJmp|M>y@^N*Jh{i0RZ^g)e%xIA58a{cDyM5{F^u<*@ ze9Y+Eo9EMu)XcVXMD0@g3Dw4XU)OnCGbZJ8Ul6u!5Dk*++mCED`xy5Q;&}yc^qDp+e7=F2i#QbHUooe1lcE8F2247={`C@rDFL&!PlF zaibk?+JHUpwSZTef(7lGnfN=&2I?i+<|aZ3ch6rkjgfpDr7nqYx(5i=uyc_|en+Yj@Aa8gA9i zJMy=_pI^8R5Qtw>^&9-%jwEe}+ZH|g^<;Mfr+2?LvfLo#NWm#G?3O!y#Kk zLsyx*PDHG~oYlgLLEmET994}}Lo8+{xZydP=Lc1i*;C~(Y5oJJ(ZyQpO?{>8#*~l~ z?O$_S^IA>-?%&KlfeAawqabhq>lG^08vEmONL&p*-w3<=e<-B zIUouvRvh#Q<>qVAiGW`;~&_F(H|Auil;X+~OrVT^`0o zYD{J&bMr3cWO|KE_qN*~NGJL5>twyT;9iq99k|e?rhnPkVZ2IqnyZ{L*a#1n>`I{- zeyBrlV!TIP93rNzI0D6h00rZor?d3wA;WCmfm&}Q3x*;mbP%h|;R9c(QB zsBG$FZC^N;9I?1gWmD|8e^voEPIL{n|J7i94Wv0R5ve7cNld@;2mcI=*DE1Q52C zdmUCci=u8^r(p3tSlP_SbrF3p0c@JY;{s?PH-3G|WM4J(R6jpsRt#qxrrn`6^XWSw z;PqJl`VvyYMuF%QigixEyMh_Uow-tE#2$pRCeBkA~sd0sN6k40;*6sEa)P{cNiZ@W4Ec-C+? z@a(Y2cnQ4xO-%^H-j0`*VO7w?trv_A_^{2{nyT^M>E4A{nFFfdFP>{}a=;nIYA?CL z(G;~VI&d-yz^II{wh4vCs6q*{SfDe~^OmlIuRYS<*B)`r{-%SwmWQJ!DO|?nL%(YW z7yZ#SbNEzz#aTCo6j6fNNbb%N^{)7tJU%@zV=$m{sjNAKwl~q!u_3tQgMuAGsU$1g zQjb-W-zv{T3az1m89epr?e`?c-Z@6+_Lva;zJlrW-FWd|eN-?|^mr6R(nJjXivMrv<6FJG;ByfQt@d;1t2H~LopL_wBF$;TYw2s(+HQo@nW zlb6Yy4c}g=T=AW;UFg^Z;$&NyQFe5tX&QRZH z+FK$+kLu!^R59KbES)*6511#ZJ{tdK9db#(&x9`iTxb_+WON zW^!2@)?*};DbaSr0Xtl)?Rjcgh(qBbjcC1}Pb&{aHu&VwXC-0%g7L=SdncNB<7Tss)L9D` z_A)(V{8apo?IV(H?snuAY6XUN9%G?T3@bmrw%b4(&p`;0W?hLx-T9 z1eSuqFmE^$2=|6SPQ)S5Cjp^o5>TTszd#9wlO&T6OM$!c58_2Z$XfFs|l>XQVAS_N4#+A!{LJX{$)67!9zh_0HmfB0__8#S?BRXp{1(<(2{~;hm1rZ z^iXs!kbp1PpJndIZ6YRr;pdq#s%y~_33%_fy?GCo?Z3Zg8mHqYO4E<$=S6hKGsh}Jw2dtuB zo|c(fqTS_yiz2-}%ecUoR%$y^ULgL6g~2(@>@8js^~w>Y>b#MSOOzWLN8&KQ0_*Bu9RqXWhp=Dn#N zngXtkzcGSP=MqZ99jL#%tq3gYXuqpVYKs@Xz6v}P3PFAmGAPEy@Xf~kRSQJgcZK#v z2<>a4g>N?Bm~o!d1khxQ<)%gCc*|s?(B#l$w}Cf#-ZDifG~GN`I^7Ay{xFQ4qpam! zL|4@EE(WiXZwBkWk=R)o!N2!NEncJ>KtHTJe}PV!Ut?M zsTFo!U9-^@`#q9AN6`-C=6Y!0g~nDlmZ**!`)2yQS#-(4yNZRLUFMA+D}&mxkk80C zC|KGJMsQ$`7vM@|;9tT45%RK6n4kL}ct5=AtLL4ec|BsmD84Cgcn8ZIf2YeCAC^^f zcOfBcpI$-YnpEhN;u3%Mxg^s$^SPTNW{fzpchcw4T9p>ryQ(V07m>CS-*=^2yk1-6 z?&O`Zey3SW|8ph~_``l$>?E zTl;_%60hBp41vqKt2z!&`9jlPSL^N{X+4|OV z^V;AE3AOrN>gIv@u%e;_rC-96={R6=QeC1#>aK z!GP)@C+5I>$u(H>53vrPkzbT%AhyFH!%&3!ox#Jv_(j^F-~$@giBi~}I;Ia#f{p|A zU>4pd(fAIjnT@=0{Aj8(gx_)Wrm3h^mpAu%!R_fn$KssBs5)}ol4j%8K>SKC#tz+h zjBjkz8ac58off%EA7(;h@G0Zy5dNn6Tbq={s5Qf^#&E?4o3jnlSlSL9bXu}T=xd>_GJ(HF^k{TKvluD5u;-{{yad$;2WepWXWFCN)h6kR2C zQ0PLU!!<2}Z6fqxmtvo(NAa3}au2CSJ()tC54GjEnz6VpC_NohTx1rrI?C3hxrpkR6%L^XBTX(Kwkx#auyE~$Xe^#>H z?I1X}vT~dkUvz>|LsTd~ftKXU#XIvk4~q&<2ku{QUFP4bwu&EpVXgj{Q}Ck-yAm0P zf?&(T*^t&&&Bo!os-Mm<_WbL-P|dlz>CvljbL99H8k~=0#{+yw(*>3nSrpG#cyN3- z)WQg3o-HnM0EIehnwB@8o4+hgV_p5qND|V6Z6s5zTK>~odi)~DPvyuyD^W*AYQ7C& zNGC4BlD01(Jd9HM(}&4UNt*rK__sk2^f>&|?RGge&4ko;??Y*2?BHi_96r8cwNf2W z7$WGzB*zk(rYO0ZhethLnhz-n^)^5BAaeJ9PVJ1Ghy*BkG3~r0?bWi);9DmNY(Q)E z+_bkegr8d)3QN?#d?n&P`pkV2JxO5u>B1|5`4fGA+TuUQq6s8h3}NYK+a!ff)?sVP zY}~#_{nMVPF4mfk2MxWxM%3;<4V6jaC`ilCR1>Hz*hkRVzJ&ZTx4uCjd{tePi_kD4 zMki6jYJ&loJNY)yk!|Obg&=4}yiI{6(Te{{??b#LDf~2%O!N}}*cLl0N9Jj-%QCsu$5}F;f$0o`R@xD6ZB5@`xH&j%sEs4p({FRz{hoSs2(e zU&pO$rfAEEbGA?uT(J^x-g2)Ee7HkPbX__#eCZcwOk-nXOME_RmK%J+eJb0n=-@=8 z{7c+>kgr2eX2M|8-#x@2BbTJw{76savc!u_(Fvuz%H|@5?X7VhnZLMs3OUC z#1N8dz@%7DwojudL$@VjZV+H|jfUMV%QNI1MmLHb+oy&C8Li56+oONi@ z`s)P6@SgQ?IhlU=W1+@o6CE#OywguVA40BMHK^@pt?Wm45W>yTtjU4Ri_CNbjV{uv zbYMp^dAwwsh$An4)Y|93xFtte;QP@-n;jfMw78I(t{y6RO5M0m`}1s-N#svK3O}l9 z0AF4?RqPPuM&3huV-rHFZz8SYqP>TADdzT1;)Jf>R8{Z!+m3|^0(IqOT)>7BFO#{Y zw>Sb;D$)72v4VE%-nJ*C;nSa(nPJ0qeuR=l>+%O#8#q=SnE`C{)Isbzm#WnH$(4m} zc)2Frj%MPK^?kh6aSZ50e0Tx_J{3f2qCATYv_pPg8jleZ^lX3nDIOm+3`_(EY-|xd zGCsi0;B0A;6ggwH%mf}Ds@uG34b%g$aALl>X6;r#>eZCpsyISK>2|qFZ%0a1ZY_`p;%ehCTVqa zcf8-LU)Vpvk;Dt{I}uX_DWF9v{=F19Ed@B$`6a6piWA?m6YBG}n&KoyQJ4~Kh~iAs!mt5{WP7gywoBaQsIY`i?^i`=_}!qL=7?sN+>tqlN+iU6xs$IlvA zM2Pl$r^rH}wuKPmff<9rq{HxWS4?@i5dwT~qPl+(svqZf=s17#H8w~_=&OfH*I`W? zhV&78VjuG-h8FlcTzBh*I`Ut&2X&62nlhI>y_mtb!3E{>*Vd`89Cz!xqi<;XHZgoA z#*QWFAHMal+u$$KDb@Yt-C_tTHHrBFKw`2Y^-jbO8X?7|L{&{@ao;j{1R%Y-Vz11i zuB+r^hn^{9`3jmb>772`y~no3HG1OOpRa+e(DrTb_vkiVu4FRVP!V$Jk&FS=Om+EP#E2Mhf-JfjeR2~2x564@Bz{5tRprD|GLgU?a z;{k9h^Kio@cz1rIlbY%e+;3GrIIdifl0KX@&J5}Zdftbl3p`{3*T-9u49A0->n9%r zWjcW$nE>E&f4X$Qm@07l=e4$nSnT~~S|$7D>vxg*uEh4OX~Kwe%qC;PI(JSi4j!4- zcYKYh>!R1)^FXB-BT%`05N$9zNF&tQ&={Ax`{GpZ25n*D$>=Ds($r53d-_u~WSQT{k1 z6UQxFb?`L;2_kl{Va?S`3Qw<2*iU9mszb@%t~bx#-|gc)Ur@h;+iKyRL$oD0d&Y;J zt)ts$7<062iH6zO1gw0yM(8`V`9*f|zrr6|8N+(BbrvB)#c@G5k8&$tXpA~Cc@e60 z$Pnr=T35yrJx}G`b=p%pu1E7zd*7UQ!iwwNJiMg%LyD;MmN)BTn1O;YyW^1u&P}-& zf9!|d&?kW{=eO)qMS|$ril6&x{s{n3iQa&^XamdnmwouB*GR5|8auGzmAhWG{Dkux=CgudUE>BPUx5%#Kg%u^bc%B()O z));#+;>tk07ViGth=M%ib;fbIMtPtxOXGuO5RZuZpo8zKIUPCso1c>**g(%FHbX#i zP(Q*5yU6`AYhpvItQWQ=;tR;ITAQZQhaRnFNv0Efl57 zguWYPJqSBKMrk;)?B!yHo+gFCYchTqo1G}vZ&V!I=ZC%5cI_rWR9I|Pv(#p*w* z+Qw^Mc`?9HC}K23r**u>%>HUX(X|$N_p*}29+oWJ^$=8d&Ma0L@d4wkdzJm`FIk7i zJK%uvbC%m4>4zKpV^^^O>KXEj{4tV~@#Kv}zKpj*OhlZh$o@g&Lj1`7-AoJ2J)EfH zZ+@bl@o~TL7ybDP2h);OV=h^6aEG3!Z^=TB=Yc1QUWT^dHF~z6L6VZxqUK)ma1qTH zQ6fwflCN3PFMf%?T^*-)S^MLgAoz8n__ZGJjMt1fVeHNFE=~GFoJ8C2s!$C{4EWM$ zzSe|M%N?$yFrh#1aCa?gMYy~&2R$4n2NDJ`AR^1UY2Cs4JG=y$VAiRt_|!!1>xQrnE_iwe#_T-8o4U%ivUwxE9ISfPcJ)HE!ZU8{vZLFD-j zz`}%|>GtNTeGTf5fnQZx&;8@izMw%=c`ox2*)#2DchGWqsjLqcS5BB*rd66Y*3~O? zQ^Zg^37p_snr|zsA}rsh&5gNpR1qp1DvEs4b%O#ODj=!|)HY=_al2x7wu)a_YmN59 zXh1jGrj(nJiSkiC^S%$wM&U!J=c@t+Dw65Gjb@-o^b5CTmyF7>MXup^A0l^@Mrps^jy{_?mOysqB=hBeA&w+)pQuCh-6x&w;D+R<# z2&JvaIo@l8(_4QO=Ls~Fgc&GosA{Xqlg27TwC1K;LU;(}uujF3aFv<%#P73ESceu(n!?}y? z-z~CHwB=IkHbyT6wv<8&HM7$cTWFNgFI6opmS7Hp`X}C z&n)aQ+@2HM4W(BU0Qw{Rv_LH+Rm0YufxJ8N@SsFz=?q8jN2-Mk8qc^1K^f1a&rBC~5~3XZD?h^)9(*`ZxUrIK z8*SL{nj^m29ypOF8FtIQxFz90cd6gL75JkWA$Y-WUKHe{5tkBkMwn$})c!qrlD{@} zacIh;$kmfOr*?uLQGVPF{nMv-gTXy&E_*A|-wBPt@?GslTD05XD_UB+-S|8BuLHY2 z$%HlfpGkM0tZMxE&=`>#%Y9zw=`Ff()=YCnyY4Vp>`x5o>ggeJQxR-VFReL4tbL{U)lSvg&L)brbt6AW7iQZE@0=)`lbLy~i`&#rM(C++>-g1RV7Zo52Fp5Kdsf zQ)^Hd=sn)&QHAnSN$ob>_bWykbp%fLp&>7hI zAYmi2-f7vk(YyB406lpypLSpm;iUS6X{se;nmlT-*0@Sq5dM=)0PUTA^o^_fB*lD) zQO^CzC~Qzc;V#1os@)MRe)0t4K&c_OB|KHspIY~t6_N@5R(p3Ci48}<{8iX(JX7^d za^Z#KtX{A0h}#7!>oEvfob#VJD{C;?CGIBQe@+#(QfnL+h0(N0$9U^I;UT_bO3swd z*OkDLa1PHN@hWnr4Qu#(&}u${PId?SF1*@(MX z#n+}a8~&4{HL$wJOzDKKS~}H6z66Um5``<~5(juhyA?Nv36e7>h!|L9a7t&&x(V1# z>xahiztN12l|7LjoH+F$a`QKGDq?n;7*D;J0^V1!YXsk_09Zw=-@m@pW%0SxC<%Y6 z&9LJFsUUTJRnRh%Mb0rPINIQts=e%y%Jh6MC=zL?p=uwa?z!rcWyH(Gsnj)xfhD)3 z#rE!}mEk$9JlTS+S2T6tpcnktRQ zQP(y{p4)?X$KrB+!%J0%(f*cq$niF_KXd5#`u0XZ__ed?h_Ca})YC=3DwYF%7H6IZ zs|nwj$qPo4U2Iz?=EiWMW$PqSQP&dAqZXWbxy#`e}!nia5Aw6al6s~ zv}klAT?lZ#DR94IUS1GNN4y@^3{G!l~ zYlJ$h!t~Es0Q6SGr?=TvgF<^qRV~ID4Cer}98@>IaH~azwA~bVhzaO>tgX*X8DSj{ zzx61O(@GhXbe-C7uh)U+XG1j43g@AxpSik#tQL6~ErqvXeI*VU>tcW{6xHh+MuOkWY6pf8PxS$Yqlr2B%j_x9cAbCUb>wbKu z!&sHz^654ci0fgJPoS#(B!hq9Nqag#5vP1g)bdF67AG_gnHV8=U`;yniutsHt~cf* zViZTko?*!7xius#*}( z_VDe0o~E%owMLOF>>Ex1EN6MydQa!%CRP1S6=9~|*p(I1y(=Va8z=vgF6jhI^%Djc zqi1wZZpJVqdCqe(U4g1xP7ZeSx`%!=3#LqZ{ZF+9jD0sz{*J`O7!rguG?vZ*{+b~4czCRjFf|Po`K@iziSm@S5aqw>ynEq$+-p>J?u`y>PVAxK8Lb@?)Ey?oP|6&X z?cq}Qo$!apz)9442p+ZAK5?}U0h)q((VAo-M)Op}UJQwubL*+j3$buwH!a6aQgzsq zPZ-;yT@tgNCRl__ppzZ7tPuH?SPh~Py1+5!B(PXVz7*~p7@mGgq3xWM`F`SLd8GtY zCazs_$A?R2@`qd9%?mpEZtT*3uNZxNKNtkvNZzL+CA0jMRNWz$B#{1FgTZj;{UYU+ z(z>PkwNU8L@HEc9@kbT7zq1JW@bEP0KY(j| zK#4=W*9Pqg#}=(UC2_vA2o!;0#Lp-&0K4ZVqZ3|ks_QP{VdR002~O5iet@|C1AK?q zd{dR}4TvdYAl|c11xE)?4^Jmtg{0p(|Bpgk$fiS48YNjp(z?(KGM1{aMO&iD-{3h+=TMe{Zaqg*xkJmaGY9`CY`l`O z1E+AIUG&WUCgWt=#1bF{?Z^}PbR(kjp&}*p&>f7Ahu{70Ob34{aOQ!QTff&?y6S-* z7j_!#=DibquaCSNXrdf0p5Y@-GIoI3ImNlI51G*UOFyf-tfJFw#8zF0&ah{^>dyi} z+j7C&JUzonDeRjm>+-uVURkZ^+=uA9O8}PZd(R%H`+6ZR?Vpns)&XG`x4^kjl|$Q4 zPJpj=MH?73`hk)S7YJqF%*Wk^a&Np|ksDB%>q^Xx-RLdO^+d?Ie8<)`f`{^(o&8Xz zkm-x42F&wH>Rpwg1;?bh^KO1C>jjZdok5VMAV~YU7LldGh4E=Kv9Ym2F#sM)ngu84 z*lLJJDG810N!Dlw>BGQR&+5p9fuhF~E7A?1o?Ox~X@cng3bRc;z}=ZSsbe!{oBDOT zFj2~g(eVs?YN$}iaAG`Kz8$}J{=`s?#8BxlHdZr8JGnkLzV&lNMsn2dco>3B>>%hzOw z84WbYEw><$t>1#QL7|Qb@JnfK3)=B%3c3a{J3g@5BLbx!#HP^W=oB|)j#ox}%I7}# zL{%I-S3o9P>0BkWdeRY@p$f|wxAWkv6|8`^uXW~cYhleR6s{TrsxI7>Xv`N>+93j@ z5Y4v_=Z0!Ti2q}Vs@f~ z4)mNE3+Pn;W&QQye^?&Rod-AbQj)@-)Ma^mt~I7Oa`m7DLZr1X&J{y4p{BOq&t?=} z_n)W@DhxPMODvyV=PFGI4E90V+$40)f?ga?-T0M95vJ}@1-I>-Dd+s&_`XFepmTL? zIjrhYq3igwt#mFa!nwYICc6AWl1Osz5hj0pbuR8~QC*oz&=kv>n{A z-Q5LnGij$clxV187EY=z|ADoZ(>b~dyyM2;ZhTjHpxC3+I8jivu;K{Tmifh1K#B5Q zAH+!8`F^{~V;J4F!cBJGwa5pzQ|ZPPe73Q%TJA$+5Ijcx$GNOUg-FYk89+Jb95!IlrV;Ai)RYxq@WdsjDj=?s< z#70a9`1Qi;_M$63M$?2Tt1D z`hVOTJU-}5&9MaFo#LoV5AJJ~XY4kgK^w}yf5Qc2eFy&Wu>Q9BUA2)%ktFZtlogrG zWBbqD!F7B9Ic|?AV-sZpZbEJAiXU54%(l{$)T0q(xjsLlpEKDU5YPhF7!{-U_Y+PN%M zso4b&1^7LIcc%Vpj)%`R$_jMwq0lF93=5==`Vg0KIW`d{HMSfmu3DD(><{Oh=1vwW*uEXWBSS#BwNDOF>skB7{BT0_f8^bFLBSEo=b+>(X}t13(` zrm~J`vJ06Cx@HV%<}!_;yuhmD%J&m<82UuPgZQfJb7#sI%v#8e)J~HtHwb0Xpw`Yx zPw;!el_$AvoA;bYoqdJRJP-CK16P zdU6)y)@e@6F{Z(CoEdA9(tRHcYCTN=1`n67(>#>zwg^=q5Du;d)_j11KaFe30^)JQ2M9 z#h8kFu>+hZ-Z*Rvx2Sn?MOpL6CA$WR4uy){3ti5pR{kGZ6(TC=I^{FJlF zO#cQlqB86vys}q8k@x5+z*PzvcC=32nG&C=UkP5xc8EgFS!^;>NGml}UYr-4EDhyY zgpai^3wK07#I=LtQpc&{96H<0LgNxvPRlQ&iH1wOPfDI(}i=; zV9Do_@rub3Ir)6S9l^VpC{4-#2`i}#`mTsD^+tWMigV;_lR}=Wxf)JO58;=3gB%EV4v5=c6PZiH!T=Rz!&8i3K*8i8rTN`^%l~uAN}{L1u-% za}4@oCD9K3HIYL(hU>iFp1+3Szx24#$`Zvo4Y^+}&&yAiO0x!A4Y_25S2ED>ziafxQbMTt>#b)4X6FWR&pBRg&gpz9Gm|}svL3-# zI6=ge=|7!)ub~MzAm4o*E%eo7E!~}V0NrSSo zpsd%+en({L|3uOvhZZu62Isnu`M)XUT}L6R%|D&U{ITC|)hU-u|F7x*vn*q5TraL7n1PS^h)lOG!4y!wk*t z68P7VSBb4MM2Su@Frfxc1V0CGKZ5qZeB9_FudVpW8RqkrfE=*a|0wo0{ zJ5Ug`2!^N@(QC!zO&HFE4fw~Hu%`Fk+cGCd9S*3`;{qO$avnb_l&!^H96{Kxbh7=>f)gigDnf z7J}Ufd<&CR?LY}hSUlR)qZF}&V^Hc zgs-|Ng7A0fU(7q-ngwTu%d7lFYbY)L!Mpqs{(T*W;k?}+bf+JO4w4?85AK);C_E04 zXHhm_MwQjflR@3Yf{(gohk`uhbnE=mo@o_cd&M z_o!ni@~@6ZlS4i(SJnA=CgWA2IU-%VGC;!9b&p#4_|L*+rHMG-XZBM;D=W7MnBW12 zR-)l!*DxeNyCxS*AvhznaWwCQzSANBU%(x&%q48P zwvW|tRuxMez|Of=(B^wLG-x}76Qf~#lWs z6C^PT(LR*o?-Uy0kq3v!&4gaC|u`Hv?FI7`JJy~rsFhFbO` z{c)DMNP)9dmxgWyI-xDzKxgSrYd4q|Z`=S`O+!Ph^>25bQSc%H+@gO^g%CgJslWtA z4qDNT!jFjw3j<4|NlC2(TFu_?!O|#o!QN&c>$U_GNti;QL!AH=H?e+HJyZ&c+adgH zVFBx4NW~}8gZ9KyjSg!M>m#&2{)?_>*OG1_SS{Z}B$-UlrAk(ZrVwl~ZDvz)K;3}0 z`3Z?j*t&JiJ>1Kc`4#A9+4$mEH6i>d2Q;uuIJmqs`XYcciDVw!4aeFTPt+cDWnSzG zc<@`dmcVQEAq-9@p;t$l+zf!__DKp_ZXflk9nP!0t16e$@}E-QG|WIz(5{s8GfL9J zA>xI{NHj{fBD{G$JITL0_v#WN#RY#O>I7`&2~Ki4NDXc=%zJO#OuK$9^h@**w>HZF z*yZNFDV*n51uVTd|Du4};JwP&RngR{&*z-d>`pJ3@WDTIS5{}#Nm&6srg1H0aZvN= zb_GyU_(8srnR36|3RZqWFQAwK6^T(QW;z+X@SQ;K0ul@B0<^Z z%s*ecrhF!Ru2fs%joG-Wh-`MKoX@ZIHZ9&yYzgpdSU7=SqvWPV9cO*XGRW;yZO9Az zgFEQWo9yP>Gk?{Z4_Lbd+`{9Ist$43I5NMToBO*1F(r$Zc50#m3s8RF;I~C_OZusP zYs@Y#-f?>8%}QC`_dTd*o_piw7;(NS^S5$M;ltZ_vUBWRm${}qrOSpWZ>u~U?e+|( zz%zBA__}J$rn8jUC6VFt37ZUFGMn`6JHEtzo;xxk`x;Yx>d`Cx3b~O+LzW&c$Et#! z4`HF*Z1|oiBB{=i;mK(_MCjM+Q_S{f#3;H?hbYNH!pHHtnq5bo!F(_ zKOUCQ_*s$OcgUY~F}Uk_*Qq{(cY3D2GP6Mi1pG)oE$sR90WF8l^Q6y$3G1|<>{o4z zCf<#eAj;hvq}shs>*GU$OIL&E&C0y0t-EZ9{We3)s+_;gjZ1_?>v+8<0kx!$u4P9y z=RqQzX5~}w2;U~iG2F(t-K%4+MAv;j`_lGV9n(PcTubf>7E|YWFdoIX%tTh_FBwG+ zt*`#11rVO#4(KPhs8W#(91d=;h%6O2bDcdrv`TziO7d4qu%Lkpw?z$)m2Z-hU? zgMmQ>5p26yZH`w#QDAAIB%#9P1u zwSS@c4>3B?C{`k1i&t|yb$J1JCR?3(xesfQ0}D?}eka`1KL-Bx4vUvvw?x>t_-;Vl zi$XK7{F4>D#HSn*n(QsLi9dAD^;~_J=tn*Zp-_-i5|XdAKb0KMv8bz4u0HO_A2G-Dk>LVQGh`4(B|936#pd9iRpu=h-AcNNV1Krl3vP}2 z$iRmD^GW|WD=JRaCuYg0-|!!LZIzzanExbZ|DaK;rTToRK7kD<)L)*cU@X^ZIxotb zZ~0=j2&Yd~AHeugY+$K{SYBMIR`{A<`u8cgh)Xcnm>F0CLL>BB{ULdpcDfG zg`{rhpN*n0hqVWz`%!KyxyMB3gnXA~@=t{n$`wH{#y|#~1}A)8W$V+z>i3r(Wlw7n zcjUgDTme<;(FdH)d!~d)4Si-0W&Rw5H6Odv&`zkCAolr;OAp1ml78c43yLM55v&$h zp0h~W<;*ivNGrF%wvK(x?ok+N-4t~~Ol*90b2y?cJUPwj#c@%!O=snqw9NQ}F6-7 zX;xZk;B*1UZ}O9br-i7|wlVu#jgr@LmMSdqxZsV9#7E0-QV$;;PTsJ^OzVqjSR(tu zo%>A#h)kv1RSDiZ1+-DNZ*o3OIfl?FKW`$W`TS{ABbPeF6}y=z0ei*MDW{+&lxDO* z%}Tb1B3@y=SM`}=>Ca40uUsYm)*86kUJR13B_hk5x`l<{)7DFjq;Sg@yQ+8MDOJB; zy}o0*&*=G3ON9>S`8J*L>BF>2nAC$4cOra{5wMKkzB>1%>GayS>UtV44$$qw=W9(iCwbtfJ@&m=E3EiuSR%rW2>0=? z`~^u|B$lTJ^mhkhw3pAS-0;ph=|?LP-{rhMkf(ghMESc^**N{44j-9e;d#q0ogPWe zpCeeOzyD?D_l_a#1L=>@&@S-EG%g(*&PxYEP1T(9TGlV zI8SWDEfOx_rBt$yM4aL}5q4`7%SIah&nRxhcBUVF-0oSi!Jr_4;zrtw{}A8!zcm^V zW|n(vhfW$>53*l|j&Ym#{)ZT-Clhb?9`$2SQmbU_!5tDVtU=||d!&9ixH`u2apYAv zA#05Gg@(k&`x&Rw=AFi^hXI{R!0oh?N7e>aZ+O9_0ljPHs^5S&jXpVKa0Yg7$KHK@ z|EkrZg1*YFK@5@fF81mPGAYZtPxqhhh9RMwC+`X1V(AXU;dz2{TeEq-Y)>BDzGSB% zLKIu#S`wxoX_Q1m>10-5u8)<0N2UVg?3{^xIV#jvG=3k^PdH0BG-oqBAFp*vmAtz@ ze~%_P+`MNnIDg-{S5 zO*u2y(EObGib0~`E9J(rhXc3E$5-dURomaWqMuE%e=vwxTAQw^pQ+DRcya+Kyfa3- zuYln(-dp+F48Eq0f#>5HW35Rtb*Jl@*sWuHH8*E}%!Kck*TGLA(}Sg8+WpRSmGZm0 z0=eK&S18*t*7v%M@Rc7suSe}f$bYdNM@TgM3MVyLm3(;>AfY|nbwsW#^Z%t^b+sEZ z7?e}{0J(AKh%2uX>O0r7@Lj9d z$z9JcjqUbK4c!gctm~(()h*-kK|20&-mkW^FAGuRe-+sscFos>oM!2RpXz)i+%%dzUgD3LUB} zo-7R!N0G4)Pm%F-TxUH!`F|4YbYFJ=AMR0faB6U&;jN)N#}zCs^z5wg!!rfQvsOI?67(C~ZM~ru8~n&GxZ66JxD9PkX#f=0$o?t}ipasK zX9H;JY7=LL{?%i@PV{-U7(1^_hHmy9r*s}9Ig(cIm`XM7=OE|5e>-4wO!>&o%k?4$ zZS41lGZ_~NUX%#$cb?9kvswK7*bu=vM61)CSL>%u;S}i>e~lE$=NO+=Me^=t-2_MV z$BS($r)_ijs>E7gA|(uz?bkG)f4UDj;I=$epILo3mzOx3Q^>w#wXg0bGA~rfW|x1Z z1MjA3&Pe$G!v6=p-?@}%;6bTZcW2^pvP$fGWXKay$-ascJili+ElIf%9ofoAC57w4 z{0f5W6dFT!>?*QMXJrq_;JQeIBzx^uWxuvhvy4u|uNmnm29`Y=WN}?ALCyuCc1c(7 zvw+en(&GqmZ9S=^_J;&PX>J;Yt{oBUcZwl0y~~no(mfwcKiy{Yfpq#H(rD^yxDUCd z*8fd;EBV9dDD#+NExU})Qz<2jC_1J+wCCAqROWHi_a5+{kyrp3`8DwCpCH>m!JnWY zf>MKnQq4tPD$gGmfrju{%G0}5Q7wxn@!ujX$*>@$XojytD!k;{#yP?QxMrTRyl|Qk zqFS~g>=M(o>XC!|g5EiTcSP18WCsdq03rL8AOw~(ETC!;git53e4It&1V9bT;H~Pc z5S5^<533a@+zAS!SA)WopfJ}O$gSLMnA50Uo6-_!AnilBKl+p`Vol?^9Q1J*i!~{5 zKD5K&E;%7E<1(GB*p{I6~ zsA5F)UH?*eBCmJN=2_KU2VAoaQT$YR(ytFL*q{poa3Ka=7`Cu6e~cGEV~gDyy1+aX7IVB9>F;)|6TF&cf(L@9Apn-L`l z)+~7E3*PnFVC8&!W%U}sVQvR89aSKPh%-D8e-*?;Cb22cz5(yz*1)?~5F_ZjM(@?e zL3IxPkAs|VE>;;&0=%qV<1i0{Sc#e%q<&S)98cA>j|Mz-RD#8Q-O~#0wk)24bZZV? zzIUQTkdkvO!lYpE-5SH&wnM5FYK9A&`>JyJ4h7)Wg2hu`Kk^7`BOy5T&p61>1o<6o z1cH#v?#loK{v^SDUXWcHAG{FC=mL73z!K6ivzna=PqmF zdNJP{JI%-^_oouM>6V@%<(0yji0%3cg#RRU*YX4yf(T zKcA?YR-2^BQ=c>g_KkdIL$|6qCss`&>b$h4)FR18j%~@4E^AcwZ9{d`*3{L)=L~6V zdj|MY@rL(Ia*=wpEML=K8bQkGw`23PINief<*o2kms(B4DrN=n=cdxVEh>%bG7WhP zl{K4HRDWrO;#lw&@DS*gS|(Nu0xdK1BpWW8R>e?D13?di?qrG4FyDa(%8fE|b2)Wf>{p{&x=&gr zOamL@92x`b?IuAiZun>qvH~Bra31brYfYJHf9eD_*6mmDx*Txymh3(C1zIbt)Ak8I ze=7JId6UqFhmcnPCT69(NKnI4x{CD7ZA!PV{PJS!*3p)gpx1bN=dM#l!>(H@zQ_io*GVtxCV8=iE#=35372rnOgbQ z&eJv1o)q!eJ=E`q8Y`66Vt_qP!4OiTxz@3S7#_2EW2{!&?bfBktj?+7Ns<4c_v*Rv zE9L#bf!NuGlaFf!n|1^;4TFp-H#h9FTM@HPt|hBD^$gw365n&8I&1H=F6s}?oKChf zs5wcho7ra$BIcajT6T{@Vs{%Bus(-gxD#4by{yQzSY4lgnwUZoK@ZHAS{6}my_#C) zpE}~7dh0Z2nnlaoK#L)ZchDPh(AzrF&Vxml_*7*NHnr1R^=UII%Nw?Bm89c5rSsj} zqCHf>Z{xFnAgpR++?gesn|M=bXD*j7P|(Iz2YM|BdRw^#t?WGcd_Qtf-ubre9Fflu zbBgjG$<-`(Hs04-xF!Ojsn(p*ZcTAoczk*icOPP>9NMrxkI_c=IZ{?}09Ab{-5Ec9 zB&Vo2NCgyzmulCB`U59_k!uF9m)jpF?nPoPX5LDi2Wf4>-8wLu@}`dmA8Qylo>z2m zl4>?~319g+EB74)>C?q#Oeiq6HVo*@HM^z_I7UXkUfMU?*%Jhk`4cfD+K10{-?$m! zd2n_xtREOX*{$%c^$cB*H^dF>&}-Zor}RCq9Z2!Gi&0Qmcy>k49ZL$SUlQ@OS}-gv zEU;i3o{Q1x!bRghGGUo$FYxRC`D?0v7mlA6Z&ha&Ijc)D{@y=|)TeYqj~DT#aJR5v zoG@^fPxV6M{i-@ppWfB~+XE|5GmjIyy875!B;5SW|23!ErTiP){Q38*>$Hu?;*SW_ zEzb0=a#zvt#K=1;>}nP3H@2ls3%;)>x1CZ0Z|DG`VB8apVq!DV6toW3D;lZ$UvYGw z_v2?>iQaSxhQUVfelBxm@itxx?B-X@jU&=+U$t6O2ISC-^ldALXs8g?n5#8ZaU!4m zj+>>=4D5zgk+aHHVdicM>_!WJWRF*~rD`ga7pzq^md!e#uJ>U?sjE6I78JQE&+fWn z%;Nma3rzg}rAbQ<$gP@+Lz=~r$N~uwAORU9R3XpeU~JG>aYVp5wHuUxocty&;HW8g znJP1X0Bc3RfD_@o2?_Nm-4K42dkMM8I%){+*!d8Cky@CHOaVawhRB(W4C9Fc45~F5 z*&vJp%&id_S*51}%&sOGnUlK$%)nLN@oW<<%})Yl_%4&Mt8N& zd(X=6`)kjCXgs87-RKtpc?BLWz+|K7WW(alLYz5<*Y$;g!j^=>Rg1bc(;mIQ%bO2d zWZU#VTQh*HAGy#kKB5oWTMH+{@wd^9jBXw6a#U+;(TJVupZ3%#k1AIWGZsFVnp44Y zUMOP%GxMCt&M?0tE;Vi%q?<(bquUnlFXZ7!DDo)oUldzo9u|F~JPHj5JR-j!j?e@E zW4np)d}S)qX2Ep{u}q&)#&`PGGp~9d*rx6QfQ?5MxXcPc@r>1T`pO6eNs*giE@qqs>{6&<7HFLBcnX;0z_SNAR<_ z0}b!)m9!2*#5U|oRSH#6gG`-6YA_^D8AH|>XX&nK7T3>IU^&0%d0|QXfRzF-hn{RU zm>lrZW}!h70)Yr1Ti^9v-{-D-&w1_Vz4zT~KYN`&&VJUzgY;{O ze1DiRq%?VPutvQMA=wZxfSk*)a}S-g3+o+!&(JFN)+@cZ>XlS%?ttVO$$QJDkMPfk zQW2;#K}c69!WqBbVEAsv?E8chh8?i1xQKQ%friz?cv()5sn|1YL2g|N9Y%=N_%7Xt zUOyMZ0;=Q@8bv%|R+<<)N;bWUEbqeEpu!p13$~&Y1?}#LiJc84@^XfG-qUYVy`@YW zEJmRr>xjQUSrE_l%K3pB{t+$1;ns_@0p?W9NY{?sJzs+(rV0Q0-TnH26Z!`3;-FY+vcb+y#8ra|};|6h%+0~YEvKiRLEEDVq9SaA8qeU&7a=(Jm& z9&$gn%pC77IX0dvu8#|p0Czy+;nwK}0mm#q?OF^$*T%5nBiWW!&%*As9;vH7*g#*7 zqR(BfYQx3vlz!x?poPM#rb#-5Z3fdcn(hgFT()h}{?a(V{dOhVu_R#j^--O8t(75+2U%0P?aYu1;V7NML!ep||2jd|J_V*-|>DwNRxLGZwwJp;OC%h{k zWEjDeTdrvaF07r8E#+A=Y+n-@v|uc7jbz?a*;0}9myWY4>o|5cCC2B>7pB~$@SBuj zrk`c@a~kHt|J))9QfpE$V%KM;0Hpc1CCFcn7-?FiMPTk@tCWsdTX8gdYL}`Uoes!M zN3VVzIf@%x{}fGzzVdz*@zD7g?sTAbr0FVgD~vn98hXuG`16h@efjL+$S+-H#Q&F=7Sp zVK{z**yo==Wh6J*rp5%QV%@p}Uw+cc({5$3y!QE5 zvoQy2&tKk(=@NZJ9t7o+5?Jmt(xhzkFo6+P0~5;KPeiliS40XwWgL@V5rY|QR9c$7 z8roCqrHI~Zj?7n{Inw$SYQy#}QYPQv@EgW;>#3V#&w;buUs9L1xX?3?@Qpz=Xc1Ss zen6Oo>rRD|5F<^XeUW40UmvmQRA+%fGM(3f&SsZJV~BxTH6c*k^kZqK2}NyMX;Y7Z zjIm?Lh2Tv+?@-fT^}cK_*ci1sj66|($)z2-FZy`%MZg3x>@4pC34j#-K=hqG93#zD zQ`EjOaCZ3+6!cBbx^H%uB<6DP>C!_Mn3cMsfq01ncAccga*5=iTb9n6z+#oon`t zM%YhTRMm_Nn2np8AA(Z-bqf1#-WvDXqQ~qK4p=`_8HPJ>Q;kC7rI*DubwYlUFXBn61d{#Y%d=ct-InnfIOs z;s@ScRaNUEY=$&4FXK>5em6NL`&+2QH#nXiDsvRsD`S#EnIG{roxdHykq1}P=Zk)$ z$D*4p{pyyxa?;Ebei9!A)PMFAV0dE2o4nT*&7+l*`FSmC+^G_CW5Tx9 z&NUM3`{-MzFCF}5bzp$JPyVx^FpfLed!}_fXr5wQZk_IRfPE3>&X{)9WW&XJzoLud z*8@mqgGcZiYe0!%Ebe7ZsQcB`V26F;5rG>!Jr?!lndlv?cLZ|~$r9U$0K-l{&Voc6 zQh8CW(nTFO_#pFgdn~S1hNBx6ga68QJBRZzzSZZoupqqpS)3)OCR9A5Oh!Xao zJ-&!U5(7A2(yJQ~p1-|6m8&$^PXvvcIGf1Vl;V*tn$3WUMxBiB9w97y9{VszCmQvT zFPAJuufsr#N;sPVgF3muu5*9TJ0$i(neg50#}|6h`tr4nhCBH9Wai%E8((W{EU9W= zaS%%w?8ww|!g)pTKT9pS8~n|Wr%r$h3QP(FDd>%=4Hy)Nn~n?N4*#Mb+fo|DMAWprX@ggjm=7%XcR+B}d#Ilm3?45V9M zOD(!|yYkh24}g_xR^VAb=bjGHlo%h-rkn6%*E;4dn`r! z`bVXGe3%?xTkX)BF7YC9?p zt4a!0B}P`&2CoZI4@G689xe$n0CrvsK)<;#P1~aWQapcCoQ`VlEfMa--nV*DkS`Bz z)4)l6d;dn#%#9S{SCB`8P&b=_mOJE)Ud*0NuzVjPkJ6f8QVK&qrH@NEq@$zQUDG{| z{kk+4EY?=*Qjyx~>bWOFkFVLCODJ4rBABc02KjjF78Q0XX=j|-1@sZ0cvT+c%d0{p`nD`Dm2ySMLhnx>Yd7OoIONu9)DaZnWI7Py?At6`?^z7^DdTGQUtIgImuK6f@h`jwr-#_a&1uP-g5P7JL7mlU^iOT$DJx&TS`)!GnlIH{#HQjm$_qpW_Gw6SPGz#C&I=Vn$TtBL z%gLXoY2_=X8ptDYMcq|vLNo9U_AT8CSsSDH39&O*n7b_1#K!=QDf^N+ILJgB8LmhI#C$a*Qmoy4}reHE-Lgi@YsM52c?uV~oAR=dU9L>L%(0e18yG@%D zujwO|daf-SlbaA1#k4n^t*tC&@^DcJw>WBx_5MO?yu0Pi%HuD#65cGjE1JoQB)Bxi zRSAPNtHXS?FT=*%WgeODg`BNC-u9mump&SIlEmOKe;?kKvIDe&WhuJA79la6Np)Wt z&J_?Rz#y`FOdR;xevrSuMI7>t@u2kF(~K6$5_~{<$+>Cvfh6ADY>>8O zqjrHou7Xg|jE05#No3po>Be018IzWeMuc}Cn%%*iv*4X3ae3fAe!iFBt!;Szr1LOg z;%A*u(plCVpvlsL%Ao2hQ9+;QkA}4$@0WDSx(z&#Xk3AS?Cjm*o04Irs*Bp|oA~kT zauPxso&o@`deU59=+C51i%I_C!G_o6JH;}0_|ogB$}He73VnvF;S-rEhN`Q2ho%bL z3#G#PZ2Di$aEUNBJEe=YwLTHs?wgO!>B-8dK@#zkU*8Sh*7ai=8(R?bntEz|%kzu0 zLu|+n$K=^jqOF&^b;@YA1VxtbUM=C*yMzKhb6j*($6z#udH!B+kU0pTE^ECFurrm> zY5{&k7YGOiVgI4TDVXR1NHhPbh6!c)Kp8%Nj1v3~2?(x%7d-(%=6}_Oq=dmvs-*of zQqbNLxI)NF1&TZ*p#!Tt0Xmj{R7-;~{E!0j67>x1XCi;K7cS$2y+bGi1ONUjV`KC)J|m49ZsghnZ;sFk4p} z9S>JGPo#~jhaG6;4Zu&fITPW54k#4_ZN64r5D^S;f~i4Jlyi+v0e1rTOilnrc+2dx zF(nvkY_U3p)f4EpIfXiVfCN;-0Q`j3_fA`&b2cQQgTpDTV4&&W4ut;nvLomo2*BYa Sq$jgPLLV1sSw6S`5d9x`8{6st diff --git a/modules/beamdyn/src/BeamDyn_IO.f90 b/modules/beamdyn/src/BeamDyn_IO.f90 index ee278ca399..4e4ccd0db5 100644 --- a/modules/beamdyn/src/BeamDyn_IO.f90 +++ b/modules/beamdyn/src/BeamDyn_IO.f90 @@ -41,7 +41,7 @@ MODULE BeamDyn_IO ! using the parameters listed in the "OutListParameters.xlsx" Excel file. Any changes to these ! lines should be modified in the Matlab script and/or Excel worksheet as necessary. ! =================================================================================================== -! This code was generated by Write_ChckOutLst.m at 29-Sep-2015 10:23:41. +! This code was generated by Write_ChckOutLst.m at 08-May-2025 15:51:30. ! Indices for computing output channels: @@ -51,387 +51,403 @@ MODULE BeamDyn_IO ! Time: - INTEGER(IntKi), PARAMETER :: Time = 0 + INTEGER(IntKi), PARAMETER :: Time = 0 ! Reaction Loads: - INTEGER(IntKi), PARAMETER :: RootFxr = 1 - INTEGER(IntKi), PARAMETER :: RootFyr = 2 - INTEGER(IntKi), PARAMETER :: RootFzr = 3 - INTEGER(IntKi), PARAMETER :: RootMxr = 4 - INTEGER(IntKi), PARAMETER :: RootMyr = 5 - INTEGER(IntKi), PARAMETER :: RootMzr = 6 + INTEGER(IntKi), PARAMETER :: RootFxr = 1 + INTEGER(IntKi), PARAMETER :: RootFyr = 2 + INTEGER(IntKi), PARAMETER :: RootFzr = 3 + INTEGER(IntKi), PARAMETER :: RootMxr = 4 + INTEGER(IntKi), PARAMETER :: RootMyr = 5 + INTEGER(IntKi), PARAMETER :: RootMzr = 6 ! Tip Motions: - INTEGER(IntKi), PARAMETER :: TipTDxr = 7 - INTEGER(IntKi), PARAMETER :: TipTDyr = 8 - INTEGER(IntKi), PARAMETER :: TipTDzr = 9 - INTEGER(IntKi), PARAMETER :: TipRDxr = 10 - INTEGER(IntKi), PARAMETER :: TipRDyr = 11 - INTEGER(IntKi), PARAMETER :: TipRDzr = 12 - INTEGER(IntKi), PARAMETER :: TipTVXg = 13 - INTEGER(IntKi), PARAMETER :: TipTVYg = 14 - INTEGER(IntKi), PARAMETER :: TipTVZg = 15 - INTEGER(IntKi), PARAMETER :: TipRVXg = 16 - INTEGER(IntKi), PARAMETER :: TipRVYg = 17 - INTEGER(IntKi), PARAMETER :: TipRVZg = 18 - INTEGER(IntKi), PARAMETER :: TipTAXl = 19 - INTEGER(IntKi), PARAMETER :: TipTAYl = 20 - INTEGER(IntKi), PARAMETER :: TipTAZl = 21 - INTEGER(IntKi), PARAMETER :: TipRAXl = 22 - INTEGER(IntKi), PARAMETER :: TipRAYl = 23 - INTEGER(IntKi), PARAMETER :: TipRAZl = 24 + INTEGER(IntKi), PARAMETER :: TipTDxr = 7 + INTEGER(IntKi), PARAMETER :: TipTDyr = 8 + INTEGER(IntKi), PARAMETER :: TipTDzr = 9 + INTEGER(IntKi), PARAMETER :: TipRDxr = 10 + INTEGER(IntKi), PARAMETER :: TipRDyr = 11 + INTEGER(IntKi), PARAMETER :: TipRDzr = 12 + INTEGER(IntKi), PARAMETER :: TipTVXg = 13 + INTEGER(IntKi), PARAMETER :: TipTVYg = 14 + INTEGER(IntKi), PARAMETER :: TipTVZg = 15 + INTEGER(IntKi), PARAMETER :: TipRVXg = 16 + INTEGER(IntKi), PARAMETER :: TipRVYg = 17 + INTEGER(IntKi), PARAMETER :: TipRVZg = 18 + INTEGER(IntKi), PARAMETER :: TipTAXl = 19 + INTEGER(IntKi), PARAMETER :: TipTAYl = 20 + INTEGER(IntKi), PARAMETER :: TipTAZl = 21 + INTEGER(IntKi), PARAMETER :: TipRAXl = 22 + INTEGER(IntKi), PARAMETER :: TipRAYl = 23 + INTEGER(IntKi), PARAMETER :: TipRAZl = 24 ! Sectional Loads: - INTEGER(IntKi), PARAMETER :: N1Fxl = 25 - INTEGER(IntKi), PARAMETER :: N1Fyl = 26 - INTEGER(IntKi), PARAMETER :: N1Fzl = 27 - INTEGER(IntKi), PARAMETER :: N2Fxl = 28 - INTEGER(IntKi), PARAMETER :: N2Fyl = 29 - INTEGER(IntKi), PARAMETER :: N2Fzl = 30 - INTEGER(IntKi), PARAMETER :: N3Fxl = 31 - INTEGER(IntKi), PARAMETER :: N3Fyl = 32 - INTEGER(IntKi), PARAMETER :: N3Fzl = 33 - INTEGER(IntKi), PARAMETER :: N4Fxl = 34 - INTEGER(IntKi), PARAMETER :: N4Fyl = 35 - INTEGER(IntKi), PARAMETER :: N4Fzl = 36 - INTEGER(IntKi), PARAMETER :: N5Fxl = 37 - INTEGER(IntKi), PARAMETER :: N5Fyl = 38 - INTEGER(IntKi), PARAMETER :: N5Fzl = 39 - INTEGER(IntKi), PARAMETER :: N6Fxl = 40 - INTEGER(IntKi), PARAMETER :: N6Fyl = 41 - INTEGER(IntKi), PARAMETER :: N6Fzl = 42 - INTEGER(IntKi), PARAMETER :: N7Fxl = 43 - INTEGER(IntKi), PARAMETER :: N7Fyl = 44 - INTEGER(IntKi), PARAMETER :: N7Fzl = 45 - INTEGER(IntKi), PARAMETER :: N8Fxl = 46 - INTEGER(IntKi), PARAMETER :: N8Fyl = 47 - INTEGER(IntKi), PARAMETER :: N8Fzl = 48 - INTEGER(IntKi), PARAMETER :: N9Fxl = 49 - INTEGER(IntKi), PARAMETER :: N9Fyl = 50 - INTEGER(IntKi), PARAMETER :: N9Fzl = 51 - INTEGER(IntKi), PARAMETER :: N1Mxl = 52 - INTEGER(IntKi), PARAMETER :: N1Myl = 53 - INTEGER(IntKi), PARAMETER :: N1Mzl = 54 - INTEGER(IntKi), PARAMETER :: N2Mxl = 55 - INTEGER(IntKi), PARAMETER :: N2Myl = 56 - INTEGER(IntKi), PARAMETER :: N2Mzl = 57 - INTEGER(IntKi), PARAMETER :: N3Mxl = 58 - INTEGER(IntKi), PARAMETER :: N3Myl = 59 - INTEGER(IntKi), PARAMETER :: N3Mzl = 60 - INTEGER(IntKi), PARAMETER :: N4Mxl = 61 - INTEGER(IntKi), PARAMETER :: N4Myl = 62 - INTEGER(IntKi), PARAMETER :: N4Mzl = 63 - INTEGER(IntKi), PARAMETER :: N5Mxl = 64 - INTEGER(IntKi), PARAMETER :: N5Myl = 65 - INTEGER(IntKi), PARAMETER :: N5Mzl = 66 - INTEGER(IntKi), PARAMETER :: N6Mxl = 67 - INTEGER(IntKi), PARAMETER :: N6Myl = 68 - INTEGER(IntKi), PARAMETER :: N6Mzl = 69 - INTEGER(IntKi), PARAMETER :: N7Mxl = 70 - INTEGER(IntKi), PARAMETER :: N7Myl = 71 - INTEGER(IntKi), PARAMETER :: N7Mzl = 72 - INTEGER(IntKi), PARAMETER :: N8Mxl = 73 - INTEGER(IntKi), PARAMETER :: N8Myl = 74 - INTEGER(IntKi), PARAMETER :: N8Mzl = 75 - INTEGER(IntKi), PARAMETER :: N9Mxl = 76 - INTEGER(IntKi), PARAMETER :: N9Myl = 77 - INTEGER(IntKi), PARAMETER :: N9Mzl = 78 + INTEGER(IntKi), PARAMETER :: N1Fxl = 25 + INTEGER(IntKi), PARAMETER :: N1Fyl = 26 + INTEGER(IntKi), PARAMETER :: N1Fzl = 27 + INTEGER(IntKi), PARAMETER :: N2Fxl = 28 + INTEGER(IntKi), PARAMETER :: N2Fyl = 29 + INTEGER(IntKi), PARAMETER :: N2Fzl = 30 + INTEGER(IntKi), PARAMETER :: N3Fxl = 31 + INTEGER(IntKi), PARAMETER :: N3Fyl = 32 + INTEGER(IntKi), PARAMETER :: N3Fzl = 33 + INTEGER(IntKi), PARAMETER :: N4Fxl = 34 + INTEGER(IntKi), PARAMETER :: N4Fyl = 35 + INTEGER(IntKi), PARAMETER :: N4Fzl = 36 + INTEGER(IntKi), PARAMETER :: N5Fxl = 37 + INTEGER(IntKi), PARAMETER :: N5Fyl = 38 + INTEGER(IntKi), PARAMETER :: N5Fzl = 39 + INTEGER(IntKi), PARAMETER :: N6Fxl = 40 + INTEGER(IntKi), PARAMETER :: N6Fyl = 41 + INTEGER(IntKi), PARAMETER :: N6Fzl = 42 + INTEGER(IntKi), PARAMETER :: N7Fxl = 43 + INTEGER(IntKi), PARAMETER :: N7Fyl = 44 + INTEGER(IntKi), PARAMETER :: N7Fzl = 45 + INTEGER(IntKi), PARAMETER :: N8Fxl = 46 + INTEGER(IntKi), PARAMETER :: N8Fyl = 47 + INTEGER(IntKi), PARAMETER :: N8Fzl = 48 + INTEGER(IntKi), PARAMETER :: N9Fxl = 49 + INTEGER(IntKi), PARAMETER :: N9Fyl = 50 + INTEGER(IntKi), PARAMETER :: N9Fzl = 51 + INTEGER(IntKi), PARAMETER :: N1Mxl = 52 + INTEGER(IntKi), PARAMETER :: N1Myl = 53 + INTEGER(IntKi), PARAMETER :: N1Mzl = 54 + INTEGER(IntKi), PARAMETER :: N2Mxl = 55 + INTEGER(IntKi), PARAMETER :: N2Myl = 56 + INTEGER(IntKi), PARAMETER :: N2Mzl = 57 + INTEGER(IntKi), PARAMETER :: N3Mxl = 58 + INTEGER(IntKi), PARAMETER :: N3Myl = 59 + INTEGER(IntKi), PARAMETER :: N3Mzl = 60 + INTEGER(IntKi), PARAMETER :: N4Mxl = 61 + INTEGER(IntKi), PARAMETER :: N4Myl = 62 + INTEGER(IntKi), PARAMETER :: N4Mzl = 63 + INTEGER(IntKi), PARAMETER :: N5Mxl = 64 + INTEGER(IntKi), PARAMETER :: N5Myl = 65 + INTEGER(IntKi), PARAMETER :: N5Mzl = 66 + INTEGER(IntKi), PARAMETER :: N6Mxl = 67 + INTEGER(IntKi), PARAMETER :: N6Myl = 68 + INTEGER(IntKi), PARAMETER :: N6Mzl = 69 + INTEGER(IntKi), PARAMETER :: N7Mxl = 70 + INTEGER(IntKi), PARAMETER :: N7Myl = 71 + INTEGER(IntKi), PARAMETER :: N7Mzl = 72 + INTEGER(IntKi), PARAMETER :: N8Mxl = 73 + INTEGER(IntKi), PARAMETER :: N8Myl = 74 + INTEGER(IntKi), PARAMETER :: N8Mzl = 75 + INTEGER(IntKi), PARAMETER :: N9Mxl = 76 + INTEGER(IntKi), PARAMETER :: N9Myl = 77 + INTEGER(IntKi), PARAMETER :: N9Mzl = 78 ! Sectional Motions: - INTEGER(IntKi), PARAMETER :: N1TDxr = 79 - INTEGER(IntKi), PARAMETER :: N1TDyr = 80 - INTEGER(IntKi), PARAMETER :: N1TDzr = 81 - INTEGER(IntKi), PARAMETER :: N2TDxr = 82 - INTEGER(IntKi), PARAMETER :: N2TDyr = 83 - INTEGER(IntKi), PARAMETER :: N2TDzr = 84 - INTEGER(IntKi), PARAMETER :: N3TDxr = 85 - INTEGER(IntKi), PARAMETER :: N3TDyr = 86 - INTEGER(IntKi), PARAMETER :: N3TDzr = 87 - INTEGER(IntKi), PARAMETER :: N4TDxr = 88 - INTEGER(IntKi), PARAMETER :: N4TDyr = 89 - INTEGER(IntKi), PARAMETER :: N4TDzr = 90 - INTEGER(IntKi), PARAMETER :: N5TDxr = 91 - INTEGER(IntKi), PARAMETER :: N5TDyr = 92 - INTEGER(IntKi), PARAMETER :: N5TDzr = 93 - INTEGER(IntKi), PARAMETER :: N6TDxr = 94 - INTEGER(IntKi), PARAMETER :: N6TDyr = 95 - INTEGER(IntKi), PARAMETER :: N6TDzr = 96 - INTEGER(IntKi), PARAMETER :: N7TDxr = 97 - INTEGER(IntKi), PARAMETER :: N7TDyr = 98 - INTEGER(IntKi), PARAMETER :: N7TDzr = 99 - INTEGER(IntKi), PARAMETER :: N8TDxr = 100 - INTEGER(IntKi), PARAMETER :: N8TDyr = 101 - INTEGER(IntKi), PARAMETER :: N8TDzr = 102 - INTEGER(IntKi), PARAMETER :: N9TDxr = 103 - INTEGER(IntKi), PARAMETER :: N9TDyr = 104 - INTEGER(IntKi), PARAMETER :: N9TDzr = 105 - INTEGER(IntKi), PARAMETER :: N1RDxr = 106 - INTEGER(IntKi), PARAMETER :: N1RDyr = 107 - INTEGER(IntKi), PARAMETER :: N1RDzr = 108 - INTEGER(IntKi), PARAMETER :: N2RDxr = 109 - INTEGER(IntKi), PARAMETER :: N2RDyr = 110 - INTEGER(IntKi), PARAMETER :: N2RDzr = 111 - INTEGER(IntKi), PARAMETER :: N3RDxr = 112 - INTEGER(IntKi), PARAMETER :: N3RDyr = 113 - INTEGER(IntKi), PARAMETER :: N3RDzr = 114 - INTEGER(IntKi), PARAMETER :: N4RDxr = 115 - INTEGER(IntKi), PARAMETER :: N4RDyr = 116 - INTEGER(IntKi), PARAMETER :: N4RDzr = 117 - INTEGER(IntKi), PARAMETER :: N5RDxr = 118 - INTEGER(IntKi), PARAMETER :: N5RDyr = 119 - INTEGER(IntKi), PARAMETER :: N5RDzr = 120 - INTEGER(IntKi), PARAMETER :: N6RDxr = 121 - INTEGER(IntKi), PARAMETER :: N6RDyr = 122 - INTEGER(IntKi), PARAMETER :: N6RDzr = 123 - INTEGER(IntKi), PARAMETER :: N7RDxr = 124 - INTEGER(IntKi), PARAMETER :: N7RDyr = 125 - INTEGER(IntKi), PARAMETER :: N7RDzr = 126 - INTEGER(IntKi), PARAMETER :: N8RDxr = 127 - INTEGER(IntKi), PARAMETER :: N8RDyr = 128 - INTEGER(IntKi), PARAMETER :: N8RDzr = 129 - INTEGER(IntKi), PARAMETER :: N9RDxr = 130 - INTEGER(IntKi), PARAMETER :: N9RDyr = 131 - INTEGER(IntKi), PARAMETER :: N9RDzr = 132 - INTEGER(IntKi), PARAMETER :: N1TVXg = 133 - INTEGER(IntKi), PARAMETER :: N1TVYg = 134 - INTEGER(IntKi), PARAMETER :: N1TVZg = 135 - INTEGER(IntKi), PARAMETER :: N2TVXg = 136 - INTEGER(IntKi), PARAMETER :: N2TVYg = 137 - INTEGER(IntKi), PARAMETER :: N2TVZg = 138 - INTEGER(IntKi), PARAMETER :: N3TVXg = 139 - INTEGER(IntKi), PARAMETER :: N3TVYg = 140 - INTEGER(IntKi), PARAMETER :: N3TVZg = 141 - INTEGER(IntKi), PARAMETER :: N4TVXg = 142 - INTEGER(IntKi), PARAMETER :: N4TVYg = 143 - INTEGER(IntKi), PARAMETER :: N4TVZg = 144 - INTEGER(IntKi), PARAMETER :: N5TVXg = 145 - INTEGER(IntKi), PARAMETER :: N5TVYg = 146 - INTEGER(IntKi), PARAMETER :: N5TVZg = 147 - INTEGER(IntKi), PARAMETER :: N6TVXg = 148 - INTEGER(IntKi), PARAMETER :: N6TVYg = 149 - INTEGER(IntKi), PARAMETER :: N6TVZg = 150 - INTEGER(IntKi), PARAMETER :: N7TVXg = 151 - INTEGER(IntKi), PARAMETER :: N7TVYg = 152 - INTEGER(IntKi), PARAMETER :: N7TVZg = 153 - INTEGER(IntKi), PARAMETER :: N8TVXg = 154 - INTEGER(IntKi), PARAMETER :: N8TVYg = 155 - INTEGER(IntKi), PARAMETER :: N8TVZg = 156 - INTEGER(IntKi), PARAMETER :: N9TVXg = 157 - INTEGER(IntKi), PARAMETER :: N9TVYg = 158 - INTEGER(IntKi), PARAMETER :: N9TVZg = 159 - INTEGER(IntKi), PARAMETER :: N1RVXg = 160 - INTEGER(IntKi), PARAMETER :: N1RVYg = 161 - INTEGER(IntKi), PARAMETER :: N1RVZg = 162 - INTEGER(IntKi), PARAMETER :: N2RVXg = 163 - INTEGER(IntKi), PARAMETER :: N2RVYg = 164 - INTEGER(IntKi), PARAMETER :: N2RVZg = 165 - INTEGER(IntKi), PARAMETER :: N3RVXg = 166 - INTEGER(IntKi), PARAMETER :: N3RVYg = 167 - INTEGER(IntKi), PARAMETER :: N3RVZg = 168 - INTEGER(IntKi), PARAMETER :: N4RVXg = 169 - INTEGER(IntKi), PARAMETER :: N4RVYg = 170 - INTEGER(IntKi), PARAMETER :: N4RVZg = 171 - INTEGER(IntKi), PARAMETER :: N5RVXg = 172 - INTEGER(IntKi), PARAMETER :: N5RVYg = 173 - INTEGER(IntKi), PARAMETER :: N5RVZg = 174 - INTEGER(IntKi), PARAMETER :: N6RVXg = 175 - INTEGER(IntKi), PARAMETER :: N6RVYg = 176 - INTEGER(IntKi), PARAMETER :: N6RVZg = 177 - INTEGER(IntKi), PARAMETER :: N7RVXg = 178 - INTEGER(IntKi), PARAMETER :: N7RVYg = 179 - INTEGER(IntKi), PARAMETER :: N7RVZg = 180 - INTEGER(IntKi), PARAMETER :: N8RVXg = 181 - INTEGER(IntKi), PARAMETER :: N8RVYg = 182 - INTEGER(IntKi), PARAMETER :: N8RVZg = 183 - INTEGER(IntKi), PARAMETER :: N9RVXg = 184 - INTEGER(IntKi), PARAMETER :: N9RVYg = 185 - INTEGER(IntKi), PARAMETER :: N9RVZg = 186 - INTEGER(IntKi), PARAMETER :: N1TAXl = 187 - INTEGER(IntKi), PARAMETER :: N1TAYl = 188 - INTEGER(IntKi), PARAMETER :: N1TAZl = 189 - INTEGER(IntKi), PARAMETER :: N2TAXl = 190 - INTEGER(IntKi), PARAMETER :: N2TAYl = 191 - INTEGER(IntKi), PARAMETER :: N2TAZl = 192 - INTEGER(IntKi), PARAMETER :: N3TAXl = 193 - INTEGER(IntKi), PARAMETER :: N3TAYl = 194 - INTEGER(IntKi), PARAMETER :: N3TAZl = 195 - INTEGER(IntKi), PARAMETER :: N4TAXl = 196 - INTEGER(IntKi), PARAMETER :: N4TAYl = 197 - INTEGER(IntKi), PARAMETER :: N4TAZl = 198 - INTEGER(IntKi), PARAMETER :: N5TAXl = 199 - INTEGER(IntKi), PARAMETER :: N5TAYl = 200 - INTEGER(IntKi), PARAMETER :: N5TAZl = 201 - INTEGER(IntKi), PARAMETER :: N6TAXl = 202 - INTEGER(IntKi), PARAMETER :: N6TAYl = 203 - INTEGER(IntKi), PARAMETER :: N6TAZl = 204 - INTEGER(IntKi), PARAMETER :: N7TAXl = 205 - INTEGER(IntKi), PARAMETER :: N7TAYl = 206 - INTEGER(IntKi), PARAMETER :: N7TAZl = 207 - INTEGER(IntKi), PARAMETER :: N8TAXl = 208 - INTEGER(IntKi), PARAMETER :: N8TAYl = 209 - INTEGER(IntKi), PARAMETER :: N8TAZl = 210 - INTEGER(IntKi), PARAMETER :: N9TAXl = 211 - INTEGER(IntKi), PARAMETER :: N9TAYl = 212 - INTEGER(IntKi), PARAMETER :: N9TAZl = 213 - INTEGER(IntKi), PARAMETER :: N1RAXl = 214 - INTEGER(IntKi), PARAMETER :: N1RAYl = 215 - INTEGER(IntKi), PARAMETER :: N1RAZl = 216 - INTEGER(IntKi), PARAMETER :: N2RAXl = 217 - INTEGER(IntKi), PARAMETER :: N2RAYl = 218 - INTEGER(IntKi), PARAMETER :: N2RAZl = 219 - INTEGER(IntKi), PARAMETER :: N3RAXl = 220 - INTEGER(IntKi), PARAMETER :: N3RAYl = 221 - INTEGER(IntKi), PARAMETER :: N3RAZl = 222 - INTEGER(IntKi), PARAMETER :: N4RAXl = 223 - INTEGER(IntKi), PARAMETER :: N4RAYl = 224 - INTEGER(IntKi), PARAMETER :: N4RAZl = 225 - INTEGER(IntKi), PARAMETER :: N5RAXl = 226 - INTEGER(IntKi), PARAMETER :: N5RAYl = 227 - INTEGER(IntKi), PARAMETER :: N5RAZl = 228 - INTEGER(IntKi), PARAMETER :: N6RAXl = 229 - INTEGER(IntKi), PARAMETER :: N6RAYl = 230 - INTEGER(IntKi), PARAMETER :: N6RAZl = 231 - INTEGER(IntKi), PARAMETER :: N7RAXl = 232 - INTEGER(IntKi), PARAMETER :: N7RAYl = 233 - INTEGER(IntKi), PARAMETER :: N7RAZl = 234 - INTEGER(IntKi), PARAMETER :: N8RAXl = 235 - INTEGER(IntKi), PARAMETER :: N8RAYl = 236 - INTEGER(IntKi), PARAMETER :: N8RAZl = 237 - INTEGER(IntKi), PARAMETER :: N9RAXl = 238 - INTEGER(IntKi), PARAMETER :: N9RAYl = 239 - INTEGER(IntKi), PARAMETER :: N9RAZl = 240 + INTEGER(IntKi), PARAMETER :: N1TDxr = 79 + INTEGER(IntKi), PARAMETER :: N1TDyr = 80 + INTEGER(IntKi), PARAMETER :: N1TDzr = 81 + INTEGER(IntKi), PARAMETER :: N2TDxr = 82 + INTEGER(IntKi), PARAMETER :: N2TDyr = 83 + INTEGER(IntKi), PARAMETER :: N2TDzr = 84 + INTEGER(IntKi), PARAMETER :: N3TDxr = 85 + INTEGER(IntKi), PARAMETER :: N3TDyr = 86 + INTEGER(IntKi), PARAMETER :: N3TDzr = 87 + INTEGER(IntKi), PARAMETER :: N4TDxr = 88 + INTEGER(IntKi), PARAMETER :: N4TDyr = 89 + INTEGER(IntKi), PARAMETER :: N4TDzr = 90 + INTEGER(IntKi), PARAMETER :: N5TDxr = 91 + INTEGER(IntKi), PARAMETER :: N5TDyr = 92 + INTEGER(IntKi), PARAMETER :: N5TDzr = 93 + INTEGER(IntKi), PARAMETER :: N6TDxr = 94 + INTEGER(IntKi), PARAMETER :: N6TDyr = 95 + INTEGER(IntKi), PARAMETER :: N6TDzr = 96 + INTEGER(IntKi), PARAMETER :: N7TDxr = 97 + INTEGER(IntKi), PARAMETER :: N7TDyr = 98 + INTEGER(IntKi), PARAMETER :: N7TDzr = 99 + INTEGER(IntKi), PARAMETER :: N8TDxr = 100 + INTEGER(IntKi), PARAMETER :: N8TDyr = 101 + INTEGER(IntKi), PARAMETER :: N8TDzr = 102 + INTEGER(IntKi), PARAMETER :: N9TDxr = 103 + INTEGER(IntKi), PARAMETER :: N9TDyr = 104 + INTEGER(IntKi), PARAMETER :: N9TDzr = 105 + INTEGER(IntKi), PARAMETER :: N1RDxr = 106 + INTEGER(IntKi), PARAMETER :: N1RDyr = 107 + INTEGER(IntKi), PARAMETER :: N1RDzr = 108 + INTEGER(IntKi), PARAMETER :: N2RDxr = 109 + INTEGER(IntKi), PARAMETER :: N2RDyr = 110 + INTEGER(IntKi), PARAMETER :: N2RDzr = 111 + INTEGER(IntKi), PARAMETER :: N3RDxr = 112 + INTEGER(IntKi), PARAMETER :: N3RDyr = 113 + INTEGER(IntKi), PARAMETER :: N3RDzr = 114 + INTEGER(IntKi), PARAMETER :: N4RDxr = 115 + INTEGER(IntKi), PARAMETER :: N4RDyr = 116 + INTEGER(IntKi), PARAMETER :: N4RDzr = 117 + INTEGER(IntKi), PARAMETER :: N5RDxr = 118 + INTEGER(IntKi), PARAMETER :: N5RDyr = 119 + INTEGER(IntKi), PARAMETER :: N5RDzr = 120 + INTEGER(IntKi), PARAMETER :: N6RDxr = 121 + INTEGER(IntKi), PARAMETER :: N6RDyr = 122 + INTEGER(IntKi), PARAMETER :: N6RDzr = 123 + INTEGER(IntKi), PARAMETER :: N7RDxr = 124 + INTEGER(IntKi), PARAMETER :: N7RDyr = 125 + INTEGER(IntKi), PARAMETER :: N7RDzr = 126 + INTEGER(IntKi), PARAMETER :: N8RDxr = 127 + INTEGER(IntKi), PARAMETER :: N8RDyr = 128 + INTEGER(IntKi), PARAMETER :: N8RDzr = 129 + INTEGER(IntKi), PARAMETER :: N9RDxr = 130 + INTEGER(IntKi), PARAMETER :: N9RDyr = 131 + INTEGER(IntKi), PARAMETER :: N9RDzr = 132 + INTEGER(IntKi), PARAMETER :: N1TVXg = 133 + INTEGER(IntKi), PARAMETER :: N1TVYg = 134 + INTEGER(IntKi), PARAMETER :: N1TVZg = 135 + INTEGER(IntKi), PARAMETER :: N2TVXg = 136 + INTEGER(IntKi), PARAMETER :: N2TVYg = 137 + INTEGER(IntKi), PARAMETER :: N2TVZg = 138 + INTEGER(IntKi), PARAMETER :: N3TVXg = 139 + INTEGER(IntKi), PARAMETER :: N3TVYg = 140 + INTEGER(IntKi), PARAMETER :: N3TVZg = 141 + INTEGER(IntKi), PARAMETER :: N4TVXg = 142 + INTEGER(IntKi), PARAMETER :: N4TVYg = 143 + INTEGER(IntKi), PARAMETER :: N4TVZg = 144 + INTEGER(IntKi), PARAMETER :: N5TVXg = 145 + INTEGER(IntKi), PARAMETER :: N5TVYg = 146 + INTEGER(IntKi), PARAMETER :: N5TVZg = 147 + INTEGER(IntKi), PARAMETER :: N6TVXg = 148 + INTEGER(IntKi), PARAMETER :: N6TVYg = 149 + INTEGER(IntKi), PARAMETER :: N6TVZg = 150 + INTEGER(IntKi), PARAMETER :: N7TVXg = 151 + INTEGER(IntKi), PARAMETER :: N7TVYg = 152 + INTEGER(IntKi), PARAMETER :: N7TVZg = 153 + INTEGER(IntKi), PARAMETER :: N8TVXg = 154 + INTEGER(IntKi), PARAMETER :: N8TVYg = 155 + INTEGER(IntKi), PARAMETER :: N8TVZg = 156 + INTEGER(IntKi), PARAMETER :: N9TVXg = 157 + INTEGER(IntKi), PARAMETER :: N9TVYg = 158 + INTEGER(IntKi), PARAMETER :: N9TVZg = 159 + INTEGER(IntKi), PARAMETER :: N1RVXg = 160 + INTEGER(IntKi), PARAMETER :: N1RVYg = 161 + INTEGER(IntKi), PARAMETER :: N1RVZg = 162 + INTEGER(IntKi), PARAMETER :: N2RVXg = 163 + INTEGER(IntKi), PARAMETER :: N2RVYg = 164 + INTEGER(IntKi), PARAMETER :: N2RVZg = 165 + INTEGER(IntKi), PARAMETER :: N3RVXg = 166 + INTEGER(IntKi), PARAMETER :: N3RVYg = 167 + INTEGER(IntKi), PARAMETER :: N3RVZg = 168 + INTEGER(IntKi), PARAMETER :: N4RVXg = 169 + INTEGER(IntKi), PARAMETER :: N4RVYg = 170 + INTEGER(IntKi), PARAMETER :: N4RVZg = 171 + INTEGER(IntKi), PARAMETER :: N5RVXg = 172 + INTEGER(IntKi), PARAMETER :: N5RVYg = 173 + INTEGER(IntKi), PARAMETER :: N5RVZg = 174 + INTEGER(IntKi), PARAMETER :: N6RVXg = 175 + INTEGER(IntKi), PARAMETER :: N6RVYg = 176 + INTEGER(IntKi), PARAMETER :: N6RVZg = 177 + INTEGER(IntKi), PARAMETER :: N7RVXg = 178 + INTEGER(IntKi), PARAMETER :: N7RVYg = 179 + INTEGER(IntKi), PARAMETER :: N7RVZg = 180 + INTEGER(IntKi), PARAMETER :: N8RVXg = 181 + INTEGER(IntKi), PARAMETER :: N8RVYg = 182 + INTEGER(IntKi), PARAMETER :: N8RVZg = 183 + INTEGER(IntKi), PARAMETER :: N9RVXg = 184 + INTEGER(IntKi), PARAMETER :: N9RVYg = 185 + INTEGER(IntKi), PARAMETER :: N9RVZg = 186 + INTEGER(IntKi), PARAMETER :: N1TAXl = 187 + INTEGER(IntKi), PARAMETER :: N1TAYl = 188 + INTEGER(IntKi), PARAMETER :: N1TAZl = 189 + INTEGER(IntKi), PARAMETER :: N2TAXl = 190 + INTEGER(IntKi), PARAMETER :: N2TAYl = 191 + INTEGER(IntKi), PARAMETER :: N2TAZl = 192 + INTEGER(IntKi), PARAMETER :: N3TAXl = 193 + INTEGER(IntKi), PARAMETER :: N3TAYl = 194 + INTEGER(IntKi), PARAMETER :: N3TAZl = 195 + INTEGER(IntKi), PARAMETER :: N4TAXl = 196 + INTEGER(IntKi), PARAMETER :: N4TAYl = 197 + INTEGER(IntKi), PARAMETER :: N4TAZl = 198 + INTEGER(IntKi), PARAMETER :: N5TAXl = 199 + INTEGER(IntKi), PARAMETER :: N5TAYl = 200 + INTEGER(IntKi), PARAMETER :: N5TAZl = 201 + INTEGER(IntKi), PARAMETER :: N6TAXl = 202 + INTEGER(IntKi), PARAMETER :: N6TAYl = 203 + INTEGER(IntKi), PARAMETER :: N6TAZl = 204 + INTEGER(IntKi), PARAMETER :: N7TAXl = 205 + INTEGER(IntKi), PARAMETER :: N7TAYl = 206 + INTEGER(IntKi), PARAMETER :: N7TAZl = 207 + INTEGER(IntKi), PARAMETER :: N8TAXl = 208 + INTEGER(IntKi), PARAMETER :: N8TAYl = 209 + INTEGER(IntKi), PARAMETER :: N8TAZl = 210 + INTEGER(IntKi), PARAMETER :: N9TAXl = 211 + INTEGER(IntKi), PARAMETER :: N9TAYl = 212 + INTEGER(IntKi), PARAMETER :: N9TAZl = 213 + INTEGER(IntKi), PARAMETER :: N1RAXl = 214 + INTEGER(IntKi), PARAMETER :: N1RAYl = 215 + INTEGER(IntKi), PARAMETER :: N1RAZl = 216 + INTEGER(IntKi), PARAMETER :: N2RAXl = 217 + INTEGER(IntKi), PARAMETER :: N2RAYl = 218 + INTEGER(IntKi), PARAMETER :: N2RAZl = 219 + INTEGER(IntKi), PARAMETER :: N3RAXl = 220 + INTEGER(IntKi), PARAMETER :: N3RAYl = 221 + INTEGER(IntKi), PARAMETER :: N3RAZl = 222 + INTEGER(IntKi), PARAMETER :: N4RAXl = 223 + INTEGER(IntKi), PARAMETER :: N4RAYl = 224 + INTEGER(IntKi), PARAMETER :: N4RAZl = 225 + INTEGER(IntKi), PARAMETER :: N5RAXl = 226 + INTEGER(IntKi), PARAMETER :: N5RAYl = 227 + INTEGER(IntKi), PARAMETER :: N5RAZl = 228 + INTEGER(IntKi), PARAMETER :: N6RAXl = 229 + INTEGER(IntKi), PARAMETER :: N6RAYl = 230 + INTEGER(IntKi), PARAMETER :: N6RAZl = 231 + INTEGER(IntKi), PARAMETER :: N7RAXl = 232 + INTEGER(IntKi), PARAMETER :: N7RAYl = 233 + INTEGER(IntKi), PARAMETER :: N7RAZl = 234 + INTEGER(IntKi), PARAMETER :: N8RAXl = 235 + INTEGER(IntKi), PARAMETER :: N8RAYl = 236 + INTEGER(IntKi), PARAMETER :: N8RAZl = 237 + INTEGER(IntKi), PARAMETER :: N9RAXl = 238 + INTEGER(IntKi), PARAMETER :: N9RAYl = 239 + INTEGER(IntKi), PARAMETER :: N9RAZl = 240 ! Applied Loads: - INTEGER(IntKi), PARAMETER :: N1PFxl = 241 - INTEGER(IntKi), PARAMETER :: N1PFyl = 242 - INTEGER(IntKi), PARAMETER :: N1PFzl = 243 - INTEGER(IntKi), PARAMETER :: N2PFxl = 244 - INTEGER(IntKi), PARAMETER :: N2PFyl = 245 - INTEGER(IntKi), PARAMETER :: N2PFzl = 246 - INTEGER(IntKi), PARAMETER :: N3PFxl = 247 - INTEGER(IntKi), PARAMETER :: N3PFyl = 248 - INTEGER(IntKi), PARAMETER :: N3PFzl = 249 - INTEGER(IntKi), PARAMETER :: N4PFxl = 250 - INTEGER(IntKi), PARAMETER :: N4PFyl = 251 - INTEGER(IntKi), PARAMETER :: N4PFzl = 252 - INTEGER(IntKi), PARAMETER :: N5PFxl = 253 - INTEGER(IntKi), PARAMETER :: N5PFyl = 254 - INTEGER(IntKi), PARAMETER :: N5PFzl = 255 - INTEGER(IntKi), PARAMETER :: N6PFxl = 256 - INTEGER(IntKi), PARAMETER :: N6PFyl = 257 - INTEGER(IntKi), PARAMETER :: N6PFzl = 258 - INTEGER(IntKi), PARAMETER :: N7PFxl = 259 - INTEGER(IntKi), PARAMETER :: N7PFyl = 260 - INTEGER(IntKi), PARAMETER :: N7PFzl = 261 - INTEGER(IntKi), PARAMETER :: N8PFxl = 262 - INTEGER(IntKi), PARAMETER :: N8PFyl = 263 - INTEGER(IntKi), PARAMETER :: N8PFzl = 264 - INTEGER(IntKi), PARAMETER :: N9PFxl = 265 - INTEGER(IntKi), PARAMETER :: N9PFyl = 266 - INTEGER(IntKi), PARAMETER :: N9PFzl = 267 - INTEGER(IntKi), PARAMETER :: N1PMxl = 268 - INTEGER(IntKi), PARAMETER :: N1PMyl = 269 - INTEGER(IntKi), PARAMETER :: N1PMzl = 270 - INTEGER(IntKi), PARAMETER :: N2PMxl = 271 - INTEGER(IntKi), PARAMETER :: N2PMyl = 272 - INTEGER(IntKi), PARAMETER :: N2PMzl = 273 - INTEGER(IntKi), PARAMETER :: N3PMxl = 274 - INTEGER(IntKi), PARAMETER :: N3PMyl = 275 - INTEGER(IntKi), PARAMETER :: N3PMzl = 276 - INTEGER(IntKi), PARAMETER :: N4PMxl = 277 - INTEGER(IntKi), PARAMETER :: N4PMyl = 278 - INTEGER(IntKi), PARAMETER :: N4PMzl = 279 - INTEGER(IntKi), PARAMETER :: N5PMxl = 280 - INTEGER(IntKi), PARAMETER :: N5PMyl = 281 - INTEGER(IntKi), PARAMETER :: N5PMzl = 282 - INTEGER(IntKi), PARAMETER :: N6PMxl = 283 - INTEGER(IntKi), PARAMETER :: N6PMyl = 284 - INTEGER(IntKi), PARAMETER :: N6PMzl = 285 - INTEGER(IntKi), PARAMETER :: N7PMxl = 286 - INTEGER(IntKi), PARAMETER :: N7PMyl = 287 - INTEGER(IntKi), PARAMETER :: N7PMzl = 288 - INTEGER(IntKi), PARAMETER :: N8PMxl = 289 - INTEGER(IntKi), PARAMETER :: N8PMyl = 290 - INTEGER(IntKi), PARAMETER :: N8PMzl = 291 - INTEGER(IntKi), PARAMETER :: N9PMxl = 292 - INTEGER(IntKi), PARAMETER :: N9PMyl = 293 - INTEGER(IntKi), PARAMETER :: N9PMzl = 294 - INTEGER(IntKi), PARAMETER :: N1DFxl = 295 - INTEGER(IntKi), PARAMETER :: N1DFyl = 296 - INTEGER(IntKi), PARAMETER :: N1DFzl = 297 - INTEGER(IntKi), PARAMETER :: N2DFxl = 298 - INTEGER(IntKi), PARAMETER :: N2DFyl = 299 - INTEGER(IntKi), PARAMETER :: N2DFzl = 300 - INTEGER(IntKi), PARAMETER :: N3DFxl = 301 - INTEGER(IntKi), PARAMETER :: N3DFyl = 302 - INTEGER(IntKi), PARAMETER :: N3DFzl = 303 - INTEGER(IntKi), PARAMETER :: N4DFxl = 304 - INTEGER(IntKi), PARAMETER :: N4DFyl = 305 - INTEGER(IntKi), PARAMETER :: N4DFzl = 306 - INTEGER(IntKi), PARAMETER :: N5DFxl = 307 - INTEGER(IntKi), PARAMETER :: N5DFyl = 308 - INTEGER(IntKi), PARAMETER :: N5DFzl = 309 - INTEGER(IntKi), PARAMETER :: N6DFxl = 310 - INTEGER(IntKi), PARAMETER :: N6DFyl = 311 - INTEGER(IntKi), PARAMETER :: N6DFzl = 312 - INTEGER(IntKi), PARAMETER :: N7DFxl = 313 - INTEGER(IntKi), PARAMETER :: N7DFyl = 314 - INTEGER(IntKi), PARAMETER :: N7DFzl = 315 - INTEGER(IntKi), PARAMETER :: N8DFxl = 316 - INTEGER(IntKi), PARAMETER :: N8DFyl = 317 - INTEGER(IntKi), PARAMETER :: N8DFzl = 318 - INTEGER(IntKi), PARAMETER :: N9DFxl = 319 - INTEGER(IntKi), PARAMETER :: N9DFyl = 320 - INTEGER(IntKi), PARAMETER :: N9DFzl = 321 - INTEGER(IntKi), PARAMETER :: N1DMxl = 322 - INTEGER(IntKi), PARAMETER :: N1DMyl = 323 - INTEGER(IntKi), PARAMETER :: N1DMzl = 324 - INTEGER(IntKi), PARAMETER :: N2DMxl = 325 - INTEGER(IntKi), PARAMETER :: N2DMyl = 326 - INTEGER(IntKi), PARAMETER :: N2DMzl = 327 - INTEGER(IntKi), PARAMETER :: N3DMxl = 328 - INTEGER(IntKi), PARAMETER :: N3DMyl = 329 - INTEGER(IntKi), PARAMETER :: N3DMzl = 330 - INTEGER(IntKi), PARAMETER :: N4DMxl = 331 - INTEGER(IntKi), PARAMETER :: N4DMyl = 332 - INTEGER(IntKi), PARAMETER :: N4DMzl = 333 - INTEGER(IntKi), PARAMETER :: N5DMxl = 334 - INTEGER(IntKi), PARAMETER :: N5DMyl = 335 - INTEGER(IntKi), PARAMETER :: N5DMzl = 336 - INTEGER(IntKi), PARAMETER :: N6DMxl = 337 - INTEGER(IntKi), PARAMETER :: N6DMyl = 338 - INTEGER(IntKi), PARAMETER :: N6DMzl = 339 - INTEGER(IntKi), PARAMETER :: N7DMxl = 340 - INTEGER(IntKi), PARAMETER :: N7DMyl = 341 - INTEGER(IntKi), PARAMETER :: N7DMzl = 342 - INTEGER(IntKi), PARAMETER :: N8DMxl = 343 - INTEGER(IntKi), PARAMETER :: N8DMyl = 344 - INTEGER(IntKi), PARAMETER :: N8DMzl = 345 - INTEGER(IntKi), PARAMETER :: N9DMxl = 346 - INTEGER(IntKi), PARAMETER :: N9DMyl = 347 - INTEGER(IntKi), PARAMETER :: N9DMzl = 348 + INTEGER(IntKi), PARAMETER :: N1PFxl = 241 + INTEGER(IntKi), PARAMETER :: N1PFyl = 242 + INTEGER(IntKi), PARAMETER :: N1PFzl = 243 + INTEGER(IntKi), PARAMETER :: N2PFxl = 244 + INTEGER(IntKi), PARAMETER :: N2PFyl = 245 + INTEGER(IntKi), PARAMETER :: N2PFzl = 246 + INTEGER(IntKi), PARAMETER :: N3PFxl = 247 + INTEGER(IntKi), PARAMETER :: N3PFyl = 248 + INTEGER(IntKi), PARAMETER :: N3PFzl = 249 + INTEGER(IntKi), PARAMETER :: N4PFxl = 250 + INTEGER(IntKi), PARAMETER :: N4PFyl = 251 + INTEGER(IntKi), PARAMETER :: N4PFzl = 252 + INTEGER(IntKi), PARAMETER :: N5PFxl = 253 + INTEGER(IntKi), PARAMETER :: N5PFyl = 254 + INTEGER(IntKi), PARAMETER :: N5PFzl = 255 + INTEGER(IntKi), PARAMETER :: N6PFxl = 256 + INTEGER(IntKi), PARAMETER :: N6PFyl = 257 + INTEGER(IntKi), PARAMETER :: N6PFzl = 258 + INTEGER(IntKi), PARAMETER :: N7PFxl = 259 + INTEGER(IntKi), PARAMETER :: N7PFyl = 260 + INTEGER(IntKi), PARAMETER :: N7PFzl = 261 + INTEGER(IntKi), PARAMETER :: N8PFxl = 262 + INTEGER(IntKi), PARAMETER :: N8PFyl = 263 + INTEGER(IntKi), PARAMETER :: N8PFzl = 264 + INTEGER(IntKi), PARAMETER :: N9PFxl = 265 + INTEGER(IntKi), PARAMETER :: N9PFyl = 266 + INTEGER(IntKi), PARAMETER :: N9PFzl = 267 + INTEGER(IntKi), PARAMETER :: N1PMxl = 268 + INTEGER(IntKi), PARAMETER :: N1PMyl = 269 + INTEGER(IntKi), PARAMETER :: N1PMzl = 270 + INTEGER(IntKi), PARAMETER :: N2PMxl = 271 + INTEGER(IntKi), PARAMETER :: N2PMyl = 272 + INTEGER(IntKi), PARAMETER :: N2PMzl = 273 + INTEGER(IntKi), PARAMETER :: N3PMxl = 274 + INTEGER(IntKi), PARAMETER :: N3PMyl = 275 + INTEGER(IntKi), PARAMETER :: N3PMzl = 276 + INTEGER(IntKi), PARAMETER :: N4PMxl = 277 + INTEGER(IntKi), PARAMETER :: N4PMyl = 278 + INTEGER(IntKi), PARAMETER :: N4PMzl = 279 + INTEGER(IntKi), PARAMETER :: N5PMxl = 280 + INTEGER(IntKi), PARAMETER :: N5PMyl = 281 + INTEGER(IntKi), PARAMETER :: N5PMzl = 282 + INTEGER(IntKi), PARAMETER :: N6PMxl = 283 + INTEGER(IntKi), PARAMETER :: N6PMyl = 284 + INTEGER(IntKi), PARAMETER :: N6PMzl = 285 + INTEGER(IntKi), PARAMETER :: N7PMxl = 286 + INTEGER(IntKi), PARAMETER :: N7PMyl = 287 + INTEGER(IntKi), PARAMETER :: N7PMzl = 288 + INTEGER(IntKi), PARAMETER :: N8PMxl = 289 + INTEGER(IntKi), PARAMETER :: N8PMyl = 290 + INTEGER(IntKi), PARAMETER :: N8PMzl = 291 + INTEGER(IntKi), PARAMETER :: N9PMxl = 292 + INTEGER(IntKi), PARAMETER :: N9PMyl = 293 + INTEGER(IntKi), PARAMETER :: N9PMzl = 294 + INTEGER(IntKi), PARAMETER :: N1DFxl = 295 + INTEGER(IntKi), PARAMETER :: N1DFyl = 296 + INTEGER(IntKi), PARAMETER :: N1DFzl = 297 + INTEGER(IntKi), PARAMETER :: N2DFxl = 298 + INTEGER(IntKi), PARAMETER :: N2DFyl = 299 + INTEGER(IntKi), PARAMETER :: N2DFzl = 300 + INTEGER(IntKi), PARAMETER :: N3DFxl = 301 + INTEGER(IntKi), PARAMETER :: N3DFyl = 302 + INTEGER(IntKi), PARAMETER :: N3DFzl = 303 + INTEGER(IntKi), PARAMETER :: N4DFxl = 304 + INTEGER(IntKi), PARAMETER :: N4DFyl = 305 + INTEGER(IntKi), PARAMETER :: N4DFzl = 306 + INTEGER(IntKi), PARAMETER :: N5DFxl = 307 + INTEGER(IntKi), PARAMETER :: N5DFyl = 308 + INTEGER(IntKi), PARAMETER :: N5DFzl = 309 + INTEGER(IntKi), PARAMETER :: N6DFxl = 310 + INTEGER(IntKi), PARAMETER :: N6DFyl = 311 + INTEGER(IntKi), PARAMETER :: N6DFzl = 312 + INTEGER(IntKi), PARAMETER :: N7DFxl = 313 + INTEGER(IntKi), PARAMETER :: N7DFyl = 314 + INTEGER(IntKi), PARAMETER :: N7DFzl = 315 + INTEGER(IntKi), PARAMETER :: N8DFxl = 316 + INTEGER(IntKi), PARAMETER :: N8DFyl = 317 + INTEGER(IntKi), PARAMETER :: N8DFzl = 318 + INTEGER(IntKi), PARAMETER :: N9DFxl = 319 + INTEGER(IntKi), PARAMETER :: N9DFyl = 320 + INTEGER(IntKi), PARAMETER :: N9DFzl = 321 + INTEGER(IntKi), PARAMETER :: N1DMxl = 322 + INTEGER(IntKi), PARAMETER :: N1DMyl = 323 + INTEGER(IntKi), PARAMETER :: N1DMzl = 324 + INTEGER(IntKi), PARAMETER :: N2DMxl = 325 + INTEGER(IntKi), PARAMETER :: N2DMyl = 326 + INTEGER(IntKi), PARAMETER :: N2DMzl = 327 + INTEGER(IntKi), PARAMETER :: N3DMxl = 328 + INTEGER(IntKi), PARAMETER :: N3DMyl = 329 + INTEGER(IntKi), PARAMETER :: N3DMzl = 330 + INTEGER(IntKi), PARAMETER :: N4DMxl = 331 + INTEGER(IntKi), PARAMETER :: N4DMyl = 332 + INTEGER(IntKi), PARAMETER :: N4DMzl = 333 + INTEGER(IntKi), PARAMETER :: N5DMxl = 334 + INTEGER(IntKi), PARAMETER :: N5DMyl = 335 + INTEGER(IntKi), PARAMETER :: N5DMzl = 336 + INTEGER(IntKi), PARAMETER :: N6DMxl = 337 + INTEGER(IntKi), PARAMETER :: N6DMyl = 338 + INTEGER(IntKi), PARAMETER :: N6DMzl = 339 + INTEGER(IntKi), PARAMETER :: N7DMxl = 340 + INTEGER(IntKi), PARAMETER :: N7DMyl = 341 + INTEGER(IntKi), PARAMETER :: N7DMzl = 342 + INTEGER(IntKi), PARAMETER :: N8DMxl = 343 + INTEGER(IntKi), PARAMETER :: N8DMyl = 344 + INTEGER(IntKi), PARAMETER :: N8DMzl = 345 + INTEGER(IntKi), PARAMETER :: N9DMxl = 346 + INTEGER(IntKi), PARAMETER :: N9DMyl = 347 + INTEGER(IntKi), PARAMETER :: N9DMzl = 348 + + + ! Applied loads mapped to root (includes distributed and point): + + INTEGER(IntKi), PARAMETER :: RootAppliedFxr = 349 + INTEGER(IntKi), PARAMETER :: RootAppliedFyr = 350 + INTEGER(IntKi), PARAMETER :: RootAppliedFzr = 351 + INTEGER(IntKi), PARAMETER :: RootAppliedMxr = 352 + INTEGER(IntKi), PARAMETER :: RootAppliedMyr = 353 + INTEGER(IntKi), PARAMETER :: RootAppliedMzr = 354 + INTEGER(IntKi), PARAMETER :: RootAppliedFxg = 355 + INTEGER(IntKi), PARAMETER :: RootAppliedFyg = 356 + INTEGER(IntKi), PARAMETER :: RootAppliedFzg = 357 + INTEGER(IntKi), PARAMETER :: RootAppliedMxg = 358 + INTEGER(IntKi), PARAMETER :: RootAppliedMyg = 359 + INTEGER(IntKi), PARAMETER :: RootAppliedMzg = 360 ! Pitch Actuator: - INTEGER(IntKi), PARAMETER :: PAngInp = 349 - INTEGER(IntKi), PARAMETER :: PAngAct = 350 - INTEGER(IntKi), PARAMETER :: PRatAct = 351 - INTEGER(IntKi), PARAMETER :: PAccAct = 352 + INTEGER(IntKi), PARAMETER :: PAngInp = 361 + INTEGER(IntKi), PARAMETER :: PAngAct = 362 + INTEGER(IntKi), PARAMETER :: PRatAct = 363 + INTEGER(IntKi), PARAMETER :: PAccAct = 364 ! The maximum number of output channels which can be output by the code. - INTEGER(IntKi), PARAMETER :: MaxOutPts = 352 + INTEGER(IntKi), PARAMETER :: MaxOutPts = 364 !End of code generated by Matlab script ! =================================================================================================== @@ -1159,15 +1175,16 @@ END SUBROUTINE BD_ReadBladeFile !---------------------------------------------------------------------------------------------------------------------------------- !********************************************************************************************************************************** ! NOTE: The following lines of code were generated by a Matlab script called "Write_ChckOutLst.m" -! using the parameters listed in the "OutListParameters.xlsx" Excel file. Any changes to these -! lines should be modified in the Matlab script and/or Excel worksheet as necessary. -! This code was generated by Write_ChckOutLst.m at 29-Sep-2015 10:23:41. +! using the parameters listed in the "OutListParameters.xlsx" Excel file. Any changes to these +! lines should be modified in the Matlab script and/or Excel worksheet as necessary. !---------------------------------------------------------------------------------------------------------------------------------- -!> This routine checks to see if any requested output channel names (stored in the OutList(:)) are invalid. It returns a +!> This routine checks to see if any requested output channel names (stored in the OutList(:)) are invalid. It returns a !! warning if any of the channels are not available outputs from the module. !! It assigns the settings for OutParam(:) (i.e, the index, name, and units of the output channels, WriteOutput(:)). !! the sign is set to 0 if the channel is invalid. !! It sets assumes the value p%NumOuts has been set before this routine has been called, and it sets the values of p%OutParam here. +!! +!! This routine was generated by Write_ChckOutLst.m using the parameters listed in OutListParameters.xlsx at 08-May-2025 15:51:30. SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) IMPLICIT NONE @@ -1191,162 +1208,232 @@ SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) CHARACTER(ChanLen) :: OutListTmp ! A string to temporarily hold OutList(I) CHARACTER(*), PARAMETER :: RoutineName = "SetOutParam" - CHARACTER(OutStrLenM1), PARAMETER :: ValidParamAry(352) = (/ & ! This lists the names of the allowed parameters, which must be sorted alphabetically - "N1DFXL ","N1DFYL ","N1DFZL ","N1DMXL ","N1DMYL ","N1DMZL ","N1FXL ", & - "N1FYL ","N1FZL ","N1MXL ","N1MYL ","N1MZL ","N1PFXL ","N1PFYL ", & - "N1PFZL ","N1PMXL ","N1PMYL ","N1PMZL ","N1RAXL ","N1RAYL ","N1RAZL ", & - "N1RDXR ","N1RDYR ","N1RDZR ","N1RVXG ","N1RVYG ","N1RVZG ","N1TAXL ", & - "N1TAYL ","N1TAZL ","N1TDXR ","N1TDYR ","N1TDZR ","N1TVXG ","N1TVYG ", & - "N1TVZG ","N2DFXL ","N2DFYL ","N2DFZL ","N2DMXL ","N2DMYL ","N2DMZL ", & - "N2FXL ","N2FYL ","N2FZL ","N2MXL ","N2MYL ","N2MZL ","N2PFXL ", & - "N2PFYL ","N2PFZL ","N2PMXL ","N2PMYL ","N2PMZL ","N2RAXL ","N2RAYL ", & - "N2RAZL ","N2RDXR ","N2RDYR ","N2RDZR ","N2RVXG ","N2RVYG ","N2RVZG ", & - "N2TAXL ","N2TAYL ","N2TAZL ","N2TDXR ","N2TDYR ","N2TDZR ","N2TVXG ", & - "N2TVYG ","N2TVZG ","N3DFXL ","N3DFYL ","N3DFZL ","N3DMXL ","N3DMYL ", & - "N3DMZL ","N3FXL ","N3FYL ","N3FZL ","N3MXL ","N3MYL ","N3MZL ", & - "N3PFXL ","N3PFYL ","N3PFZL ","N3PMXL ","N3PMYL ","N3PMZL ","N3RAXL ", & - "N3RAYL ","N3RAZL ","N3RDXR ","N3RDYR ","N3RDZR ","N3RVXG ","N3RVYG ", & - "N3RVZG ","N3TAXL ","N3TAYL ","N3TAZL ","N3TDXR ","N3TDYR ","N3TDZR ", & - "N3TVXG ","N3TVYG ","N3TVZG ","N4DFXL ","N4DFYL ","N4DFZL ","N4DMXL ", & - "N4DMYL ","N4DMZL ","N4FXL ","N4FYL ","N4FZL ","N4MXL ","N4MYL ", & - "N4MZL ","N4PFXL ","N4PFYL ","N4PFZL ","N4PMXL ","N4PMYL ","N4PMZL ", & - "N4RAXL ","N4RAYL ","N4RAZL ","N4RDXR ","N4RDYR ","N4RDZR ","N4RVXG ", & - "N4RVYG ","N4RVZG ","N4TAXL ","N4TAYL ","N4TAZL ","N4TDXR ","N4TDYR ", & - "N4TDZR ","N4TVXG ","N4TVYG ","N4TVZG ","N5DFXL ","N5DFYL ","N5DFZL ", & - "N5DMXL ","N5DMYL ","N5DMZL ","N5FXL ","N5FYL ","N5FZL ","N5MXL ", & - "N5MYL ","N5MZL ","N5PFXL ","N5PFYL ","N5PFZL ","N5PMXL ","N5PMYL ", & - "N5PMZL ","N5RAXL ","N5RAYL ","N5RAZL ","N5RDXR ","N5RDYR ","N5RDZR ", & - "N5RVXG ","N5RVYG ","N5RVZG ","N5TAXL ","N5TAYL ","N5TAZL ","N5TDXR ", & - "N5TDYR ","N5TDZR ","N5TVXG ","N5TVYG ","N5TVZG ","N6DFXL ","N6DFYL ", & - "N6DFZL ","N6DMXL ","N6DMYL ","N6DMZL ","N6FXL ","N6FYL ","N6FZL ", & - "N6MXL ","N6MYL ","N6MZL ","N6PFXL ","N6PFYL ","N6PFZL ","N6PMXL ", & - "N6PMYL ","N6PMZL ","N6RAXL ","N6RAYL ","N6RAZL ","N6RDXR ","N6RDYR ", & - "N6RDZR ","N6RVXG ","N6RVYG ","N6RVZG ","N6TAXL ","N6TAYL ","N6TAZL ", & - "N6TDXR ","N6TDYR ","N6TDZR ","N6TVXG ","N6TVYG ","N6TVZG ","N7DFXL ", & - "N7DFYL ","N7DFZL ","N7DMXL ","N7DMYL ","N7DMZL ","N7FXL ","N7FYL ", & - "N7FZL ","N7MXL ","N7MYL ","N7MZL ","N7PFXL ","N7PFYL ","N7PFZL ", & - "N7PMXL ","N7PMYL ","N7PMZL ","N7RAXL ","N7RAYL ","N7RAZL ","N7RDXR ", & - "N7RDYR ","N7RDZR ","N7RVXG ","N7RVYG ","N7RVZG ","N7TAXL ","N7TAYL ", & - "N7TAZL ","N7TDXR ","N7TDYR ","N7TDZR ","N7TVXG ","N7TVYG ","N7TVZG ", & - "N8DFXL ","N8DFYL ","N8DFZL ","N8DMXL ","N8DMYL ","N8DMZL ","N8FXL ", & - "N8FYL ","N8FZL ","N8MXL ","N8MYL ","N8MZL ","N8PFXL ","N8PFYL ", & - "N8PFZL ","N8PMXL ","N8PMYL ","N8PMZL ","N8RAXL ","N8RAYL ","N8RAZL ", & - "N8RDXR ","N8RDYR ","N8RDZR ","N8RVXG ","N8RVYG ","N8RVZG ","N8TAXL ", & - "N8TAYL ","N8TAZL ","N8TDXR ","N8TDYR ","N8TDZR ","N8TVXG ","N8TVYG ", & - "N8TVZG ","N9DFXL ","N9DFYL ","N9DFZL ","N9DMXL ","N9DMYL ","N9DMZL ", & - "N9FXL ","N9FYL ","N9FZL ","N9MXL ","N9MYL ","N9MZL ","N9PFXL ", & - "N9PFYL ","N9PFZL ","N9PMXL ","N9PMYL ","N9PMZL ","N9RAXL ","N9RAYL ", & - "N9RAZL ","N9RDXR ","N9RDYR ","N9RDZR ","N9RVXG ","N9RVYG ","N9RVZG ", & - "N9TAXL ","N9TAYL ","N9TAZL ","N9TDXR ","N9TDYR ","N9TDZR ","N9TVXG ", & - "N9TVYG ","N9TVZG ","PACCACT ","PANGACT ","PANGINP ","PRATACT ","ROOTFXR ", & - "ROOTFYR ","ROOTFZR ","ROOTMXR ","ROOTMYR ","ROOTMZR ","TIPRAXL ","TIPRAYL ", & - "TIPRAZL ","TIPRDXR ","TIPRDYR ","TIPRDZR ","TIPRVXG ","TIPRVYG ","TIPRVZG ", & - "TIPTAXL ","TIPTAYL ","TIPTAZL ","TIPTDXR ","TIPTDYR ","TIPTDZR ","TIPTVXG ", & - "TIPTVYG ","TIPTVZG "/) - INTEGER(IntKi), PARAMETER :: ParamIndxAry(352) = (/ & ! This lists the index into AllOuts(:) of the allowed parameters ValidParamAry(:) - N1DFxl , N1DFyl , N1DFzl , N1DMxl , N1DMyl , N1DMzl , N1Fxl , & - N1Fyl , N1Fzl , N1Mxl , N1Myl , N1Mzl , N1PFxl , N1PFyl , & - N1PFzl , N1PMxl , N1PMyl , N1PMzl , N1RAXl , N1RAYl , N1RAZl , & - N1RDxr , N1RDyr , N1RDzr , N1RVXg , N1RVYg , N1RVZg , N1TAXl , & - N1TAYl , N1TAZl , N1TDxr , N1TDyr , N1TDzr , N1TVXg , N1TVYg , & - N1TVZg , N2DFxl , N2DFyl , N2DFzl , N2DMxl , N2DMyl , N2DMzl , & - N2Fxl , N2Fyl , N2Fzl , N2Mxl , N2Myl , N2Mzl , N2PFxl , & - N2PFyl , N2PFzl , N2PMxl , N2PMyl , N2PMzl , N2RAXl , N2RAYl , & - N2RAZl , N2RDxr , N2RDyr , N2RDzr , N2RVXg , N2RVYg , N2RVZg , & - N2TAXl , N2TAYl , N2TAZl , N2TDxr , N2TDyr , N2TDzr , N2TVXg , & - N2TVYg , N2TVZg , N3DFxl , N3DFyl , N3DFzl , N3DMxl , N3DMyl , & - N3DMzl , N3Fxl , N3Fyl , N3Fzl , N3Mxl , N3Myl , N3Mzl , & - N3PFxl , N3PFyl , N3PFzl , N3PMxl , N3PMyl , N3PMzl , N3RAXl , & - N3RAYl , N3RAZl , N3RDxr , N3RDyr , N3RDzr , N3RVXg , N3RVYg , & - N3RVZg , N3TAXl , N3TAYl , N3TAZl , N3TDxr , N3TDyr , N3TDzr , & - N3TVXg , N3TVYg , N3TVZg , N4DFxl , N4DFyl , N4DFzl , N4DMxl , & - N4DMyl , N4DMzl , N4Fxl , N4Fyl , N4Fzl , N4Mxl , N4Myl , & - N4Mzl , N4PFxl , N4PFyl , N4PFzl , N4PMxl , N4PMyl , N4PMzl , & - N4RAXl , N4RAYl , N4RAZl , N4RDxr , N4RDyr , N4RDzr , N4RVXg , & - N4RVYg , N4RVZg , N4TAXl , N4TAYl , N4TAZl , N4TDxr , N4TDyr , & - N4TDzr , N4TVXg , N4TVYg , N4TVZg , N5DFxl , N5DFyl , N5DFzl , & - N5DMxl , N5DMyl , N5DMzl , N5Fxl , N5Fyl , N5Fzl , N5Mxl , & - N5Myl , N5Mzl , N5PFxl , N5PFyl , N5PFzl , N5PMxl , N5PMyl , & - N5PMzl , N5RAXl , N5RAYl , N5RAZl , N5RDxr , N5RDyr , N5RDzr , & - N5RVXg , N5RVYg , N5RVZg , N5TAXl , N5TAYl , N5TAZl , N5TDxr , & - N5TDyr , N5TDzr , N5TVXg , N5TVYg , N5TVZg , N6DFxl , N6DFyl , & - N6DFzl , N6DMxl , N6DMyl , N6DMzl , N6Fxl , N6Fyl , N6Fzl , & - N6Mxl , N6Myl , N6Mzl , N6PFxl , N6PFyl , N6PFzl , N6PMxl , & - N6PMyl , N6PMzl , N6RAXl , N6RAYl , N6RAZl , N6RDxr , N6RDyr , & - N6RDzr , N6RVXg , N6RVYg , N6RVZg , N6TAXl , N6TAYl , N6TAZl , & - N6TDxr , N6TDyr , N6TDzr , N6TVXg , N6TVYg , N6TVZg , N7DFxl , & - N7DFyl , N7DFzl , N7DMxl , N7DMyl , N7DMzl , N7Fxl , N7Fyl , & - N7Fzl , N7Mxl , N7Myl , N7Mzl , N7PFxl , N7PFyl , N7PFzl , & - N7PMxl , N7PMyl , N7PMzl , N7RAXl , N7RAYl , N7RAZl , N7RDxr , & - N7RDyr , N7RDzr , N7RVXg , N7RVYg , N7RVZg , N7TAXl , N7TAYl , & - N7TAZl , N7TDxr , N7TDyr , N7TDzr , N7TVXg , N7TVYg , N7TVZg , & - N8DFxl , N8DFyl , N8DFzl , N8DMxl , N8DMyl , N8DMzl , N8Fxl , & - N8Fyl , N8Fzl , N8Mxl , N8Myl , N8Mzl , N8PFxl , N8PFyl , & - N8PFzl , N8PMxl , N8PMyl , N8PMzl , N8RAXl , N8RAYl , N8RAZl , & - N8RDxr , N8RDyr , N8RDzr , N8RVXg , N8RVYg , N8RVZg , N8TAXl , & - N8TAYl , N8TAZl , N8TDxr , N8TDyr , N8TDzr , N8TVXg , N8TVYg , & - N8TVZg , N9DFxl , N9DFyl , N9DFzl , N9DMxl , N9DMyl , N9DMzl , & - N9Fxl , N9Fyl , N9Fzl , N9Mxl , N9Myl , N9Mzl , N9PFxl , & - N9PFyl , N9PFzl , N9PMxl , N9PMyl , N9PMzl , N9RAXl , N9RAYl , & - N9RAZl , N9RDxr , N9RDyr , N9RDzr , N9RVXg , N9RVYg , N9RVZg , & - N9TAXl , N9TAYl , N9TAZl , N9TDxr , N9TDyr , N9TDzr , N9TVXg , & - N9TVYg , N9TVZg , PAccAct , PAngAct , PAngInp , PRatAct , RootFxr , & - RootFyr , RootFzr , RootMxr , RootMyr , RootMzr , TipRAXl , TipRAYl , & - TipRAZl , TipRDxr , TipRDyr , TipRDzr , TipRVXg , TipRVYg , TipRVZg , & - TipTAXl , TipTAYl , TipTAZl , TipTDxr , TipTDyr , TipTDzr , TipTVXg , & - TipTVYg , TipTVZg /) - CHARACTER(ChanLen), PARAMETER :: ParamUnitsAry(352) = (/ & ! This lists the units corresponding to the allowed parameters - "(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ", & - "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ", & - "(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ","(deg/s^2) ", & - "(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ", & - "(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ","(m/s) ", & - "(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ", & - "(N) ","(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ", & - "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ", & - "(deg/s^2) ","(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & - "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ", & - "(m/s) ","(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ", & - "(N-m/m) ","(N) ","(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & - "(N) ","(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ", & - "(deg/s^2) ","(deg/s^2) ","(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ", & - "(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ", & - "(m/s) ","(m/s) ","(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ", & - "(N-m/m) ","(N-m/m) ","(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & - "(N-m) ","(N) ","(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & - "(deg/s^2) ","(deg/s^2) ","(deg/s^2) ","(-) ","(-) ","(-) ","(deg/s) ", & - "(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ", & - "(m) ","(m/s) ","(m/s) ","(m/s) ","(N/m) ","(N/m) ","(N/m) ", & - "(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ","(N) ","(N) ","(N-m) ", & - "(N-m) ","(N-m) ","(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & - "(N-m) ","(deg/s^2) ","(deg/s^2) ","(deg/s^2) ","(-) ","(-) ","(-) ", & - "(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ", & - "(m) ","(m) ","(m/s) ","(m/s) ","(m/s) ","(N/m) ","(N/m) ", & - "(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ","(N) ","(N) ", & - "(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ","(N) ","(N-m) ", & - "(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ","(deg/s^2) ","(-) ","(-) ", & - "(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ", & - "(m) ","(m) ","(m) ","(m/s) ","(m/s) ","(m/s) ","(N/m) ", & - "(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ","(N) ", & - "(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ","(N) ", & - "(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ","(deg/s^2) ","(-) ", & - "(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ", & - "(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ","(m/s) ","(m/s) ", & - "(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ", & - "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ", & - "(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ","(deg/s^2) ", & - "(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ", & - "(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ","(m/s) ", & - "(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ", & - "(N) ","(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ", & - "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ", & - "(deg/s^2) ","(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & - "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ", & - "(m/s) ","(m/s) ","(deg/s^2) ","(deg) ","(deg) ","(deg/s) ","(N) ", & - "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2) ","(deg/s^2) ", & - "(deg/s^2) ","(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & - "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ", & - "(m/s) ","(m/s) "/) + CHARACTER(OutStrLenM1), PARAMETER :: ValidParamAry(364) = (/ & ! This lists the names of the allowed parameters, which must be sorted alphabetically + "N1DFXL ","N1DFYL ","N1DFZL ","N1DMXL ","N1DMYL ", & + "N1DMZL ","N1FXL ","N1FYL ","N1FZL ","N1MXL ", & + "N1MYL ","N1MZL ","N1PFXL ","N1PFYL ","N1PFZL ", & + "N1PMXL ","N1PMYL ","N1PMZL ","N1RAXL ","N1RAYL ", & + "N1RAZL ","N1RDXR ","N1RDYR ","N1RDZR ","N1RVXG ", & + "N1RVYG ","N1RVZG ","N1TAXL ","N1TAYL ","N1TAZL ", & + "N1TDXR ","N1TDYR ","N1TDZR ","N1TVXG ","N1TVYG ", & + "N1TVZG ","N2DFXL ","N2DFYL ","N2DFZL ","N2DMXL ", & + "N2DMYL ","N2DMZL ","N2FXL ","N2FYL ","N2FZL ", & + "N2MXL ","N2MYL ","N2MZL ","N2PFXL ","N2PFYL ", & + "N2PFZL ","N2PMXL ","N2PMYL ","N2PMZL ","N2RAXL ", & + "N2RAYL ","N2RAZL ","N2RDXR ","N2RDYR ","N2RDZR ", & + "N2RVXG ","N2RVYG ","N2RVZG ","N2TAXL ","N2TAYL ", & + "N2TAZL ","N2TDXR ","N2TDYR ","N2TDZR ","N2TVXG ", & + "N2TVYG ","N2TVZG ","N3DFXL ","N3DFYL ","N3DFZL ", & + "N3DMXL ","N3DMYL ","N3DMZL ","N3FXL ","N3FYL ", & + "N3FZL ","N3MXL ","N3MYL ","N3MZL ","N3PFXL ", & + "N3PFYL ","N3PFZL ","N3PMXL ","N3PMYL ","N3PMZL ", & + "N3RAXL ","N3RAYL ","N3RAZL ","N3RDXR ","N3RDYR ", & + "N3RDZR ","N3RVXG ","N3RVYG ","N3RVZG ","N3TAXL ", & + "N3TAYL ","N3TAZL ","N3TDXR ","N3TDYR ","N3TDZR ", & + "N3TVXG ","N3TVYG ","N3TVZG ","N4DFXL ","N4DFYL ", & + "N4DFZL ","N4DMXL ","N4DMYL ","N4DMZL ","N4FXL ", & + "N4FYL ","N4FZL ","N4MXL ","N4MYL ","N4MZL ", & + "N4PFXL ","N4PFYL ","N4PFZL ","N4PMXL ","N4PMYL ", & + "N4PMZL ","N4RAXL ","N4RAYL ","N4RAZL ","N4RDXR ", & + "N4RDYR ","N4RDZR ","N4RVXG ","N4RVYG ","N4RVZG ", & + "N4TAXL ","N4TAYL ","N4TAZL ","N4TDXR ","N4TDYR ", & + "N4TDZR ","N4TVXG ","N4TVYG ","N4TVZG ","N5DFXL ", & + "N5DFYL ","N5DFZL ","N5DMXL ","N5DMYL ","N5DMZL ", & + "N5FXL ","N5FYL ","N5FZL ","N5MXL ","N5MYL ", & + "N5MZL ","N5PFXL ","N5PFYL ","N5PFZL ","N5PMXL ", & + "N5PMYL ","N5PMZL ","N5RAXL ","N5RAYL ","N5RAZL ", & + "N5RDXR ","N5RDYR ","N5RDZR ","N5RVXG ","N5RVYG ", & + "N5RVZG ","N5TAXL ","N5TAYL ","N5TAZL ","N5TDXR ", & + "N5TDYR ","N5TDZR ","N5TVXG ","N5TVYG ","N5TVZG ", & + "N6DFXL ","N6DFYL ","N6DFZL ","N6DMXL ","N6DMYL ", & + "N6DMZL ","N6FXL ","N6FYL ","N6FZL ","N6MXL ", & + "N6MYL ","N6MZL ","N6PFXL ","N6PFYL ","N6PFZL ", & + "N6PMXL ","N6PMYL ","N6PMZL ","N6RAXL ","N6RAYL ", & + "N6RAZL ","N6RDXR ","N6RDYR ","N6RDZR ","N6RVXG ", & + "N6RVYG ","N6RVZG ","N6TAXL ","N6TAYL ","N6TAZL ", & + "N6TDXR ","N6TDYR ","N6TDZR ","N6TVXG ","N6TVYG ", & + "N6TVZG ","N7DFXL ","N7DFYL ","N7DFZL ","N7DMXL ", & + "N7DMYL ","N7DMZL ","N7FXL ","N7FYL ","N7FZL ", & + "N7MXL ","N7MYL ","N7MZL ","N7PFXL ","N7PFYL ", & + "N7PFZL ","N7PMXL ","N7PMYL ","N7PMZL ","N7RAXL ", & + "N7RAYL ","N7RAZL ","N7RDXR ","N7RDYR ","N7RDZR ", & + "N7RVXG ","N7RVYG ","N7RVZG ","N7TAXL ","N7TAYL ", & + "N7TAZL ","N7TDXR ","N7TDYR ","N7TDZR ","N7TVXG ", & + "N7TVYG ","N7TVZG ","N8DFXL ","N8DFYL ","N8DFZL ", & + "N8DMXL ","N8DMYL ","N8DMZL ","N8FXL ","N8FYL ", & + "N8FZL ","N8MXL ","N8MYL ","N8MZL ","N8PFXL ", & + "N8PFYL ","N8PFZL ","N8PMXL ","N8PMYL ","N8PMZL ", & + "N8RAXL ","N8RAYL ","N8RAZL ","N8RDXR ","N8RDYR ", & + "N8RDZR ","N8RVXG ","N8RVYG ","N8RVZG ","N8TAXL ", & + "N8TAYL ","N8TAZL ","N8TDXR ","N8TDYR ","N8TDZR ", & + "N8TVXG ","N8TVYG ","N8TVZG ","N9DFXL ","N9DFYL ", & + "N9DFZL ","N9DMXL ","N9DMYL ","N9DMZL ","N9FXL ", & + "N9FYL ","N9FZL ","N9MXL ","N9MYL ","N9MZL ", & + "N9PFXL ","N9PFYL ","N9PFZL ","N9PMXL ","N9PMYL ", & + "N9PMZL ","N9RAXL ","N9RAYL ","N9RAZL ","N9RDXR ", & + "N9RDYR ","N9RDZR ","N9RVXG ","N9RVYG ","N9RVZG ", & + "N9TAXL ","N9TAYL ","N9TAZL ","N9TDXR ","N9TDYR ", & + "N9TDZR ","N9TVXG ","N9TVYG ","N9TVZG ","PACCACT ", & + "PANGACT ","PANGINP ","PRATACT ","ROOTAPPLIEDFXG","ROOTAPPLIEDFXR", & + "ROOTAPPLIEDFYG","ROOTAPPLIEDFYR","ROOTAPPLIEDFZG","ROOTAPPLIEDFZR","ROOTAPPLIEDMXG", & + "ROOTAPPLIEDMXR","ROOTAPPLIEDMYG","ROOTAPPLIEDMYR","ROOTAPPLIEDMZG","ROOTAPPLIEDMZR", & + "ROOTFXR ","ROOTFYR ","ROOTFZR ","ROOTMXR ","ROOTMYR ", & + "ROOTMZR ","TIPRAXL ","TIPRAYL ","TIPRAZL ","TIPRDXR ", & + "TIPRDYR ","TIPRDZR ","TIPRVXG ","TIPRVYG ","TIPRVZG ", & + "TIPTAXL ","TIPTAYL ","TIPTAZL ","TIPTDXR ","TIPTDYR ", & + "TIPTDZR ","TIPTVXG ","TIPTVYG ","TIPTVZG "/) + INTEGER(IntKi), PARAMETER :: ParamIndxAry(364) = (/ & ! This lists the index into AllOuts(:) of the allowed parameters ValidParamAry(:) + N1DFxl , N1DFyl , N1DFzl , N1DMxl , N1DMyl , & + N1DMzl , N1Fxl , N1Fyl , N1Fzl , N1Mxl , & + N1Myl , N1Mzl , N1PFxl , N1PFyl , N1PFzl , & + N1PMxl , N1PMyl , N1PMzl , N1RAXl , N1RAYl , & + N1RAZl , N1RDxr , N1RDyr , N1RDzr , N1RVXg , & + N1RVYg , N1RVZg , N1TAXl , N1TAYl , N1TAZl , & + N1TDxr , N1TDyr , N1TDzr , N1TVXg , N1TVYg , & + N1TVZg , N2DFxl , N2DFyl , N2DFzl , N2DMxl , & + N2DMyl , N2DMzl , N2Fxl , N2Fyl , N2Fzl , & + N2Mxl , N2Myl , N2Mzl , N2PFxl , N2PFyl , & + N2PFzl , N2PMxl , N2PMyl , N2PMzl , N2RAXl , & + N2RAYl , N2RAZl , N2RDxr , N2RDyr , N2RDzr , & + N2RVXg , N2RVYg , N2RVZg , N2TAXl , N2TAYl , & + N2TAZl , N2TDxr , N2TDyr , N2TDzr , N2TVXg , & + N2TVYg , N2TVZg , N3DFxl , N3DFyl , N3DFzl , & + N3DMxl , N3DMyl , N3DMzl , N3Fxl , N3Fyl , & + N3Fzl , N3Mxl , N3Myl , N3Mzl , N3PFxl , & + N3PFyl , N3PFzl , N3PMxl , N3PMyl , N3PMzl , & + N3RAXl , N3RAYl , N3RAZl , N3RDxr , N3RDyr , & + N3RDzr , N3RVXg , N3RVYg , N3RVZg , N3TAXl , & + N3TAYl , N3TAZl , N3TDxr , N3TDyr , N3TDzr , & + N3TVXg , N3TVYg , N3TVZg , N4DFxl , N4DFyl , & + N4DFzl , N4DMxl , N4DMyl , N4DMzl , N4Fxl , & + N4Fyl , N4Fzl , N4Mxl , N4Myl , N4Mzl , & + N4PFxl , N4PFyl , N4PFzl , N4PMxl , N4PMyl , & + N4PMzl , N4RAXl , N4RAYl , N4RAZl , N4RDxr , & + N4RDyr , N4RDzr , N4RVXg , N4RVYg , N4RVZg , & + N4TAXl , N4TAYl , N4TAZl , N4TDxr , N4TDyr , & + N4TDzr , N4TVXg , N4TVYg , N4TVZg , N5DFxl , & + N5DFyl , N5DFzl , N5DMxl , N5DMyl , N5DMzl , & + N5Fxl , N5Fyl , N5Fzl , N5Mxl , N5Myl , & + N5Mzl , N5PFxl , N5PFyl , N5PFzl , N5PMxl , & + N5PMyl , N5PMzl , N5RAXl , N5RAYl , N5RAZl , & + N5RDxr , N5RDyr , N5RDzr , N5RVXg , N5RVYg , & + N5RVZg , N5TAXl , N5TAYl , N5TAZl , N5TDxr , & + N5TDyr , N5TDzr , N5TVXg , N5TVYg , N5TVZg , & + N6DFxl , N6DFyl , N6DFzl , N6DMxl , N6DMyl , & + N6DMzl , N6Fxl , N6Fyl , N6Fzl , N6Mxl , & + N6Myl , N6Mzl , N6PFxl , N6PFyl , N6PFzl , & + N6PMxl , N6PMyl , N6PMzl , N6RAXl , N6RAYl , & + N6RAZl , N6RDxr , N6RDyr , N6RDzr , N6RVXg , & + N6RVYg , N6RVZg , N6TAXl , N6TAYl , N6TAZl , & + N6TDxr , N6TDyr , N6TDzr , N6TVXg , N6TVYg , & + N6TVZg , N7DFxl , N7DFyl , N7DFzl , N7DMxl , & + N7DMyl , N7DMzl , N7Fxl , N7Fyl , N7Fzl , & + N7Mxl , N7Myl , N7Mzl , N7PFxl , N7PFyl , & + N7PFzl , N7PMxl , N7PMyl , N7PMzl , N7RAXl , & + N7RAYl , N7RAZl , N7RDxr , N7RDyr , N7RDzr , & + N7RVXg , N7RVYg , N7RVZg , N7TAXl , N7TAYl , & + N7TAZl , N7TDxr , N7TDyr , N7TDzr , N7TVXg , & + N7TVYg , N7TVZg , N8DFxl , N8DFyl , N8DFzl , & + N8DMxl , N8DMyl , N8DMzl , N8Fxl , N8Fyl , & + N8Fzl , N8Mxl , N8Myl , N8Mzl , N8PFxl , & + N8PFyl , N8PFzl , N8PMxl , N8PMyl , N8PMzl , & + N8RAXl , N8RAYl , N8RAZl , N8RDxr , N8RDyr , & + N8RDzr , N8RVXg , N8RVYg , N8RVZg , N8TAXl , & + N8TAYl , N8TAZl , N8TDxr , N8TDyr , N8TDzr , & + N8TVXg , N8TVYg , N8TVZg , N9DFxl , N9DFyl , & + N9DFzl , N9DMxl , N9DMyl , N9DMzl , N9Fxl , & + N9Fyl , N9Fzl , N9Mxl , N9Myl , N9Mzl , & + N9PFxl , N9PFyl , N9PFzl , N9PMxl , N9PMyl , & + N9PMzl , N9RAXl , N9RAYl , N9RAZl , N9RDxr , & + N9RDyr , N9RDzr , N9RVXg , N9RVYg , N9RVZg , & + N9TAXl , N9TAYl , N9TAZl , N9TDxr , N9TDyr , & + N9TDzr , N9TVXg , N9TVYg , N9TVZg , PAccAct , & + PAngAct , PAngInp , PRatAct , RootAppliedFxg , RootAppliedFxr , & + RootAppliedFyg , RootAppliedFyr , RootAppliedFzg , RootAppliedFzr , RootAppliedMxg , & + RootAppliedMxr , RootAppliedMyg , RootAppliedMyr , RootAppliedMzg , RootAppliedMzr , & + RootFxr , RootFyr , RootFzr , RootMxr , RootMyr , & + RootMzr , TipRAXl , TipRAYl , TipRAZl , TipRDxr , & + TipRDyr , TipRDzr , TipRVXg , TipRVYg , TipRVZg , & + TipTAXl , TipTAYl , TipTAZl , TipTDxr , TipTDyr , & + TipTDzr , TipTVXg , TipTVYg , TipTVZg /) + CHARACTER(ChanLen), PARAMETER :: ParamUnitsAry(364) = (/ & ! This lists the units corresponding to the allowed parameters + "(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ", & + "(N-m/m) ","(N) ","(N) ","(N) ","(N-m) ", & + "(N-m) ","(N-m) ","(N) ","(N) ","(N) ", & + "(N-m) ","(N-m) ","(N-m) ","(deg/s^2)","(deg/s^2)", & + "(deg/s^2)","(-) ","(-) ","(-) ","(deg/s) ", & + "(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ", & + "(m) ","(m) ","(m) ","(m/s) ","(m/s) ", & + "(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ", & + "(N-m/m) ","(N-m/m) ","(N) ","(N) ","(N) ", & + "(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ", & + "(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2)", & + "(deg/s^2)","(deg/s^2)","(-) ","(-) ","(-) ", & + "(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ", & + "(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ", & + "(m/s) ","(m/s) ","(N/m) ","(N/m) ","(N/m) ", & + "(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ","(N) ", & + "(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ", & + "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & + "(deg/s^2)","(deg/s^2)","(deg/s^2)","(-) ","(-) ", & + "(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ", & + "(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ", & + "(m/s) ","(m/s) ","(m/s) ","(N/m) ","(N/m) ", & + "(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ", & + "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & + "(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & + "(N-m) ","(deg/s^2)","(deg/s^2)","(deg/s^2)","(-) ", & + "(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & + "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ", & + "(m) ","(m/s) ","(m/s) ","(m/s) ","(N/m) ", & + "(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ", & + "(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & + "(N-m) ","(N) ","(N) ","(N) ","(N-m) ", & + "(N-m) ","(N-m) ","(deg/s^2)","(deg/s^2)","(deg/s^2)", & + "(-) ","(-) ","(-) ","(deg/s) ","(deg/s) ", & + "(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ", & + "(m) ","(m) ","(m/s) ","(m/s) ","(m/s) ", & + "(N/m) ","(N/m) ","(N/m) ","(N-m/m) ","(N-m/m) ", & + "(N-m/m) ","(N) ","(N) ","(N) ","(N-m) ", & + "(N-m) ","(N-m) ","(N) ","(N) ","(N) ", & + "(N-m) ","(N-m) ","(N-m) ","(deg/s^2)","(deg/s^2)", & + "(deg/s^2)","(-) ","(-) ","(-) ","(deg/s) ", & + "(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ","(m/s^2) ", & + "(m) ","(m) ","(m) ","(m/s) ","(m/s) ", & + "(m/s) ","(N/m) ","(N/m) ","(N/m) ","(N-m/m) ", & + "(N-m/m) ","(N-m/m) ","(N) ","(N) ","(N) ", & + "(N-m) ","(N-m) ","(N-m) ","(N) ","(N) ", & + "(N) ","(N-m) ","(N-m) ","(N-m) ","(deg/s^2)", & + "(deg/s^2)","(deg/s^2)","(-) ","(-) ","(-) ", & + "(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ","(m/s^2) ", & + "(m/s^2) ","(m) ","(m) ","(m) ","(m/s) ", & + "(m/s) ","(m/s) ","(N/m) ","(N/m) ","(N/m) ", & + "(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ","(N) ", & + "(N) ","(N-m) ","(N-m) ","(N-m) ","(N) ", & + "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & + "(deg/s^2)","(deg/s^2)","(deg/s^2)","(-) ","(-) ", & + "(-) ","(deg/s) ","(deg/s) ","(deg/s) ","(m/s^2) ", & + "(m/s^2) ","(m/s^2) ","(m) ","(m) ","(m) ", & + "(m/s) ","(m/s) ","(m/s) ","(N/m) ","(N/m) ", & + "(N/m) ","(N-m/m) ","(N-m/m) ","(N-m/m) ","(N) ", & + "(N) ","(N) ","(N-m) ","(N-m) ","(N-m) ", & + "(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & + "(N-m) ","(deg/s^2)","(deg/s^2)","(deg/s^2)","(-) ", & + "(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & + "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ", & + "(m) ","(m/s) ","(m/s) ","(m/s) ","(deg/s^2)", & + "(deg) ","(deg) ","(deg/s) ","(N) ","(N) ", & + "(N) ","(N) ","(N) ","(N) ","(N-m) ", & + "(N-m) ","(N-m) ","(N-m) ","(N-m) ","(N-m) ", & + "(N) ","(N) ","(N) ","(N-m) ","(N-m) ", & + "(N-m) ","(deg/s^2)","(deg/s^2)","(deg/s^2)","(-) ", & + "(-) ","(-) ","(deg/s) ","(deg/s) ","(deg/s) ", & + "(m/s^2) ","(m/s^2) ","(m/s^2) ","(m) ","(m) ", & + "(m) ","(m/s) ","(m/s) ","(m/s) "/) + + INTEGER, PARAMETER :: RootAppliedLd(12) = (/ & ! all applied load mapped to root outputs. For convenience in setting calculation flag + RootAppliedFxr, RootAppliedFyr, RootAppliedFzr, RootAppliedMxr, RootAppliedMyr, RootAppliedMzr, & + RootAppliedFxg, RootAppliedFyg, RootAppliedFzg, RootAppliedMxg, RootAppliedMyg, RootAppliedMzg /) ! Initialize values @@ -1357,7 +1444,7 @@ SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) ! ..... Developer must add checking for invalid inputs here: ..... DO I = p%NNodeOuts+1,9 ! Invalid nodes - + InvalidOutput( NFl( i,:) ) = .true. InvalidOutput( NMl( i,:) ) = .true. InvalidOutput( NTDr(i,:) ) = .true. @@ -1458,6 +1545,7 @@ SUBROUTINE SetOutParam(OutList, p, ErrStat, ErrMsg ) p%OutParam(I)%Units = ParamUnitsAry(Indx) ! it's a valid output if ( p%OutParam(I)%Indx >= N1DFxl .and. p%OutParam(I)%Indx <= N9DMzl ) p%OutInputs = .true. + if ( any(RootAppliedLd==p%OutParam(I)%Indx) ) p%CompAppliedLdAtRoot = .true. ! need to setup meshes END IF ELSE ! this channel isn't valid p%OutParam(I)%Indx = Time ! pick any valid channel (I just picked "Time" here because it's universal) diff --git a/modules/beamdyn/src/BeamDyn_Types.f90 b/modules/beamdyn/src/BeamDyn_Types.f90 index 81632c30ff..58e2895b43 100644 --- a/modules/beamdyn/src/BeamDyn_Types.f90 +++ b/modules/beamdyn/src/BeamDyn_Types.f90 @@ -237,6 +237,7 @@ MODULE BeamDyn_Types LOGICAL :: RotStates = .false. !< Orient states in rotating frame during linearization? (flag) [-] LOGICAL :: RelStates = .false. !< Define states relative to root motion during linearization? (flag) [-] LOGICAL :: CompAeroMaps = .FALSE. !< flag to determine if BeamDyn is computing aero maps (true) or running a normal simulation (false) [-] + LOGICAL :: CompAppliedLdAtRoot = .FALSE. !< flag to determine if BeamDyn should compute the applied loads at root [-] END TYPE BD_ParameterType ! ======================= ! ========= BD_InputType ======= @@ -295,8 +296,11 @@ MODULE BeamDyn_Types TYPE, PUBLIC :: BD_MiscVarType TYPE(MeshType) :: u_DistrLoad_at_y !< input loads at output node locations [-] TYPE(MeshType) :: y_BldMotion_at_u !< output motions at input node locations (displacements necessary for mapping loads) [-] + TYPE(MeshType) :: LoadsAtRoot !< Applied loads mapped to root [-] TYPE(MeshMapType) :: Map_u_DistrLoad_to_y !< mapping of input loads to output node locations [-] TYPE(MeshMapType) :: Map_y_BldMotion_to_u !< mapping of output motions to input node locations (for load transfer) [-] + TYPE(MeshMapType) :: Map_u_DistrLoad_to_R !< mapping of input loads to root location [-] + TYPE(MeshMapType) :: Map_u_PtLoad_to_R !< mapping of input loads to root location [-] INTEGER(IntKi) :: Un_Sum = 0_IntKi !< unit number of summary file [-] TYPE(EqMotionQP) :: qp !< Quadrature point calculation info [-] REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: lin_A !< A (dXdx) matrix used in linearization (before RotState is applied) [-] @@ -1685,6 +1689,7 @@ subroutine BD_CopyParam(SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg) DstParamData%RotStates = SrcParamData%RotStates DstParamData%RelStates = SrcParamData%RelStates DstParamData%CompAeroMaps = SrcParamData%CompAeroMaps + DstParamData%CompAppliedLdAtRoot = SrcParamData%CompAppliedLdAtRoot end subroutine subroutine BD_DestroyParam(ParamData, ErrStat, ErrMsg) @@ -1899,6 +1904,7 @@ subroutine BD_PackParam(RF, Indata) call RegPack(RF, InData%RotStates) call RegPack(RF, InData%RelStates) call RegPack(RF, InData%CompAeroMaps) + call RegPack(RF, InData%CompAppliedLdAtRoot) if (RegCheckErr(RF, RoutineName)) return end subroutine @@ -2013,6 +2019,7 @@ subroutine BD_UnPackParam(RF, OutData) call RegUnpack(RF, OutData%RotStates); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%RelStates); if (RegCheckErr(RF, RoutineName)) return call RegUnpack(RF, OutData%CompAeroMaps); if (RegCheckErr(RF, RoutineName)) return + call RegUnpack(RF, OutData%CompAppliedLdAtRoot); if (RegCheckErr(RF, RoutineName)) return end subroutine subroutine BD_CopyInput(SrcInputData, DstInputData, CtrlCode, ErrStat, ErrMsg) @@ -2747,12 +2754,21 @@ subroutine BD_CopyMisc(SrcMiscData, DstMiscData, CtrlCode, ErrStat, ErrMsg) call MeshCopy(SrcMiscData%y_BldMotion_at_u, DstMiscData%y_BldMotion_at_u, CtrlCode, ErrStat2, ErrMsg2 ) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return + call MeshCopy(SrcMiscData%LoadsAtRoot, DstMiscData%LoadsAtRoot, CtrlCode, ErrStat2, ErrMsg2 ) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + if (ErrStat >= AbortErrLev) return call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_u_DistrLoad_to_y, DstMiscData%Map_u_DistrLoad_to_y, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_y_BldMotion_to_u, DstMiscData%Map_y_BldMotion_to_u, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return + call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_u_DistrLoad_to_R, DstMiscData%Map_u_DistrLoad_to_R, CtrlCode, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + if (ErrStat >= AbortErrLev) return + call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_u_PtLoad_to_R, DstMiscData%Map_u_PtLoad_to_R, CtrlCode, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + if (ErrStat >= AbortErrLev) return DstMiscData%Un_Sum = SrcMiscData%Un_Sum call BD_CopyEqMotionQP(SrcMiscData%qp, DstMiscData%qp, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) @@ -3138,10 +3154,16 @@ subroutine BD_DestroyMisc(MiscData, ErrStat, ErrMsg) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call MeshDestroy( MiscData%y_BldMotion_at_u, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + call MeshDestroy( MiscData%LoadsAtRoot, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call NWTC_Library_DestroyMeshMapType(MiscData%Map_u_DistrLoad_to_y, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call NWTC_Library_DestroyMeshMapType(MiscData%Map_y_BldMotion_to_u, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + call NWTC_Library_DestroyMeshMapType(MiscData%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + call NWTC_Library_DestroyMeshMapType(MiscData%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call BD_DestroyEqMotionQP(MiscData%qp, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (allocated(MiscData%lin_A)) then @@ -3247,8 +3269,11 @@ subroutine BD_PackMisc(RF, Indata) if (RF%ErrStat >= AbortErrLev) return call MeshPack(RF, InData%u_DistrLoad_at_y) call MeshPack(RF, InData%y_BldMotion_at_u) + call MeshPack(RF, InData%LoadsAtRoot) call NWTC_Library_PackMeshMapType(RF, InData%Map_u_DistrLoad_to_y) call NWTC_Library_PackMeshMapType(RF, InData%Map_y_BldMotion_to_u) + call NWTC_Library_PackMeshMapType(RF, InData%Map_u_DistrLoad_to_R) + call NWTC_Library_PackMeshMapType(RF, InData%Map_u_PtLoad_to_R) call RegPack(RF, InData%Un_Sum) call BD_PackEqMotionQP(RF, InData%qp) call RegPackAlloc(RF, InData%lin_A) @@ -3296,8 +3321,11 @@ subroutine BD_UnPackMisc(RF, OutData) if (RF%ErrStat /= ErrID_None) return call MeshUnpack(RF, OutData%u_DistrLoad_at_y) ! u_DistrLoad_at_y call MeshUnpack(RF, OutData%y_BldMotion_at_u) ! y_BldMotion_at_u + call MeshUnpack(RF, OutData%LoadsAtRoot) ! LoadsAtRoot call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_DistrLoad_to_y) ! Map_u_DistrLoad_to_y call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_y_BldMotion_to_u) ! Map_y_BldMotion_to_u + call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_DistrLoad_to_R) ! Map_u_DistrLoad_to_R + call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_PtLoad_to_R) ! Map_u_PtLoad_to_R call RegUnpack(RF, OutData%Un_Sum); if (RegCheckErr(RF, RoutineName)) return call BD_UnpackEqMotionQP(RF, OutData%qp) ! qp call RegUnpackAlloc(RF, OutData%lin_A); if (RegCheckErr(RF, RoutineName)) return diff --git a/modules/beamdyn/src/Registry_BeamDyn.txt b/modules/beamdyn/src/Registry_BeamDyn.txt index 448cd81abe..bd90a2a168 100644 --- a/modules/beamdyn/src/Registry_BeamDyn.txt +++ b/modules/beamdyn/src/Registry_BeamDyn.txt @@ -250,6 +250,7 @@ typedef ^ ParameterType Integer Jac_nx - typedef ^ ParameterType logical RotStates - - - "Orient states in rotating frame during linearization? (flag)" - typedef ^ ParameterType Logical RelStates - - - "Define states relative to root motion during linearization? (flag)" - typedef ^ ParameterType LOGICAL CompAeroMaps - .FALSE. - "flag to determine if BeamDyn is computing aero maps (true) or running a normal simulation (false)" - +typedef ^ ParameterType LOGICAL CompAppliedLdAtRoot - .FALSE. - "flag to determine if BeamDyn should compute the applied loads at root" - # ..... Inputs @@ -330,8 +331,11 @@ typedef ^ EqMotionQP ^ Yd :::: - - "Dissipative # e.g. indices for searching in an array, large arrays that are local variables in any routine called multiple times, etc. typedef ^ MiscVarType MeshType u_DistrLoad_at_y - - - "input loads at output node locations" - typedef ^ MiscVarType MeshType y_BldMotion_at_u - - - "output motions at input node locations (displacements necessary for mapping loads)" - +typedef ^ MiscVarType MeshType LoadsAtRoot - - - "Applied loads mapped to root" - typedef ^ MiscVarType MeshMapType Map_u_DistrLoad_to_y - - - "mapping of input loads to output node locations" - typedef ^ MiscVarType MeshMapType Map_y_BldMotion_to_u - - - "mapping of output motions to input node locations (for load transfer)" - +typedef ^ MiscVarType MeshMapType Map_u_DistrLoad_to_R - - - "mapping of input loads to root location" - +typedef ^ MiscVarType MeshMapType Map_u_PtLoad_to_R - - - "mapping of input loads to root location" - typedef ^ MiscVarType IntKi Un_Sum - - - "unit number of summary file" - typedef ^ MiscVarType EqMotionQP qp - - - "Quadrature point calculation info" - typedef ^ MiscVarType R8Ki lin_A {:}{:} - - "A (dXdx) matrix used in linearization (before RotState is applied)" - From d8efcb4a5978fb285a646da7299a90aeb8743433 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Thu, 8 May 2025 17:08:00 -0600 Subject: [PATCH 32/63] BD: add calculations for mapping loads to root outputs --- modules/beamdyn/src/BeamDyn.f90 | 20 ++++++++++++++++++++ modules/beamdyn/src/BeamDyn_IO.f90 | 29 +++++++++++++++++++++++++++++ 2 files changed, 49 insertions(+) diff --git a/modules/beamdyn/src/BeamDyn.f90 b/modules/beamdyn/src/BeamDyn.f90 index 86d3382a47..b65fb0d636 100644 --- a/modules/beamdyn/src/BeamDyn.f90 +++ b/modules/beamdyn/src/BeamDyn.f90 @@ -1746,6 +1746,26 @@ subroutine Init_MiscVars( p, u, y, m, ErrStat, ErrMsg ) CALL BD_CopyInput(u, m%u2, MESH_NEWCOPY, ErrStat2, ErrMsg2) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + ! compute mapping of all applied loads to the root location + if (p%CompAppliedLdAtRoot) then + ! create point mesh at root (cousin of rootmotion) + CALL MeshCopy( SrcMesh = u%RootMotion & + , DestMesh = m%LoadsAtRoot & + , CtrlCode = MESH_SIBLING & + , IOS = COMPONENT_OUTPUT & + , Force = .TRUE. & + , Moment = .TRUE. & + , ErrStat = ErrStat2 & + , ErrMess = ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + if (ErrStat>=AbortErrLev) RETURN + ! mapping of distributed loads to LoadsAtRoot + CALL MeshMapCreate( u%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + ! mapping of point loads to LoadsAtRoot + CALL MeshMapCreate( u%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + endif end subroutine Init_MiscVars !----------------------------------------------------------------------------------------------------------------------------------- diff --git a/modules/beamdyn/src/BeamDyn_IO.f90 b/modules/beamdyn/src/BeamDyn_IO.f90 index 4e4ccd0db5..05fd686715 100644 --- a/modules/beamdyn/src/BeamDyn_IO.f90 +++ b/modules/beamdyn/src/BeamDyn_IO.f90 @@ -2000,6 +2000,35 @@ SUBROUTINE Calc_WriteOutput( p, AllOuts, y, m, ErrStat, ErrMsg, CalcWriteOutput end if + ! compute mapping of all applied loads to the root location + if (p%CompAppliedLdAtRoot) then +!FIXME: check if should be using u2 or u + ! mapping of distributed loads to LoadsAtRoot + call Transfer_Line2_to_Point( m%u2%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) + call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) +!FIXME: might need temp copy here to avoid clobbering all the forces with second transfer. + ! mapping of point loads to LoadsAtRoot + call Transfer_Point_to_Point( m%u2%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) + call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + + ! Global coords + AllOuts( RootAppliedFxg ) = m%LoadsAtRoot%Force(1,1) + AllOuts( RootAppliedFyg ) = m%LoadsAtRoot%Force(2,1) + AllOuts( RootAppliedFzg ) = m%LoadsAtRoot%Force(3,1) + AllOuts( RootAppliedMxg ) = m%LoadsAtRoot%Moment(1,1) + AllOuts( RootAppliedMyg ) = m%LoadsAtRoot%Moment(2,1) + AllOuts( RootAppliedMzg ) = m%LoadsAtRoot%Moment(3,1) + + ! Root coords + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),m%LoadsAtRoot%Force(:,1)) + AllOuts( RootAppliedFxr ) = temp_vec(1) + AllOuts( RootAppliedFyr ) = temp_vec(2) + AllOuts( RootAppliedFzr ) = temp_vec(3) + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),m%LoadsAtRoot%Moment(:,1)) + AllOuts( RootAppliedMxr ) = temp_vec(1) + AllOuts( RootAppliedMyr ) = temp_vec(2) + AllOuts( RootAppliedMzr ) = temp_vec(3) + endif end if From d3093168f046bff0cfa148e719b395936a269eb2 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Fri, 9 May 2025 07:12:15 -0600 Subject: [PATCH 33/63] BD: LoadsAtRoot - sum forces/moments from distr and point --- modules/beamdyn/src/BeamDyn.f90 | 4 ++++ modules/beamdyn/src/BeamDyn_IO.f90 | 30 ++++++++++++++++++++---------- 2 files changed, 24 insertions(+), 10 deletions(-) diff --git a/modules/beamdyn/src/BeamDyn.f90 b/modules/beamdyn/src/BeamDyn.f90 index b65fb0d636..069485b8f0 100644 --- a/modules/beamdyn/src/BeamDyn.f90 +++ b/modules/beamdyn/src/BeamDyn.f90 @@ -1759,12 +1759,16 @@ subroutine Init_MiscVars( p, u, y, m, ErrStat, ErrMsg ) , ErrMess = ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) if (ErrStat>=AbortErrLev) RETURN + ! mapping of distributed loads to LoadsAtRoot CALL MeshMapCreate( u%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + ! mapping of point loads to LoadsAtRoot CALL MeshMapCreate( u%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + + m%LoadsAtRoot%remapFlag = .false. endif end subroutine Init_MiscVars diff --git a/modules/beamdyn/src/BeamDyn_IO.f90 b/modules/beamdyn/src/BeamDyn_IO.f90 index 05fd686715..560b9a3730 100644 --- a/modules/beamdyn/src/BeamDyn_IO.f90 +++ b/modules/beamdyn/src/BeamDyn_IO.f90 @@ -1742,6 +1742,8 @@ SUBROUTINE Calc_WriteOutput( p, AllOuts, y, m, ErrStat, ErrMsg, CalcWriteOutput INTEGER(IntKi) :: j,beta,j_BldMotion REAL(BDKi) :: temp_vec(3) REAL(BDKi) :: temp_vec2(3) + REAL(ReKi) :: temp_frc(3) + REAL(ReKi) :: temp_mom(3) REAL(BDKi) :: temp33(3,3) REAL(BDKi) :: temp33_2(3,3) @@ -2002,29 +2004,37 @@ SUBROUTINE Calc_WriteOutput( p, AllOuts, y, m, ErrStat, ErrMsg, CalcWriteOutput ! compute mapping of all applied loads to the root location if (p%CompAppliedLdAtRoot) then -!FIXME: check if should be using u2 or u + ! mapping of distributed loads to LoadsAtRoot call Transfer_Line2_to_Point( m%u2%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) -!FIXME: might need temp copy here to avoid clobbering all the forces with second transfer. + + ! a second transfer will zero out the forces, and moments, so store them elsewhere + temp_frc = m%LoadsAtRoot%Force(:,1) + temp_mom = m%LoadsAtRoot%Moment(:,1) + ! mapping of point loads to LoadsAtRoot call Transfer_Point_to_Point( m%u2%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + ! add the distributed loads + temp_frc = temp_frc + m%LoadsAtRoot%Force(:,1) + temp_mom = temp_mom + m%LoadsAtRoot%Moment(:,1) + ! Global coords - AllOuts( RootAppliedFxg ) = m%LoadsAtRoot%Force(1,1) - AllOuts( RootAppliedFyg ) = m%LoadsAtRoot%Force(2,1) - AllOuts( RootAppliedFzg ) = m%LoadsAtRoot%Force(3,1) - AllOuts( RootAppliedMxg ) = m%LoadsAtRoot%Moment(1,1) - AllOuts( RootAppliedMyg ) = m%LoadsAtRoot%Moment(2,1) - AllOuts( RootAppliedMzg ) = m%LoadsAtRoot%Moment(3,1) + AllOuts( RootAppliedFxg ) = temp_frc(1) + AllOuts( RootAppliedFyg ) = temp_frc(2) + AllOuts( RootAppliedFzg ) = temp_frc(3) + AllOuts( RootAppliedMxg ) = temp_mom(1) + AllOuts( RootAppliedMyg ) = temp_mom(2) + AllOuts( RootAppliedMzg ) = temp_mom(3) ! Root coords - temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),m%LoadsAtRoot%Force(:,1)) + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),temp_frc) AllOuts( RootAppliedFxr ) = temp_vec(1) AllOuts( RootAppliedFyr ) = temp_vec(2) AllOuts( RootAppliedFzr ) = temp_vec(3) - temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),m%LoadsAtRoot%Moment(:,1)) + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),temp_mom) AllOuts( RootAppliedMxr ) = temp_vec(1) AllOuts( RootAppliedMyr ) = temp_vec(2) AllOuts( RootAppliedMzr ) = temp_vec(3) From 185a092030d48e6dbeb73c49e664079a1d2e7354 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Fri, 9 May 2025 07:41:56 -0600 Subject: [PATCH 34/63] BD: Loads at root -- change mesh from sibling to cousin --- modules/beamdyn/src/BeamDyn.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/beamdyn/src/BeamDyn.f90 b/modules/beamdyn/src/BeamDyn.f90 index 069485b8f0..4361954328 100644 --- a/modules/beamdyn/src/BeamDyn.f90 +++ b/modules/beamdyn/src/BeamDyn.f90 @@ -1751,7 +1751,7 @@ subroutine Init_MiscVars( p, u, y, m, ErrStat, ErrMsg ) ! create point mesh at root (cousin of rootmotion) CALL MeshCopy( SrcMesh = u%RootMotion & , DestMesh = m%LoadsAtRoot & - , CtrlCode = MESH_SIBLING & + , CtrlCode = MESH_COUSIN & , IOS = COMPONENT_OUTPUT & , Force = .TRUE. & , Moment = .TRUE. & From 7821a49de52f86f662d25a28a4bddb57ba902d50 Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Fri, 9 May 2025 13:04:54 -0600 Subject: [PATCH 35/63] Add a checkError in openfast cpp --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index b064c29bee..ee229b3135 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -668,6 +668,7 @@ void fast::OpenFAST::init() { &sc->op_to_FAST[iTurb], &ErrStat, ErrMsg); + checkError(ErrStat, ErrMsg); turbineData[iTurb].inflowType = 0; } From 9f4621498522410b4ec66bd41c2f5bb10b277245 Mon Sep 17 00:00:00 2001 From: ptrbortolotti Date: Tue, 13 May 2025 15:20:27 -0600 Subject: [PATCH 36/63] compute Zbottom from GridHeight, not RotorDiameter --- modules/turbsim/src/TSsubs.f90 | 4 ++-- modules/turbsim/src/TurbSim_Types.f90 | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/modules/turbsim/src/TSsubs.f90 b/modules/turbsim/src/TSsubs.f90 index 173fd53f62..429078c1ea 100644 --- a/modules/turbsim/src/TSsubs.f90 +++ b/modules/turbsim/src/TSsubs.f90 @@ -1347,8 +1347,8 @@ SUBROUTINE CreateGrid( p_grid, p_usr, UHub, AddTower, ErrStat, ErrMsg ) p_grid%GridRes_Y = p_grid%GridWidth / REAL( p_grid%NumGrid_Y - 1, ReKi ) p_grid%GridRes_Z = p_grid%GridHeight / REAL( p_grid%NumGrid_Z - 1, ReKi ) - p_grid%Zbottom = p_grid%HubHt + 0.5*p_grid%RotorDiameter ! height of the highest grid points - p_grid%Zbottom = p_grid%Zbottom - p_grid%GridRes_Z * REAL(p_grid%NumGrid_Z - 1, ReKi) ! height of the lowest grid points + p_grid%Ztop = p_grid%HubHt + 0.5*p_grid%GridHeight ! height of the highest grid points + p_grid%Zbottom = p_grid%Ztop - p_grid%GridRes_Z * REAL(p_grid%NumGrid_Z - 1, ReKi) ! height of the lowest grid points IF ( p_grid%Zbottom <= 0.0_ReKi ) THEN CALL SetErrStat(ErrID_Fatal,'The lowest grid point ('//TRIM(Num2LStr(p_grid%Zbottom))// ' m) must be above the ground. '//& diff --git a/modules/turbsim/src/TurbSim_Types.f90 b/modules/turbsim/src/TurbSim_Types.f90 index 07a7773018..0426c3f2d2 100644 --- a/modules/turbsim/src/TurbSim_Types.f90 +++ b/modules/turbsim/src/TurbSim_Types.f90 @@ -111,6 +111,7 @@ MODULE TurbSim_Types INTEGER(IntKi) :: NPoints ! Number of points being simulated. INTEGER(IntKi) :: NPacked ! Number of entries stored in the packed version of the symmetric matrix of size NPoints by NPoints + REAL(ReKi) :: Ztop ! The height of the highest point on the grid (before tower points are added) REAL(ReKi) :: Zbottom ! The height of the lowest point on the grid (before tower points are added), equal to Z(1) REAL(ReKi) :: RotorDiameter ! The assumed diameter of the rotor From 31918a56667de66c3fdb7886ba95b18f0fe8e6c6 Mon Sep 17 00:00:00 2001 From: ptrbortolotti Date: Tue, 13 May 2025 15:34:30 -0600 Subject: [PATCH 37/63] Zbottom is simply HubHt - half GridHeight. skip Ztop --- modules/turbsim/src/TSsubs.f90 | 3 +-- modules/turbsim/src/TurbSim_Types.f90 | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/modules/turbsim/src/TSsubs.f90 b/modules/turbsim/src/TSsubs.f90 index 429078c1ea..db15ecc344 100644 --- a/modules/turbsim/src/TSsubs.f90 +++ b/modules/turbsim/src/TSsubs.f90 @@ -1347,8 +1347,7 @@ SUBROUTINE CreateGrid( p_grid, p_usr, UHub, AddTower, ErrStat, ErrMsg ) p_grid%GridRes_Y = p_grid%GridWidth / REAL( p_grid%NumGrid_Y - 1, ReKi ) p_grid%GridRes_Z = p_grid%GridHeight / REAL( p_grid%NumGrid_Z - 1, ReKi ) - p_grid%Ztop = p_grid%HubHt + 0.5*p_grid%GridHeight ! height of the highest grid points - p_grid%Zbottom = p_grid%Ztop - p_grid%GridRes_Z * REAL(p_grid%NumGrid_Z - 1, ReKi) ! height of the lowest grid points + p_grid%Zbottom = p_grid%HubHt - 0.5*p_grid%GridHeight ! height of the lowest grid points IF ( p_grid%Zbottom <= 0.0_ReKi ) THEN CALL SetErrStat(ErrID_Fatal,'The lowest grid point ('//TRIM(Num2LStr(p_grid%Zbottom))// ' m) must be above the ground. '//& diff --git a/modules/turbsim/src/TurbSim_Types.f90 b/modules/turbsim/src/TurbSim_Types.f90 index 0426c3f2d2..07a7773018 100644 --- a/modules/turbsim/src/TurbSim_Types.f90 +++ b/modules/turbsim/src/TurbSim_Types.f90 @@ -111,7 +111,6 @@ MODULE TurbSim_Types INTEGER(IntKi) :: NPoints ! Number of points being simulated. INTEGER(IntKi) :: NPacked ! Number of entries stored in the packed version of the symmetric matrix of size NPoints by NPoints - REAL(ReKi) :: Ztop ! The height of the highest point on the grid (before tower points are added) REAL(ReKi) :: Zbottom ! The height of the lowest point on the grid (before tower points are added), equal to Z(1) REAL(ReKi) :: RotorDiameter ! The assumed diameter of the rotor From cfeb2d5148172badae5a2c223713ca4105951472 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 13 May 2025 18:14:27 -0600 Subject: [PATCH 38/63] BD: aero loads at root - remove point load mapping Only using distributed loads (StC maps to distributed loads if MESH_QP right now. Point loads in the driver map to the FE nodes) --- modules/beamdyn/src/BeamDyn.f90 | 11 ++--- modules/beamdyn/src/BeamDyn_IO.f90 | 54 +++++++++++------------- modules/beamdyn/src/BeamDyn_Types.f90 | 8 ---- modules/beamdyn/src/Registry_BeamDyn.txt | 1 - 4 files changed, 29 insertions(+), 45 deletions(-) diff --git a/modules/beamdyn/src/BeamDyn.f90 b/modules/beamdyn/src/BeamDyn.f90 index 4361954328..8a4dd5411e 100644 --- a/modules/beamdyn/src/BeamDyn.f90 +++ b/modules/beamdyn/src/BeamDyn.f90 @@ -1746,8 +1746,9 @@ subroutine Init_MiscVars( p, u, y, m, ErrStat, ErrMsg ) CALL BD_CopyInput(u, m%u2, MESH_NEWCOPY, ErrStat2, ErrMsg2) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - ! compute mapping of all applied loads to the root location - if (p%CompAppliedLdAtRoot) then + ! compute mapping of applied distributed loads to the root location + ! NOTE: PtLoads are not handled at present. See comments in BeamDyn_IO.f90 for changes required. + if (p%CompAppliedLdAtRoot .and. p%BldMotionNodeLoc == BD_MESH_QP) then ! create point mesh at root (cousin of rootmotion) CALL MeshCopy( SrcMesh = u%RootMotion & , DestMesh = m%LoadsAtRoot & @@ -1763,12 +1764,8 @@ subroutine Init_MiscVars( p, u, y, m, ErrStat, ErrMsg ) ! mapping of distributed loads to LoadsAtRoot CALL MeshMapCreate( u%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - - ! mapping of point loads to LoadsAtRoot - CALL MeshMapCreate( u%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) - CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - m%LoadsAtRoot%remapFlag = .false. + endif end subroutine Init_MiscVars diff --git a/modules/beamdyn/src/BeamDyn_IO.f90 b/modules/beamdyn/src/BeamDyn_IO.f90 index 560b9a3730..5840b4b160 100644 --- a/modules/beamdyn/src/BeamDyn_IO.f90 +++ b/modules/beamdyn/src/BeamDyn_IO.f90 @@ -1742,8 +1742,6 @@ SUBROUTINE Calc_WriteOutput( p, AllOuts, y, m, ErrStat, ErrMsg, CalcWriteOutput INTEGER(IntKi) :: j,beta,j_BldMotion REAL(BDKi) :: temp_vec(3) REAL(BDKi) :: temp_vec2(3) - REAL(ReKi) :: temp_frc(3) - REAL(ReKi) :: temp_mom(3) REAL(BDKi) :: temp33(3,3) REAL(BDKi) :: temp33_2(3,3) @@ -2001,48 +1999,46 @@ SUBROUTINE Calc_WriteOutput( p, AllOuts, y, m, ErrStat, ErrMsg, CalcWriteOutput end do ! nodes end if + end if - ! compute mapping of all applied loads to the root location - if (p%CompAppliedLdAtRoot) then - - ! mapping of distributed loads to LoadsAtRoot - call Transfer_Line2_to_Point( m%u2%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2 ) - call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + ! compute mapping of applied distributed loads to the root location + ! FIXME: currently not mapping the PointLoads over since there is no motion mesh associated with the PointLoad + ! To get the PointLoads mapped, the following is necessary + ! 1. create a y%BldMotionFE mesh at the finite element points (this would be very useful someday) + ! - take position info directly from uuu and state information etc. + ! - Add output channels for this for comparison + ! 2. make u%PointLoad a sibling of y%BldMotionFE + ! 3. Setup m%Map_u_PtLoad_to_R + ! 4. map loads and do summation here (remember Transfer zero's out forces/moments, so add temp arrays to hold those) + if (p%CompAppliedLdAtRoot .and. p%BldMotionNodeLoc == BD_MESH_QP) then - ! a second transfer will zero out the forces, and moments, so store them elsewhere - temp_frc = m%LoadsAtRoot%Force(:,1) - temp_mom = m%LoadsAtRoot%Moment(:,1) + ! shorthand to simplify life + associate(RF => m%LoadsAtRoot%Force, RM => m%LoadsAtRoot%Moment) - ! mapping of point loads to LoadsAtRoot - call Transfer_Point_to_Point( m%u2%PointLoad, m%LoadsAtRoot, m%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2 ) + ! mapping of distributed loads to LoadsAtRoot + call Transfer_Line2_to_Point( m%u2%DistrLoad, m%LoadsAtRoot, m%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2, y%BldMotion, m%u2%RootMotion ) call SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - ! add the distributed loads - temp_frc = temp_frc + m%LoadsAtRoot%Force(:,1) - temp_mom = temp_mom + m%LoadsAtRoot%Moment(:,1) - ! Global coords - AllOuts( RootAppliedFxg ) = temp_frc(1) - AllOuts( RootAppliedFyg ) = temp_frc(2) - AllOuts( RootAppliedFzg ) = temp_frc(3) - AllOuts( RootAppliedMxg ) = temp_mom(1) - AllOuts( RootAppliedMyg ) = temp_mom(2) - AllOuts( RootAppliedMzg ) = temp_mom(3) + AllOuts( RootAppliedFxg ) = RF(1,1) + AllOuts( RootAppliedFyg ) = RF(2,1) + AllOuts( RootAppliedFzg ) = RF(3,1) + AllOuts( RootAppliedMxg ) = RM(1,1) + AllOuts( RootAppliedMyg ) = RM(2,1) + AllOuts( RootAppliedMzg ) = RM(3,1) ! Root coords - temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),temp_frc) + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),RF(:,1)) AllOuts( RootAppliedFxr ) = temp_vec(1) AllOuts( RootAppliedFyr ) = temp_vec(2) AllOuts( RootAppliedFzr ) = temp_vec(3) - temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),temp_mom) + temp_vec = MATMUL(m%u2%RootMotion%Orientation(:,:,1),RM(:,1)) AllOuts( RootAppliedMxr ) = temp_vec(1) AllOuts( RootAppliedMyr ) = temp_vec(2) AllOuts( RootAppliedMzr ) = temp_vec(3) - endif - - end if - + end associate + endif END SUBROUTINE Calc_WriteOutput diff --git a/modules/beamdyn/src/BeamDyn_Types.f90 b/modules/beamdyn/src/BeamDyn_Types.f90 index 58e2895b43..81b34982b8 100644 --- a/modules/beamdyn/src/BeamDyn_Types.f90 +++ b/modules/beamdyn/src/BeamDyn_Types.f90 @@ -300,7 +300,6 @@ MODULE BeamDyn_Types TYPE(MeshMapType) :: Map_u_DistrLoad_to_y !< mapping of input loads to output node locations [-] TYPE(MeshMapType) :: Map_y_BldMotion_to_u !< mapping of output motions to input node locations (for load transfer) [-] TYPE(MeshMapType) :: Map_u_DistrLoad_to_R !< mapping of input loads to root location [-] - TYPE(MeshMapType) :: Map_u_PtLoad_to_R !< mapping of input loads to root location [-] INTEGER(IntKi) :: Un_Sum = 0_IntKi !< unit number of summary file [-] TYPE(EqMotionQP) :: qp !< Quadrature point calculation info [-] REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: lin_A !< A (dXdx) matrix used in linearization (before RotState is applied) [-] @@ -2766,9 +2765,6 @@ subroutine BD_CopyMisc(SrcMiscData, DstMiscData, CtrlCode, ErrStat, ErrMsg) call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_u_DistrLoad_to_R, DstMiscData%Map_u_DistrLoad_to_R, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (ErrStat >= AbortErrLev) return - call NWTC_Library_CopyMeshMapType(SrcMiscData%Map_u_PtLoad_to_R, DstMiscData%Map_u_PtLoad_to_R, CtrlCode, ErrStat2, ErrMsg2) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - if (ErrStat >= AbortErrLev) return DstMiscData%Un_Sum = SrcMiscData%Un_Sum call BD_CopyEqMotionQP(SrcMiscData%qp, DstMiscData%qp, CtrlCode, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) @@ -3162,8 +3158,6 @@ subroutine BD_DestroyMisc(MiscData, ErrStat, ErrMsg) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call NWTC_Library_DestroyMeshMapType(MiscData%Map_u_DistrLoad_to_R, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - call NWTC_Library_DestroyMeshMapType(MiscData%Map_u_PtLoad_to_R, ErrStat2, ErrMsg2) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) call BD_DestroyEqMotionQP(MiscData%qp, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if (allocated(MiscData%lin_A)) then @@ -3273,7 +3267,6 @@ subroutine BD_PackMisc(RF, Indata) call NWTC_Library_PackMeshMapType(RF, InData%Map_u_DistrLoad_to_y) call NWTC_Library_PackMeshMapType(RF, InData%Map_y_BldMotion_to_u) call NWTC_Library_PackMeshMapType(RF, InData%Map_u_DistrLoad_to_R) - call NWTC_Library_PackMeshMapType(RF, InData%Map_u_PtLoad_to_R) call RegPack(RF, InData%Un_Sum) call BD_PackEqMotionQP(RF, InData%qp) call RegPackAlloc(RF, InData%lin_A) @@ -3325,7 +3318,6 @@ subroutine BD_UnPackMisc(RF, OutData) call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_DistrLoad_to_y) ! Map_u_DistrLoad_to_y call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_y_BldMotion_to_u) ! Map_y_BldMotion_to_u call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_DistrLoad_to_R) ! Map_u_DistrLoad_to_R - call NWTC_Library_UnpackMeshMapType(RF, OutData%Map_u_PtLoad_to_R) ! Map_u_PtLoad_to_R call RegUnpack(RF, OutData%Un_Sum); if (RegCheckErr(RF, RoutineName)) return call BD_UnpackEqMotionQP(RF, OutData%qp) ! qp call RegUnpackAlloc(RF, OutData%lin_A); if (RegCheckErr(RF, RoutineName)) return diff --git a/modules/beamdyn/src/Registry_BeamDyn.txt b/modules/beamdyn/src/Registry_BeamDyn.txt index bd90a2a168..1500bd2a20 100644 --- a/modules/beamdyn/src/Registry_BeamDyn.txt +++ b/modules/beamdyn/src/Registry_BeamDyn.txt @@ -335,7 +335,6 @@ typedef ^ MiscVarType MeshType LoadsAtRoot - - - "Applie typedef ^ MiscVarType MeshMapType Map_u_DistrLoad_to_y - - - "mapping of input loads to output node locations" - typedef ^ MiscVarType MeshMapType Map_y_BldMotion_to_u - - - "mapping of output motions to input node locations (for load transfer)" - typedef ^ MiscVarType MeshMapType Map_u_DistrLoad_to_R - - - "mapping of input loads to root location" - -typedef ^ MiscVarType MeshMapType Map_u_PtLoad_to_R - - - "mapping of input loads to root location" - typedef ^ MiscVarType IntKi Un_Sum - - - "unit number of summary file" - typedef ^ MiscVarType EqMotionQP qp - - - "Quadrature point calculation info" - typedef ^ MiscVarType R8Ki lin_A {:}{:} - - "A (dXdx) matrix used in linearization (before RotState is applied)" - From b13fa618c7df8a403b392c2e713981ce5ad2e104 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 13 May 2025 18:16:59 -0600 Subject: [PATCH 39/63] OF: correct description of BStC to beamdyn --- modules/openfast-library/src/FAST_Registry.txt | 2 +- modules/openfast-library/src/FAST_Types.f90 | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/openfast-library/src/FAST_Registry.txt b/modules/openfast-library/src/FAST_Registry.txt index 2cbaa53e41..95f2410ecb 100644 --- a/modules/openfast-library/src/FAST_Registry.txt +++ b/modules/openfast-library/src/FAST_Registry.txt @@ -720,7 +720,7 @@ typedef ^ FAST_ModuleMapType MeshMapType TStC_P_2_ED_P_T {:} - - "Map ServoDyn/T typedef ^ FAST_ModuleMapType MeshMapType ED_L_2_BStC_P_B {:}{:} - - "Map ElastoDyn blade line2 mesh to ServoDyn/BStC point mesh" typedef ^ FAST_ModuleMapType MeshMapType BStC_P_2_ED_P_B {:}{:} - - "Map ServoDyn/BStC point mesh to ElastoDyn point load mesh on the blade" typedef ^ FAST_ModuleMapType MeshMapType BD_L_2_BStC_P_B {:}{:} - - "Map BeamDyn blade line2 mesh to ServoDyn/BStC point mesh" -typedef ^ FAST_ModuleMapType MeshMapType BStC_P_2_BD_P_B {:}{:} - - "Map ServoDyn/BStC point mesh to BeamDyn point load mesh on the blade" +typedef ^ FAST_ModuleMapType MeshMapType BStC_P_2_BD_P_B {:}{:} - - "Map ServoDyn/BStC point mesh to BeamDyn distributed load mesh on the blade" # ED/SD <-> SrvD/StC -- Platform TMD typedef ^ FAST_ModuleMapType MeshMapType SStC_P_P_2_SubStructure {:} - - "Map ServoDyn/SStC platform point mesh load to SubDyn/ElastoDyn point load mesh" typedef ^ FAST_ModuleMapType MeshMapType SubStructure_2_SStC_P_P {:} - - "Map SubDyn y3mesh or ED platform mesh motion to ServoDyn/SStC point mesh" diff --git a/modules/openfast-library/src/FAST_Types.f90 b/modules/openfast-library/src/FAST_Types.f90 index 125d2a0643..858f538a4f 100644 --- a/modules/openfast-library/src/FAST_Types.f90 +++ b/modules/openfast-library/src/FAST_Types.f90 @@ -743,7 +743,7 @@ MODULE FAST_Types TYPE(MeshMapType) , DIMENSION(:,:), ALLOCATABLE :: ED_L_2_BStC_P_B !< Map ElastoDyn blade line2 mesh to ServoDyn/BStC point mesh [-] TYPE(MeshMapType) , DIMENSION(:,:), ALLOCATABLE :: BStC_P_2_ED_P_B !< Map ServoDyn/BStC point mesh to ElastoDyn point load mesh on the blade [-] TYPE(MeshMapType) , DIMENSION(:,:), ALLOCATABLE :: BD_L_2_BStC_P_B !< Map BeamDyn blade line2 mesh to ServoDyn/BStC point mesh [-] - TYPE(MeshMapType) , DIMENSION(:,:), ALLOCATABLE :: BStC_P_2_BD_P_B !< Map ServoDyn/BStC point mesh to BeamDyn point load mesh on the blade [-] + TYPE(MeshMapType) , DIMENSION(:,:), ALLOCATABLE :: BStC_P_2_BD_P_B !< Map ServoDyn/BStC point mesh to BeamDyn distributed load mesh on the blade [-] TYPE(MeshMapType) , DIMENSION(:), ALLOCATABLE :: SStC_P_P_2_SubStructure !< Map ServoDyn/SStC platform point mesh load to SubDyn/ElastoDyn point load mesh [-] TYPE(MeshMapType) , DIMENSION(:), ALLOCATABLE :: SubStructure_2_SStC_P_P !< Map SubDyn y3mesh or ED platform mesh motion to ServoDyn/SStC point mesh [-] TYPE(MeshMapType) :: ED_P_2_SrvD_P_P !< Map ElastoDyn/Simplified-ElastoDyn platform point mesh motion to ServoDyn point mesh -- for passing to controller [-] From e676fb5f7e9adb75d23555a433c30eb4ee8aa465 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Wed, 14 May 2025 10:28:12 -0600 Subject: [PATCH 40/63] TurbSim: if grid goes below ground, shift the bottom point --- modules/turbsim/src/TS_FileIO.f90 | 4 +++- modules/turbsim/src/TSsubs.f90 | 11 +++-------- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/modules/turbsim/src/TS_FileIO.f90 b/modules/turbsim/src/TS_FileIO.f90 index d4a5814137..c9afe84b09 100644 --- a/modules/turbsim/src/TS_FileIO.f90 +++ b/modules/turbsim/src/TS_FileIO.f90 @@ -4868,7 +4868,9 @@ SUBROUTINE GetDefaultRS( p, OtherSt_RandNum, TmpUstarHub, ErrStat, ErrMsg ) Z(2) = p%grid%HubHt + 0.5*p%grid%RotorDiameter ! top of the grid - Z(1) = Z(2) - p%grid%GridHeight ! bottom of the grid + Z(1) = MAX( Tolerance, Z(2) - p%grid%GridHeight ) ! bottom of the grid + Z(2) = Z(1) + p%grid%GridHeight ! re-calculate just in case Z1 is set to Tolerance + CALL getVelocityProfile(p, p%UHub, p%grid%HubHt, Z, V, ErrStat2, ErrMsg2) CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'GetDefaultRS') diff --git a/modules/turbsim/src/TSsubs.f90 b/modules/turbsim/src/TSsubs.f90 index db15ecc344..f869387b6e 100644 --- a/modules/turbsim/src/TSsubs.f90 +++ b/modules/turbsim/src/TSsubs.f90 @@ -1347,14 +1347,9 @@ SUBROUTINE CreateGrid( p_grid, p_usr, UHub, AddTower, ErrStat, ErrMsg ) p_grid%GridRes_Y = p_grid%GridWidth / REAL( p_grid%NumGrid_Y - 1, ReKi ) p_grid%GridRes_Z = p_grid%GridHeight / REAL( p_grid%NumGrid_Z - 1, ReKi ) - p_grid%Zbottom = p_grid%HubHt - 0.5*p_grid%GridHeight ! height of the lowest grid points - - IF ( p_grid%Zbottom <= 0.0_ReKi ) THEN - CALL SetErrStat(ErrID_Fatal,'The lowest grid point ('//TRIM(Num2LStr(p_grid%Zbottom))// ' m) must be above the ground. '//& - 'Adjust the appropriate values in the input file.',ErrStat,ErrMsg,RoutineName) - RETURN - ENDIF - + p_grid%Zbottom = p_grid%HubHt + 0.5*p_grid%RotorDiameter ! height of the highest grid points + p_grid%Zbottom = p_grid%Zbottom - p_grid%GridRes_Z * REAL(p_grid%NumGrid_Z - 1, ReKi) ! height of the lowest grid points + p_grid%Zbottom = MAX( Tolerance, p_grid%Zbottom) ! make sure it's above the ground ! (2) the tower points: IF ( AddTower ) THEN From fccd9c5c03a75b06b2c681fd9accf1007cca383e Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Thu, 1 May 2025 11:48:04 -0400 Subject: [PATCH 41/63] Fix restart parsing of file name --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index ee229b3135..8f3c0aeb67 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -94,8 +94,15 @@ void fast::OpenFAST::findRestartFile(int iTurbLoc) { check_nc_error(ierr, "nc_get_vara_double - getting latest time"); tStart = latest_time; - char tmpOutFileRoot[INTERFACE_STRING_LENGTH]; + char *tmpOutFileRoot; + size_t len; + ierr = nc_inq_attlen(ncid, NC_GLOBAL, "out_file_root", &len); + check_nc_error(ierr, "nc_inq_attlen - getting out_file_root length"); + + tmpOutFileRoot = (char*) malloc(len + 1); ierr = nc_get_att_text(ncid, NC_GLOBAL, "out_file_root", tmpOutFileRoot); + check_nc_error(ierr, "nc_get_att_text - getting out_file_root"); + tmpOutFileRoot[len] = '\0'; turbineData[iTurbLoc].outFileRoot.assign(tmpOutFileRoot); ierr = nc_get_att_double(ncid, NC_GLOBAL, "dt_fast", &dtFAST); From 8f7a97a189d46cd78ff856b770945463fcf29d4a Mon Sep 17 00:00:00 2001 From: Marc Henry de Frahan Date: Fri, 2 May 2025 09:37:01 -0600 Subject: [PATCH 42/63] Free tmpOutFileRoot char pointer in openfast cpp --- glue-codes/openfast-cpp/src/OpenFAST.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/glue-codes/openfast-cpp/src/OpenFAST.cpp b/glue-codes/openfast-cpp/src/OpenFAST.cpp index 8f3c0aeb67..a638ec545c 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.cpp +++ b/glue-codes/openfast-cpp/src/OpenFAST.cpp @@ -126,7 +126,7 @@ void fast::OpenFAST::findRestartFile(int iTurbLoc) { std::cout << "Restarting from time " << latest_time << " at time step " << tstep << " from file name " << turbineData[iTurbLoc].FASTRestartFileName << std::endl ; nc_close(ncid); - + free(tmpOutFileRoot); } void fast::OpenFAST::prepareRestartFile(int iTurbLoc) { From bcffabda06ba0dbf72b2aa6f6e143556c22a9104 Mon Sep 17 00:00:00 2001 From: omahs <73983677+omahs@users.noreply.github.com> Date: Fri, 16 May 2025 12:06:26 +0200 Subject: [PATCH 43/63] Fix typos --- docs/source/dev/index.rst | 2 +- docs/source/install/index.rst | 2 +- docs/source/user/aerodyn-olaf/OLAFTheory.rst | 2 +- docs/source/user/aerodyn/input.rst | 2 +- docs/source/user/aerodyn/theory.rst | 2 +- docs/source/user/beamdyn/theory.rst | 2 +- docs/source/user/cppapi/files/cDriver.i | 2 +- docs/source/user/elastodyn/theory.rst | 2 +- docs/source/user/fast.farm/FFarmTheory.rst | 2 +- docs/source/user/fast.farm/OutputFiles.rst | 2 +- docs/source/user/subdyn/theory.rst | 2 +- glue-codes/fast-farm/src/FAST_Farm.f90 | 4 +- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 2 +- glue-codes/openfast-cpp/src/OpenFAST.H | 4 +- modules/aerodyn/src/AeroDyn_Driver.f90 | 4 +- .../aerodyn/src/AeroDyn_Inflow_C_Binding.f90 | 8 +-- modules/aerodyn/src/AirfoilInfo.f90 | 4 +- modules/aerodyn/src/DBEMT.f90 | 2 +- modules/aerodyn/src/FVW.f90 | 6 +- modules/aerodyn/src/FVW_Subs.f90 | 2 +- modules/aerodyn/src/UnsteadyAero.f90 | 2 +- modules/beamdyn/src/BeamDyn.f90 | 4 +- modules/beamdyn/src/BeamDyn_Subs.f90 | 8 +-- modules/beamdyn/src/Driver_Beam.f90 | 4 +- modules/elastodyn/src/ElastoDyn.f90 | 2 +- modules/feamooring/src/FEAM.f90 | 4 +- modules/hydrodyn/src/Conv_Radiation.f90 | 2 +- modules/hydrodyn/src/HydroDyn_DriverCode.f90 | 4 +- modules/hydrodyn/src/Morison.f90 | 12 ++-- modules/hydrodyn/src/Morison_Output.f90 | 2 +- modules/hydrodyn/src/WAMIT.f90 | 14 ++--- modules/hydrodyn/src/WAMIT2.f90 | 18 +++--- modules/icedyn/src/IceDyn.f90 | 2 +- modules/icefloe/src/icefloe/IceFlexISO.f90 | 6 +- .../icefloe/src/interfaces/FAST/IceFloe.f90 | 2 +- modules/icefloe/test/GLA_proto_flex_ISO.log | 2 +- modules/inflowwind/src/IfW_C_Binding.f90 | 2 +- modules/inflowwind/src/InflowWind.f90 | 2 +- modules/inflowwind/src/InflowWind_Driver.f90 | 8 +-- modules/inflowwind/src/InflowWind_Subs.f90 | 2 +- modules/lindyn/src/LinDyn.f90 | 4 +- modules/map/src/bstring/bstrlib.h | 4 +- modules/map/src/freedata.c | 4 +- modules/map/src/lineroutines.c | 2 +- modules/map/src/mapapi.c | 4 +- modules/map/src/mapapi.h | 6 +- modules/map/src/mapinit.h | 8 +-- modules/map/src/simclist/simclist.h | 2 +- modules/moordyn/src/MoorDyn.f90 | 10 ++-- modules/moordyn/src/MoorDyn_Driver.f90 | 4 +- modules/moordyn/src/MoorDyn_Misc.f90 | 16 +++--- modules/moordyn/src/MoorDyn_Registry.txt | 2 +- modules/moordyn/src/MoorDyn_Types.f90 | 2 +- modules/nwtc-library/src/NWTC_IO.f90 | 2 +- modules/nwtc-library/src/NWTC_Num.f90 | 22 ++++---- .../src/NetLib/scalapack/dlasrt2.f | 2 +- .../src/NetLib/scalapack/slasrt2.f | 2 +- .../openfast-library/src/FAST_Registry.txt | 4 +- modules/openfast-library/src/FAST_Solver.f90 | 2 +- modules/openfast-library/src/FAST_Subs.f90 | 4 +- modules/openfast-library/src/FAST_Types.f90 | 4 +- modules/orcaflex-interface/src/OrcaDriver.f90 | 12 ++-- modules/seastate/src/SeaState_DriverCode.f90 | 4 +- modules/seastate/src/UserWaves.f90 | 6 +- modules/seastate/src/Waves.f90 | 12 ++-- modules/seastate/src/Waves2.f90 | 56 +++++++++---------- modules/servodyn/src/BladedInterface_EX.f90 | 8 +-- modules/servodyn/src/ServoDyn.f90 | 20 +++---- modules/servodyn/src/ServoDyn_IO.f90 | 18 +++--- modules/subdyn/src/SubDyn_Output.f90 | 2 +- openfast_io/openfast_io/FAST_reader.py | 2 +- openfast_io/openfast_io/FAST_writer.py | 2 +- openfast_io/openfast_io/turbsim_file.py | 4 +- .../executeUnsteadyAeroRegressionCase.py | 2 +- reg_tests/lib/rtestlib.py | 2 +- share/discon/DISCON.F90 | 4 +- 76 files changed, 212 insertions(+), 212 deletions(-) diff --git a/docs/source/dev/index.rst b/docs/source/dev/index.rst index dd833c8ef6..96ef271719 100644 --- a/docs/source/dev/index.rst +++ b/docs/source/dev/index.rst @@ -61,7 +61,7 @@ with the NREL OpenFAST team to define the scope of the work and coordinate development efforts. This is particularly important since many groups work on OpenFAST simultaneously. By engaging early, all developers can stay up to date and minimize conflicts during the code merge. -The prefered method of communication is `GitHub Issues `_. +The preferred method of communication is `GitHub Issues `_. An initial post should contain all relevant information about the planned development work, the areas of the software that will be impacted, and any model validation materials. See :ref:`development_plan` diff --git a/docs/source/install/index.rst b/docs/source/install/index.rst index 643fa0fc38..932a15d2be 100644 --- a/docs/source/install/index.rst +++ b/docs/source/install/index.rst @@ -478,7 +478,7 @@ The CMake options specific to OpenFAST and their default settings are: ORCA_DLL_LOAD - Enable OrcaFlex library load (Default: ON) USE_DLL_INTERFACE - Enable runtime loading of dynamic libraries (Default: ON) USE_LOCAL_STATIC_LAPACK - Enable downloading and building static LAPACK and BLAS libs (Default: OFF) - VARIABLE_TRACKING - Enables variable tracking for better runtime debugging output. May increase compile time. Valid only for GNU. (Defualt: ON) + VARIABLE_TRACKING - Enables variable tracking for better runtime debugging output. May increase compile time. Valid only for GNU. (Default: ON) Additional system-specific options may exist for a given system, but those diff --git a/docs/source/user/aerodyn-olaf/OLAFTheory.rst b/docs/source/user/aerodyn-olaf/OLAFTheory.rst index 7bde8f6587..ac21622da4 100644 --- a/docs/source/user/aerodyn-olaf/OLAFTheory.rst +++ b/docs/source/user/aerodyn-olaf/OLAFTheory.rst @@ -94,7 +94,7 @@ a line of varying circulation. The line follows the motion of the blade and is referred to as “bound” circulation. The bound circulation does not follow the same dynamic equation as the free vorticity of the wake. Instead, the intensity is linked to airfoil lift via the Kutta-Joukowski theorem. Spanwise variation of -the bound circulation results in vorticity being emitted into the the wake. This +the bound circulation results in vorticity being emitted into the wake. This is referred to as “trailed vorticity”. Time changes of the bound circulation are also emitted in the wake, referred to as “shed” vorticity. The subsequent paragraphs describe the representation of the bound vorticity. diff --git a/docs/source/user/aerodyn/input.rst b/docs/source/user/aerodyn/input.rst index 000fc089fe..5013abbad5 100644 --- a/docs/source/user/aerodyn/input.rst +++ b/docs/source/user/aerodyn/input.rst @@ -187,7 +187,7 @@ Determines the kind of BEM algorithm to use. .. warning:: - ``BEM_Mod`` currently governs the coordinate system used for "ill-defined" outputs (outputs that don't have a specified coordinate system) such as the ones that ends with "x" and "y". Other ill-defined outputs are the typical BEM quantities such as "AxInd", "TnInd", "Phi", etc. These are defined in a different coordinate system depending on `BEM_Mod`. For consistency accross differents `Wake_Mod` (even when `Wake_Mod/=1`), we use `BEM_Mod` to determine the coordinate system of the ill-defined outputs. + ``BEM_Mod`` currently governs the coordinate system used for "ill-defined" outputs (outputs that don't have a specified coordinate system) such as the ones that ends with "x" and "y". Other ill-defined outputs are the typical BEM quantities such as "AxInd", "TnInd", "Phi", etc. These are defined in a different coordinate system depending on `BEM_Mod`. For consistency across differents `Wake_Mod` (even when `Wake_Mod/=1`), we use `BEM_Mod` to determine the coordinate system of the ill-defined outputs. The following inputs in this section are only used when ``Wake_Mod = 1``. diff --git a/docs/source/user/aerodyn/theory.rst b/docs/source/user/aerodyn/theory.rst index 8043c51cfe..edd4aa2f1f 100644 --- a/docs/source/user/aerodyn/theory.rst +++ b/docs/source/user/aerodyn/theory.rst @@ -4,7 +4,7 @@ AeroDyn Theory ============== -This theory manual is work in progress, please refer to the AeroDyn 14 manual for more details :cite:`ad-AeroDyn:manual`. Many changes have occured since AeroDyn 14 (e.g. BEM formulation, coordinate system used in the BEM equations, dynamic stall, dynamic BEM), but these changes are not yet documented here. +This theory manual is work in progress, please refer to the AeroDyn 14 manual for more details :cite:`ad-AeroDyn:manual`. Many changes have occurred since AeroDyn 14 (e.g. BEM formulation, coordinate system used in the BEM equations, dynamic stall, dynamic BEM), but these changes are not yet documented here. diff --git a/docs/source/user/beamdyn/theory.rst b/docs/source/user/beamdyn/theory.rst index f8a80e1e1f..78d14e6936 100644 --- a/docs/source/user/beamdyn/theory.rst +++ b/docs/source/user/beamdyn/theory.rst @@ -82,7 +82,7 @@ Local blade coordinate system The local blade coordinate system is used for some input and output quantities, for example, the cross-sectional mass and stiffness matrices -and the the sectional force and moment resultants. This coordinate +and the sectional force and moment resultants. This coordinate system is different from the blade reference coordinate system in that its :math:`Z_l` axis is always tangent to the blade axis as the blade deflects. Note that a subscript :math:`l` denotes the local blade diff --git a/docs/source/user/cppapi/files/cDriver.i b/docs/source/user/cppapi/files/cDriver.i index 917208c312..f62e9725eb 100644 --- a/docs/source/user/cppapi/files/cDriver.i +++ b/docs/source/user/cppapi/files/cDriver.i @@ -27,7 +27,7 @@ n_substeps: 1 # Number of substeps per timestep of the glue-code n_checkpoint: 160 # Restart files will be written every so many time steps -set_exp_law_wind: false # Set velocity at the the turbine using an exponential law profile. +set_exp_law_wind: false # Set velocity at the turbine using an exponential law profile. Turbine0: diff --git a/docs/source/user/elastodyn/theory.rst b/docs/source/user/elastodyn/theory.rst index d4756dd0cd..09f2eec1e6 100644 --- a/docs/source/user/elastodyn/theory.rst +++ b/docs/source/user/elastodyn/theory.rst @@ -5,7 +5,7 @@ ElastoDyn Theory ================ Note this document is work in progress and is greatly incomplete. -This documentation was started to document some code changes to the the tail furl and rotor furl part of ElastoDyn. +This documentation was started to document some code changes to the tail furl and rotor furl part of ElastoDyn. Please refer to the different ressources provided in :numref:`ed_intro` for additional documents. diff --git a/docs/source/user/fast.farm/FFarmTheory.rst b/docs/source/user/fast.farm/FFarmTheory.rst index f07ab6e140..306a9b2878 100644 --- a/docs/source/user/fast.farm/FFarmTheory.rst +++ b/docs/source/user/fast.farm/FFarmTheory.rst @@ -1338,7 +1338,7 @@ where :math:`D` is a reference diameter, and :math:`\bar{U}` is the mean velocity taken as the filtered velocity at the turbine location normal to the rotor disk. The coordinates :math:`x,y,z` and :math:`r,\theta` are taken in the meandering frame of reference. The parameters :math:`k_\text{def}^\text{WAT}` -and :math:`k_\text{grad}^\text{WAT}` are tuning paramters of the model +and :math:`k_\text{grad}^\text{WAT}` are tuning parameters of the model respectively multiplying the quasi-steady wake deficit and the gradient of the wake deficit. These are based on an eddy-viscosity filter with five calibrated parameters to give a more realistic dependence on downstream position. The diff --git a/docs/source/user/fast.farm/OutputFiles.rst b/docs/source/user/fast.farm/OutputFiles.rst index 683820605f..4e65e3accf 100644 --- a/docs/source/user/fast.farm/OutputFiles.rst +++ b/docs/source/user/fast.farm/OutputFiles.rst @@ -138,5 +138,5 @@ module levels, as specified within the OpenFAST input files) are described in the OpenFAST documentation and include summary (*.sum*) files, time-series results (ASCI *.out* or binary *.outb*) files, visualization (*.vtk*) files, etc. FAST.Farm simulations will generate -these same files, but with the the path/rootname changed to *.T*. diff --git a/docs/source/user/subdyn/theory.rst b/docs/source/user/subdyn/theory.rst index 4df87b53cf..89e2cc31d5 100755 --- a/docs/source/user/subdyn/theory.rst +++ b/docs/source/user/subdyn/theory.rst @@ -1879,7 +1879,7 @@ This applies e.g.: to :math:`F_{R,e}, F_{L,e}, F_{R,g}, F_{L,g}`, where the foll The dependency of the load vectors on :math:`U_{TP}` introduces some complications for the state space representation, where for instance the :math:`B` and :math:`F_X` matrices should be modified to account for the dependency in :math:`U_{TP}` in Eq. :eq:`ABFx`. -The equation remains valid even if :math:`F_{L,e}` and :math:`F_{L,g}` contains a dependency in :math:`U_{TP}`, but the matrix :math:`B` shouldn't be used for the linearization (numerical differentiation is then prefered for simplicity). +The equation remains valid even if :math:`F_{L,e}` and :math:`F_{L,g}` contains a dependency in :math:`U_{TP}`, but the matrix :math:`B` shouldn't be used for the linearization (numerical differentiation is then preferred for simplicity). Similar considerations apply for Eq. :eq:`bigY2`. diff --git a/glue-codes/fast-farm/src/FAST_Farm.f90 b/glue-codes/fast-farm/src/FAST_Farm.f90 index bbc9ad94bd..6d2a8c141b 100644 --- a/glue-codes/fast-farm/src/FAST_Farm.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm.f90 @@ -49,8 +49,8 @@ PROGRAM FAST_Farm REAL(ReKi) :: PrevClockTime !< Previous clock time in seconds past midnight INTEGER :: SimStrtTime (8) !< An array containing the elements of the start time (after initialization). INTEGER :: ProgStrtTime (8) !< An array containing the elements of the program start time (before initialization). -REAL(ReKi) :: SimStrtCPU !< User CPU time for simulation (without intialization) -REAL(ReKi) :: ProgStrtCPU !< User CPU time for program (with intialization) +REAL(ReKi) :: SimStrtCPU !< User CPU time for simulation (without initialization) +REAL(ReKi) :: ProgStrtCPU !< User CPU time for program (with initialization) ! these should probably go in the FAST.Farm registry: type(All_FastFarm_Data) :: farm diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index 0a7f1a60b0..1a179e17b7 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -371,7 +371,7 @@ SUBROUTINE WAT_init( p, WAT_IfW, AWAE_InitInput, ErrStat, ErrMsg ) HAWC_InitInput%WindFileName(3) = trim(BoxFileRoot)//trim(FileEnding(3)) ! HAWC spatial grid - if (p%WAT == Mod_WAT_PreDef) then ! from libary of WAT files, set the NxNyNz and DxDyDz terms + if (p%WAT == Mod_WAT_PreDef) then ! from library of WAT files, set the NxNyNz and DxDyDz terms call MannLibDims(BoxFileRoot, p%RotorDiamRef, p%WAT_NxNyNz, p%WAT_DxDyDz, ErrStat2, ErrMsg2); if (Failed()) return write(sDummy, '(3(I8,1X))') p%WAT_NxNyNz call WrScr(' WAT: NxNyNz set to: '//trim(sDummy)//' (inferred from filename)') diff --git a/glue-codes/openfast-cpp/src/OpenFAST.H b/glue-codes/openfast-cpp/src/OpenFAST.H index 9915d7bbb3..f85d8fe619 100644 --- a/glue-codes/openfast-cpp/src/OpenFAST.H +++ b/glue-codes/openfast-cpp/src/OpenFAST.H @@ -82,7 +82,7 @@ struct turbineDataType { int nBRfsiPtsTwr; //! The mean azimuth at which the loads are blended between AeroDyn and CFD double azBlendMean; - //! The delta azimuth over which the the loads are blended between AeroDyn and CFD + //! The delta azimuth over which the loads are blended between AeroDyn and CFD double azBlendDelta; //! Mean velocity at reference height double velMean; @@ -729,7 +729,7 @@ private: //! Allocate memory for data structures for all turbines on this processor void allocateMemory_preInit(); - //! Allocate more memory for each turbine after intialization/restart + //! Allocate more memory for each turbine after initialization/restart void allocateMemory_postInit(int iTurbLoc); //! Get the nacelle drag coefficient of local turbine number 'iTurbLoc' diff --git a/modules/aerodyn/src/AeroDyn_Driver.f90 b/modules/aerodyn/src/AeroDyn_Driver.f90 index 076f0a4bcc..63b9eaef79 100644 --- a/modules/aerodyn/src/AeroDyn_Driver.f90 +++ b/modules/aerodyn/src/AeroDyn_Driver.f90 @@ -26,8 +26,8 @@ program AeroDyn_Driver ! Program variables REAL(ReKi) :: PrevClockTime ! Clock time at start of simulation in seconds [(s)] REAL(ReKi) :: UsrTime1 ! User CPU time for simulation initialization [(s)] - REAL(ReKi) :: UsrTime2 ! User CPU time for simulation (without intialization) [(s)] - INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime ! Start time of simulation (including intialization) [-] + REAL(ReKi) :: UsrTime2 ! User CPU time for simulation (without initialization) [(s)] + INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime ! Start time of simulation (including initialization) [-] INTEGER(IntKi) , DIMENSION(1:8) :: SimStrtTime ! Start time of simulation (after initialization) [-] REAL(DbKi) :: t_global ! global-loop time marker REAL(DbKi) :: t_final ! global-loop time marker diff --git a/modules/aerodyn/src/AeroDyn_Inflow_C_Binding.f90 b/modules/aerodyn/src/AeroDyn_Inflow_C_Binding.f90 index 4508cbafe7..9787eb4111 100644 --- a/modules/aerodyn/src/AeroDyn_Inflow_C_Binding.f90 +++ b/modules/aerodyn/src/AeroDyn_Inflow_C_Binding.f90 @@ -419,10 +419,10 @@ SUBROUTINE ADI_C_Init( ADinputFilePassed, ADinputFileString_C, ADinputFileString ! Input file info integer(c_int), intent(in ) :: ADinputFilePassed !< Write VTK outputs [0: none, 1: init only, 2: animation] type(c_ptr), intent(in ) :: ADinputFileString_C !< Input file as a single string with lines deliniated by C_NULL_CHAR - integer(c_int), intent(in ) :: ADinputFileStringLength_C !< lenght of the input file string + integer(c_int), intent(in ) :: ADinputFileStringLength_C !< length of the input file string integer(c_int), intent(in ) :: IfWinputFilePassed !< Write VTK outputs [0: none, 1: init only, 2: animation] type(c_ptr), intent(in ) :: IfWinputFileString_C !< Input file as a single string with lines deliniated by C_NULL_CHAR - integer(c_int), intent(in ) :: IfWinputFileStringLength_C !< lenght of the input file string + integer(c_int), intent(in ) :: IfWinputFileStringLength_C !< length of the input file string character(kind=c_char), intent(in ) :: OutRootName_C(IntfStrLen) !< Root name to use for echo files and other character(kind=c_char), intent(in ) :: OutVTKDir_C(IntfStrLen) !< Directory to put all vtk output ! Environmental @@ -2104,7 +2104,7 @@ end subroutine ADI_C_GetDiskAvgVel !=================================================================================================================================== !> This routine is operating on module level data. Error handling here in case checks added -!! NOTE: the OriginInit is not included in the data passed in and must be added to the the position info here +!! NOTE: the OriginInit is not included in the data passed in and must be added to the position info here subroutine Set_MotionMesh(iWT, ErrStat3, ErrMsg3) integer(IntKi), intent(in ) :: iWT !< current rotor/turbine integer(IntKi), intent( out) :: ErrStat3 @@ -2132,7 +2132,7 @@ end subroutine Set_MotionMesh !> Map the motion of the intermediate input mesh over to the input meshes !! This routine is operating on module level data, hence few inputs -!! NOTE: the OriginInit is not included in the data passed in and must be added to the the position info here +!! NOTE: the OriginInit is not included in the data passed in and must be added to the position info here subroutine AD_SetInputMotion( iWT, u_local, & HubPos_C, HubOri_C, HubVel_C, HubAcc_C, & NacPos_C, NacOri_C, NacVel_C, NacAcc_C, & diff --git a/modules/aerodyn/src/AirfoilInfo.f90 b/modules/aerodyn/src/AirfoilInfo.f90 index 55f0d5d2a4..b00886b7da 100644 --- a/modules/aerodyn/src/AirfoilInfo.f90 +++ b/modules/aerodyn/src/AirfoilInfo.f90 @@ -1391,8 +1391,8 @@ SUBROUTINE ComputeUA360_AttachedFlow(p, ColUAf, cn_cl, iLower, iUpper) !------------------------------------------------ call Compute_iLoweriUpper(p, iLower, iUpper) - p%UA_BL%alphaLower = p%alpha(iLower) ! note we are overwritting values here to make them consistent in the linear equation - p%UA_BL%alphaUpper = p%alpha(iUpper) ! note we are overwritting values here to make them consistent in the linear equation + p%UA_BL%alphaLower = p%alpha(iLower) ! note we are overwriting values here to make them consistent in the linear equation + p%UA_BL%alphaUpper = p%alpha(iUpper) ! note we are overwriting values here to make them consistent in the linear equation p%UA_BL%c_alphaLower = cn_cl(iLower) ! for vortex calculations (x5, HGMV model) p%UA_BL%c_alphaUpper = cn_cl(iUpper) ! for vortex calculations (x5, HGMV model) diff --git a/modules/aerodyn/src/DBEMT.f90 b/modules/aerodyn/src/DBEMT.f90 index 4f5a2d6bd8..add09cedc5 100644 --- a/modules/aerodyn/src/DBEMT.f90 +++ b/modules/aerodyn/src/DBEMT.f90 @@ -844,7 +844,7 @@ SUBROUTINE DBEMT_ABM4( i, j, t, n, u, utimes, p, x, OtherState, m, ErrStat, ErrM x_in = x%element(i,j) - ! predict: (note that we are overwritting x%element(i,j)%vind and x%element(i,j)%vind_1 here): + ! predict: (note that we are overwriting x%element(i,j)%vind and x%element(i,j)%vind_1 here): CALL DBEMT_AB4( i, j, t, n, u, utimes, p, x, OtherState, m, ErrStat2, ErrMsg2 ) CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) RETURN diff --git a/modules/aerodyn/src/FVW.f90 b/modules/aerodyn/src/FVW.f90 index 2c55f4dc27..92b43acfbb 100644 --- a/modules/aerodyn/src/FVW.f90 +++ b/modules/aerodyn/src/FVW.f90 @@ -480,7 +480,7 @@ subroutine FVW_FinalWrite(u, p, x, z, m, ErrStat, ErrMsg) ErrMsg = "" ! Place any last minute operations or calculations here: if (p%WrVTK>0 .and. m%VTKstep= AbortErrLev ) RETURN diff --git a/modules/beamdyn/src/BeamDyn.f90 b/modules/beamdyn/src/BeamDyn.f90 index 86d3382a47..28683f111a 100644 --- a/modules/beamdyn/src/BeamDyn.f90 +++ b/modules/beamdyn/src/BeamDyn.f90 @@ -2282,7 +2282,7 @@ SUBROUTINE BD_QuadraturePointDataAt0( p ) DO nelem = 1,p%elem_total DO idx_qp = 1,p%nqp - !> ### Calculate the the initial displacement fields in an element + !> ### Calculate the initial displacement fields in an element !! Initial displacement field \n !! \f$ \underline{u_0}\left( \xi \right) = !! \sum_{k=1}^{p+1} h^k\left( \xi \right) \underline{\hat{u}_0}^k @@ -2370,7 +2370,7 @@ SUBROUTINE BD_DisplacementQP( nelem, p, x, m ) INTEGER(IntKi) :: idx_qp !< index to the current quadrature point INTEGER(IntKi) :: elem_start !< Node point of first node in current element - !> ### Calculate the the displacement fields in an element + !> ### Calculate the displacement fields in an element !! Using equations (27) and (28) \n !! \f$ \underline{u}\left( \xi \right) = !! \sum_{i=1}^{p+1} h^i\left( \xi \right) \underline{\hat{u}}^i diff --git a/modules/beamdyn/src/BeamDyn_Subs.f90 b/modules/beamdyn/src/BeamDyn_Subs.f90 index c1b9796a07..823fa9d0e2 100644 --- a/modules/beamdyn/src/BeamDyn_Subs.f90 +++ b/modules/beamdyn/src/BeamDyn_Subs.f90 @@ -146,7 +146,7 @@ SUBROUTINE BD_CrvMatrixR(cc,Rr) c2 = cc(2)/4.0_BDKi c3 = cc(3)/4.0_BDKi ! \f$ c_0 \f$ is equivalent to \f$ 0.5 - (||\vec{c}||)^2 / 32 \f$ - c0 = 0.5_BDKi * (1.0_BDKi-c1*c1-c2*c2-c3*c3) ! 1/4 the value of the the AIAA paper (after plugging in c1, c2, c3 conversions) + c0 = 0.5_BDKi * (1.0_BDKi-c1*c1-c2*c2-c3*c3) ! 1/4 the value of the AIAA paper (after plugging in c1, c2, c3 conversions) tr0 = 1.0_BDKi - c0 ! This is 1/4 the value of the AIAA paper, after converting c0. @@ -316,7 +316,7 @@ END SUBROUTINE BD_CrvCompose SUBROUTINE BD_CrvExtractCrv(R, cc, ErrStat, ErrMsg) REAL(BDKi), INTENT(IN ) :: R(3,3) !< Rotation Matrix - REAL(BDKi), INTENT( OUT) :: cc(3) !< Crv paramters + REAL(BDKi), INTENT( OUT) :: cc(3) !< Crv parameters INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None @@ -525,13 +525,13 @@ SUBROUTINE BD_GaussPointWeight(n, x, w, ErrStat, ErrMsg) ! loop through each of the "half" n points do i = 1, n_half - ! Intial guess for ith root; based on ith root of Chebyshev polynomial + ! Initial guess for ith root; based on ith root of Chebyshev polynomial x(i) = - cos( REAL( 2*i - 1, BDKi) * pi_D / (2.0_BDKi * n_real) ) ! initialize newton iteration counter newton = 0 - p3 = 1. ! some intial big number; logic will always take at least one newton iteration + p3 = 1. ! some initial big number; logic will always take at least one newton iteration do while (abs(p3) .gt. eps .and. newton .le. newton_max) newton = newton + 1 ! keep track of number of newton iterations diff --git a/modules/beamdyn/src/Driver_Beam.f90 b/modules/beamdyn/src/Driver_Beam.f90 index 8b1d51d194..0141190d7e 100644 --- a/modules/beamdyn/src/Driver_Beam.f90 +++ b/modules/beamdyn/src/Driver_Beam.f90 @@ -63,8 +63,8 @@ PROGRAM BeamDyn_Driver_Program REAL(DbKi) :: TiLstPrn ! The simulation time of the last print (to file) [(s)] REAL(ReKi) :: PrevClockTime ! Clock time at start of simulation in seconds [(s)] REAL(ReKi) :: UsrTime1 ! User CPU time for simulation initialization [(s)] - REAL(ReKi) :: UsrTime2 ! User CPU time for simulation (without intialization) [(s)] - INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime ! Start time of simulation (including intialization) [-] + REAL(ReKi) :: UsrTime2 ! User CPU time for simulation (without initialization) [(s)] + INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime ! Start time of simulation (including initialization) [-] INTEGER(IntKi) , DIMENSION(1:8) :: SimStrtTime ! Start time of simulation (after initialization) [-] CHARACTER(200) :: git_commit ! String containing the current git commit hash diff --git a/modules/elastodyn/src/ElastoDyn.f90 b/modules/elastodyn/src/ElastoDyn.f90 index dc5d36ee2d..fd8104bb1e 100644 --- a/modules/elastodyn/src/ElastoDyn.f90 +++ b/modules/elastodyn/src/ElastoDyn.f90 @@ -5211,7 +5211,7 @@ SUBROUTINE Coeff(p,InputFileData, ErrStat, ErrMsg) END SUBROUTINE Coeff !---------------------------------------------------------------------------------------------------------------------------------- !> This routine calculates the initial blade deflections. -!! Base the intial values of the blade DOFs, INITQF1, INITQF2, and +!! Base the initial values of the blade DOFs, INITQF1, INITQF2, and !! INITQE1, on OoPDefl and IPDefl. !! Write messages to the screen if the specified initial tip displacements !! are incompatible with the enabled DOFs. diff --git a/modules/feamooring/src/FEAM.f90 b/modules/feamooring/src/FEAM.f90 index a97aeee76b..76ac6fccbd 100644 --- a/modules/feamooring/src/FEAM.f90 +++ b/modules/feamooring/src/FEAM.f90 @@ -1444,7 +1444,7 @@ SUBROUTINE FEAM_CalcOutput ( t, u, p, x, xd, z, OtherState, y, misc, ErrStat, CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None ! Local variables - REAL(ReKi) :: AllOuts(MaxOutPts) ! All the the available output channels + REAL(ReKi) :: AllOuts(MaxOutPts) ! All the available output channels INTEGER(IntKi) :: I,J ! Generic loop index ! INTEGER(IntKi) :: K ! Blade index ! INTEGER(IntKi) :: ErrStat2 @@ -2208,7 +2208,7 @@ SUBROUTINE SetPrimaryParameters( p, InputFileData, ErrStat, ErrMsg ) p%NEQ(:) = (p%NumElems+1)*p%NHBD-1 ! number of equations DO I = 1, p%NumLines - p%GSL (I,:,:) = InputFileData%GSL (I,:,:) !bjj: todo: Inspector flags this as unintialized + p%GSL (I,:,:) = InputFileData%GSL (I,:,:) !bjj: todo: Inspector flags this as uninitialized p%LineCI (I) = InputFileData%LineCI (I) p%LineCD (I) = InputFileData%LineCD (I) p%Elength (I) = InputFileData%LUnstrLen(I)/p%NumElems diff --git a/modules/hydrodyn/src/Conv_Radiation.f90 b/modules/hydrodyn/src/Conv_Radiation.f90 index 59842ddd2c..0584f2a8ef 100644 --- a/modules/hydrodyn/src/Conv_Radiation.f90 +++ b/modules/hydrodyn/src/Conv_Radiation.f90 @@ -178,7 +178,7 @@ SUBROUTINE Conv_Rdtn_Init( InitInp, u, p, x, xd, z, OtherState, y, m, InitOut, E RETURN END IF - ! Initialize all elements of the xd%XDHistory array with the intial values of u%Velocity + ! Initialize all elements of the xd%XDHistory array with the initial values of u%Velocity DO K = 0,p%NStepRdtn-1 DO J = 1,6*p%NBody ! Loop through all DOFs xd%XDHistory(K,J) = u%Velocity(J) diff --git a/modules/hydrodyn/src/HydroDyn_DriverCode.f90 b/modules/hydrodyn/src/HydroDyn_DriverCode.f90 index 4c2ccf61bb..a0cc08d04e 100644 --- a/modules/hydrodyn/src/HydroDyn_DriverCode.f90 +++ b/modules/hydrodyn/src/HydroDyn_DriverCode.f90 @@ -73,11 +73,11 @@ PROGRAM HydroDynDriver TYPE(HD_Drvr_Data) :: drvrData ! Data for the driver program (from an input file) TYPE(HD_Drvr_MappingData) :: mappingData ! data for mesh mappings in the driver - integer :: StrtTime (8) ! Start time of simulation (including intialization) + integer :: StrtTime (8) ! Start time of simulation (including initialization) integer :: SimStrtTime (8) ! Start time of simulation (after initialization) real(ReKi) :: PrevClockTime ! Clock time at start of simulation in seconds real(ReKi) :: UsrTime1 ! User CPU time for simulation initialization - real(ReKi) :: UsrTime2 ! User CPU time for simulation (without intialization) + real(ReKi) :: UsrTime2 ! User CPU time for simulation (without initialization) real(DbKi) :: TiLstPrn ! The simulation time of the last print integer :: n_SttsTime ! Number of time steps between screen status messages (-) diff --git a/modules/hydrodyn/src/Morison.f90 b/modules/hydrodyn/src/Morison.f90 index 2926f82e6b..88c9e20719 100644 --- a/modules/hydrodyn/src/Morison.f90 +++ b/modules/hydrodyn/src/Morison.f90 @@ -181,7 +181,7 @@ END SUBROUTINE FindInterpFactor FUNCTION InterpWrappedStpInt( XValIn, XAry, YAry, Ind, AryLen ) - ! This funtion returns a y-value that corresponds to an input x-value which is wrapped back + ! This function returns a y-value that corresponds to an input x-value which is wrapped back ! into the range [1-XAry(AryLen). It finds a x-value which corresponds to a value in the XAry where XAry(Ind-1) < MOD(XValIn, XAry(AryLen)) <= XAry(Ind) ! It is assumed that XAry is sorted in ascending order. ! It uses the passed index as the starting point and does a stepwise interpolation from there. This is @@ -262,7 +262,7 @@ END FUNCTION InterpWrappedStpInt ! ( XVal, XAry, YAry, Ind, AryLen ) FUNCTION InterpWrappedStpLogical( XValIn, XAry, YAry, Ind, AryLen ) - ! This funtion returns a y-value that corresponds to an input x-value which is wrapped back + ! This function returns a y-value that corresponds to an input x-value which is wrapped back ! into the range [0-XAry(AryLen) by interpolating into the arrays. ! It is assumed that XAry is sorted in ascending order. ! It uses the passed index as the starting point and does a stepwise interpolation from there. This is @@ -393,7 +393,7 @@ SUBROUTINE TaperCalc(R1, R2, H, taperV, h_c) if ( EqualRealNos(R1, R2) ) then ! if just a cylinder taperV = abs(pi*R1*R1*H) h_c = H/2.0 - elseif ( EqualRealNos(R1,0.0_ReKi) ) then ! seperate this case out because it gives a divide by zero in general formula + elseif ( EqualRealNos(R1,0.0_ReKi) ) then ! separate this case out because it gives a divide by zero in general formula taperV = abs(1.0/3.0*pi*R2*R2*H) ! cone volume h_c = 3.0/4.0*H ! from base else @@ -418,7 +418,7 @@ SUBROUTINE CylInertia(R1, R2, H, rho, Il, Ir) if ( EqualRealNos(R1, R2) ) then ! if just a cylinder Ir = abs(1.0/12.0* rho*pi*R1*R1*H *(3.0*R1*R1 + 4.0*H*H)) ! radial inertia about node 1 Il = abs(0.5* rho*pi*R1*R1*H *R1*R1) - ELSEIF ( EqualRealNos(R1,0.0_ReKi) ) then ! seperate this case out because it gives a divide by zero in general formula + ELSEIF ( EqualRealNos(R1,0.0_ReKi) ) then ! separate this case out because it gives a divide by zero in general formula Ir = abs(rho*pi*(1.0/20.0/m + 1.0/5.0/m**3) * R2**5) Il = abs(1.0/10.0*rho*pi/m*R2**5) ELSE @@ -1409,7 +1409,7 @@ subroutine FlipMemberNodeData( member, nodes, doSwap) doSwap = .TRUE. ! Z1 > Z2 END IF - ! If we swap the the nodes, we need know this later when calculating the normal vector to the ends + ! If we swap the nodes, we need know this later when calculating the normal vector to the ends member%Flipped = doSwap IF ( doSwap ) THEN member%NodeIndx(1) = j2 @@ -1772,7 +1772,7 @@ subroutine SetMemberProperties( gravity, member, MCoefMod, MmbrCoefIDIndx, MmbrF end if ! Need to enforce the modeling requirement that a partially flooded member must not be close to horizontal if ( (InitInp%Nodes(member%NodeIndx(N+1))%Position(3) - member%Rin(N+1)*sinPhi) < member%FillFSLoc ) then - call SetErrStat(ErrID_Fatal,'The modeling of partially flooded/ballested members requires the the member not be near horizontal. This is not true for MemberID '//trim(num2lstr(member%MemberID)),ErrStat,ErrMsg,'SetMemberProperties') + call SetErrStat(ErrID_Fatal,'The modeling of partially flooded/ballested members requires the member not be near horizontal. This is not true for MemberID '//trim(num2lstr(member%MemberID)),ErrStat,ErrMsg,'SetMemberProperties') return end if diff --git a/modules/hydrodyn/src/Morison_Output.f90 b/modules/hydrodyn/src/Morison_Output.f90 index 16ccff3178..4aa0d64dd6 100644 --- a/modules/hydrodyn/src/Morison_Output.f90 +++ b/modules/hydrodyn/src/Morison_Output.f90 @@ -7980,7 +7980,7 @@ SUBROUTINE MrsnOut_Init( InitInp, y, p, InitOut, ErrStat, ErrMsg ) TYPE(Morison_InitInputType ), INTENT( IN ) :: InitInp ! data needed to initialize the output module TYPE(Morison_OutputType), INTENT( INOUT ) :: y ! Morison module's output data - TYPE(Morison_ParameterType), INTENT( INOUT ) :: p ! Morison module paramters + TYPE(Morison_ParameterType), INTENT( INOUT ) :: p ! Morison module parameters TYPE(Morison_InitOutputType ), INTENT( INOUT ) :: InitOut ! Morison module initialization output data INTEGER, INTENT( OUT ) :: ErrStat ! a non-zero value indicates an error occurred CHARACTER(*), INTENT( OUT ) :: ErrMsg ! Error message if ErrStat /= ErrID_None diff --git a/modules/hydrodyn/src/WAMIT.f90 b/modules/hydrodyn/src/WAMIT.f90 index d04c5a823b..bf1260f4ca 100644 --- a/modules/hydrodyn/src/WAMIT.f90 +++ b/modules/hydrodyn/src/WAMIT.f90 @@ -126,12 +126,12 @@ SUBROUTINE WAMIT_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, ErrS ! These are dummy variables to satisfy the framework, but are not used - TYPE(Conv_Rdtn_InitInputType) :: Conv_Rdtn_InitInp ! Local version of the intialization data for the radiation module + TYPE(Conv_Rdtn_InitInputType) :: Conv_Rdtn_InitInp ! Local version of the initialization data for the radiation module TYPE(Conv_Rdtn_InitOutputType) :: Conv_Rdtn_InitOut ! Initialization Outputs from the Conv_Rdtn module initialization !TYPE(Conv_Rdtn_InitOutputType) :: Conv_RdtnInitOutData - TYPE(SS_Rad_InitInputType) :: SS_Rdtn_InitInp ! Local version of the intialization data for the radiation module + TYPE(SS_Rad_InitInputType) :: SS_Rdtn_InitInp ! Local version of the initialization data for the radiation module TYPE(SS_Rad_InitOutputType) :: SS_Rdtn_InitOut ! Initialization Outputs from the SS_Rdtn module initialization - TYPE(SS_Exc_InitInputType) :: SS_Exctn_InitInp ! Local version of the intialization data for the SS wave excitation module + TYPE(SS_Exc_InitInputType) :: SS_Exctn_InitInp ! Local version of the initialization data for the SS wave excitation module TYPE(SS_Exc_InitOutputType) :: SS_Exctn_InitOut ! Initialization Outputs from the SS wave excitation module initialization @@ -1163,7 +1163,7 @@ SUBROUTINE WAMIT_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, ErrS DO iHdg = 1,p%NExctnHdg+1 DO J = 1,6*p%NBody ! Loop through all wave excitation forces and moments CALL ApplyFFT_cx ( p%WaveExctnGrid(0:p%WaveField%NStepWave-1,1_IntKi,1_IntKi,iHdg,J), WaveExctnC(:,iHdg,J), FFT_Data, ErrStat2 ) - CALL SetErrStat( ErrStat2, ' An error occured while applying an FFT to WaveExctnC.', ErrStat, ErrMsg, RoutineName) + CALL SetErrStat( ErrStat2, ' An error occurred while applying an FFT to WaveExctnC.', ErrStat, ErrMsg, RoutineName) IF ( ErrStat >= AbortErrLev) THEN CALL Cleanup() RETURN @@ -1249,7 +1249,7 @@ SUBROUTINE WAMIT_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, ErrS iY = (iGrid-1) / p%ExctnGridParams%n(2) + 1 DO J = 1,6*p%NBody ! Loop through all wave excitation forces and moments CALL ApplyFFT_cx ( p%WaveExctnGrid(0:p%WaveField%NStepWave-1,iX,iY,iHdg,J), WaveExctnCGrid(:,iGrid,iHdg,J), FFT_Data, ErrStat2 ) - CALL SetErrStat( ErrStat2, ' An error occured while applying an FFT to WaveExctnC.', ErrStat, ErrMsg, RoutineName) + CALL SetErrStat( ErrStat2, ' An error occurred while applying an FFT to WaveExctnC.', ErrStat, ErrMsg, RoutineName) IF ( ErrStat >= AbortErrLev) THEN CALL Cleanup() RETURN @@ -1332,7 +1332,7 @@ SUBROUTINE WAMIT_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, ErrS ! representations of the wave kinematics without stretching: CALL InitFFT ( p%WaveField%NStepWave, FFT_Data, .TRUE., ErrStat2 ) - CALL SetErrStat(ErrStat2,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -1341,7 +1341,7 @@ SUBROUTINE WAMIT_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, ErrS ! We'll need the following for wave stretching once we implement it. ! NOTE THIS IS OVERWRITING THE WAVEFIELD WaveElev0 PARAMETER DATA CALL ApplyFFT_cx ( SS_Exctn_InitInp%WaveField%WaveElev0(0:p%WaveField%NStepWave-1), tmpComplexArr(: ), FFT_Data, ErrStat2 ) - CALL SetErrStat(ErrStat2,'Error occured while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStat2,'Error occurred while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN diff --git a/modules/hydrodyn/src/WAMIT2.f90 b/modules/hydrodyn/src/WAMIT2.f90 index f62043b92f..3c38462510 100644 --- a/modules/hydrodyn/src/WAMIT2.f90 +++ b/modules/hydrodyn/src/WAMIT2.f90 @@ -1339,7 +1339,7 @@ SUBROUTINE NewmanApp_InitCalc( InitInp, p, NewmanAppData, NewmanAppForce, ErrMsg ! Initialize the FFT library CALL InitCFFT ( InitInp%WaveField%NStepWave, FFT_Data, .FALSE., ErrStatTmp ) ! Complex result FFT initialize - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData3D)) DEALLOCATE(TmpData3D,STAT=ErrStatTmp) IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) @@ -1620,7 +1620,7 @@ SUBROUTINE NewmanApp_InitCalc( InitInp, p, NewmanAppData, NewmanAppForce, ErrMsg ! Done with the FFT library routines, so end them. CALL ExitCFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData3D)) DEALLOCATE(TmpData3D,STAT=ErrStatTmp) IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) @@ -1803,7 +1803,7 @@ SUBROUTINE DiffQTF_InitCalc( InitInp, p, DiffQTFData, DiffQTFForce, ErrMsg, ErrS ! Initialize the FFT library. Do not apply normalization. CALL InitFFT ( InitInp%WaveField%NStepWave, FFT_Data, .FALSE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN call cleanup() RETURN @@ -1990,7 +1990,7 @@ SUBROUTINE DiffQTF_InitCalc( InitInp, p, DiffQTFData, DiffQTFForce, ErrMsg, ErrS ! Now we apply the FFT to the result of the sum CALL ApplyFFT_cx( TmpDiffQTFForce(:), TmpComplexArr(:,ThisDim), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to the second term of the difference QTF.', & + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to the second term of the difference QTF.', & ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN call cleanup() @@ -2015,7 +2015,7 @@ SUBROUTINE DiffQTF_InitCalc( InitInp, p, DiffQTFData, DiffQTFForce, ErrMsg, ErrS ! Done with the FFT library routines, so end them. CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN call cleanup() RETURN @@ -2234,7 +2234,7 @@ SUBROUTINE SumQTF_InitCalc( InitInp, p, SumQTFData, SumQTFForce, ErrMsg, ErrStat ! Initialize the FFT library. Normalization not required in this formulation. CALL InitFFT ( InitInp%WaveField%NStepWave, FFT_Data, .FALSE., ErrStatTmp ) ! FIXME: - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) IF (ALLOCATED(SumQTFForce)) DEALLOCATE(SumQTFForce,STAT=ErrStatTmp) @@ -2516,7 +2516,7 @@ SUBROUTINE SumQTF_InitCalc( InitInp, p, SumQTFData, SumQTFForce, ErrMsg, ErrStat ! Now we apply the FFT to the result of the sum. CALL ApplyFFT_cx( Term1Array(:), Term1ArrayC(:,ThisDim), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to the first term of the Sum QTF.', & + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to the first term of the Sum QTF.', & ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) @@ -2525,7 +2525,7 @@ SUBROUTINE SumQTF_InitCalc( InitInp, p, SumQTFData, SumQTFForce, ErrMsg, ErrStat ! Now we apply the FFT to the result of the sum. CALL ApplyFFT_cx( Term2Array(:), Term2ArrayC(:,ThisDim), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to the second term of the Sum QTF.', & + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to the second term of the Sum QTF.', & ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) @@ -2548,7 +2548,7 @@ SUBROUTINE SumQTF_InitCalc( InitInp, p, SumQTFData, SumQTFForce, ErrMsg, ErrStat ! Done with the FFT library routines, so end them. CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN IF (ALLOCATED(TmpData4D)) DEALLOCATE(TmpData4D,STAT=ErrStatTmp) RETURN diff --git a/modules/icedyn/src/IceDyn.f90 b/modules/icedyn/src/IceDyn.f90 index 9abd548d9f..87440da45c 100644 --- a/modules/icedyn/src/IceDyn.f90 +++ b/modules/icedyn/src/IceDyn.f90 @@ -2516,7 +2516,7 @@ END FUNCTION SolveLambda FUNCTION BrkLdPar (alpha, lambda, mu) Result (A) - !BRKLDPAR Calculates Ralston's horizontal force paramters A1, A2, A3, A4 and B1, B2. + !BRKLDPAR Calculates Ralston's horizontal force parameters A1, A2, A3, A4 and B1, B2. ! Detailed explanation in Ralston's paper: Ice Force Desgin Consideration ! for Conical Offshore Structure and Ice Module Manual diff --git a/modules/icefloe/src/icefloe/IceFlexISO.f90 b/modules/icefloe/src/icefloe/IceFlexISO.f90 index aeb4e9f25d..4e292c8bc5 100644 --- a/modules/icefloe/src/icefloe/IceFlexISO.f90 +++ b/modules/icefloe/src/icefloe/IceFlexISO.f90 @@ -126,9 +126,9 @@ subroutine initFlexISO (iceInput, myIceParams, iceLog) call getIceInput(iceInput, 'includeLc', inParams%includeLc, iceLog) if (inParams%includeLc) then - call logMessage(iceLog, ' Including crack lenght modification term, Lc') + call logMessage(iceLog, ' Including crack length modification term, Lc') else - call logMessage(iceLog, ' NOT including crack lenght modification term, Lc') + call logMessage(iceLog, ' NOT including crack length modification term, Lc') endif ! The Croasdale method precalculates a time series of loads based @@ -275,7 +275,7 @@ subroutine randomFlexLoadTimeSeries (myIceParams, iceLog, maxLoad) ! Loop on all legs do nL = 1, myIceParams%numLegs - ! Number of whole periods required not known (since period lenght is random) + ! Number of whole periods required not known (since period length is random) ! So iterate until we have enough points in the time series n = 1 seriesLoop: do while (n < nSteps+1) diff --git a/modules/icefloe/src/interfaces/FAST/IceFloe.f90 b/modules/icefloe/src/interfaces/FAST/IceFloe.f90 index f257ddeb6e..90b2b4490e 100644 --- a/modules/icefloe/src/interfaces/FAST/IceFloe.f90 +++ b/modules/icefloe/src/interfaces/FAST/IceFloe.f90 @@ -190,7 +190,7 @@ SUBROUTINE IceFloe_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, In endif ! get the simulation length from FAST - ! if the the length from FAST is zero read from iceFloe input file + ! if the length from FAST is zero read from iceFloe input file if (InitInp%simLength <= 0) then duration = InitInp%simLength else diff --git a/modules/icefloe/test/GLA_proto_flex_ISO.log b/modules/icefloe/test/GLA_proto_flex_ISO.log index 88efb643e8..d46f6f5115 100644 --- a/modules/icefloe/test/GLA_proto_flex_ISO.log +++ b/modules/icefloe/test/GLA_proto_flex_ISO.log @@ -44,7 +44,7 @@ Including pile up term, Hp Including rubble lifting term, Hl Including block rotation term, Ht - Including crack lenght modification term, Lc + Including crack length modification term, Lc ** Pile up term, Hp = 2242 Newtons ** Rubble lifting term, Hl = 2.09678E+05 Newtons ** Block rotation term, Ht = 42609 Newtons diff --git a/modules/inflowwind/src/IfW_C_Binding.f90 b/modules/inflowwind/src/IfW_C_Binding.f90 index 8299d6010f..1050b1cec4 100644 --- a/modules/inflowwind/src/IfW_C_Binding.f90 +++ b/modules/inflowwind/src/IfW_C_Binding.f90 @@ -101,7 +101,7 @@ SUBROUTINE IfW_C_Init(IfWinputFilePassed, IfWinputFileString_C, IfWinputFileStri #endif integer(c_int), intent(in ) :: IfWinputFilePassed !< Write VTK outputs [0: none, 1: init only, 2: animation] type(c_ptr), intent(in ) :: IfWinputFileString_C !< Input file as a single string with lines deliniated by C_NULL_CHAR - integer(c_int), intent(in ) :: IfWinputFileStringLength_C !< lenght of the input file string + integer(c_int), intent(in ) :: IfWinputFileStringLength_C !< length of the input file string character(kind=c_char), intent(in ) :: OutRootName_C(IntfStrLen) !< Root name to use for echo files and other integer(c_int), intent(in ) :: NumWindPts_C real(c_double), intent(in ) :: DT_C diff --git a/modules/inflowwind/src/InflowWind.f90 b/modules/inflowwind/src/InflowWind.f90 index de2d713a3b..f21389143f 100644 --- a/modules/inflowwind/src/InflowWind.f90 +++ b/modules/inflowwind/src/InflowWind.f90 @@ -550,7 +550,7 @@ END SUBROUTINE InflowWind_Init !! these PositionXYZPrime coordinates. !! !! After the calculation by the submodule, the PositionXYZPrime coordinate array is deallocated. The returned VelocityUVW -!! array is then rotated by p%PropagationDir so that it now corresponds the the global coordinate UVW values for wind +!! array is then rotated by p%PropagationDir so that it now corresponds to the global coordinate UVW values for wind !! with that direction. !---------------------------------------------------------------------------------------------------- SUBROUTINE InflowWind_CalcOutput( Time, InputData, p, & diff --git a/modules/inflowwind/src/InflowWind_Driver.f90 b/modules/inflowwind/src/InflowWind_Driver.f90 index 42b29d1d11..f1d7dcfb12 100644 --- a/modules/inflowwind/src/InflowWind_Driver.f90 +++ b/modules/inflowwind/src/InflowWind_Driver.f90 @@ -733,7 +733,7 @@ PROGRAM InflowWind_Driver InflowWind_x, InflowWind_xd, InflowWind_z, InflowWind_OtherState, & InflowWind_y1, InflowWind_MiscVars, ErrStat, ErrMsg) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -860,7 +860,7 @@ PROGRAM InflowWind_Driver InflowWind_x, InflowWind_xd, InflowWind_z, InflowWind_OtherState, & InflowWind_y1, InflowWind_MiscVars, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -879,7 +879,7 @@ PROGRAM InflowWind_Driver InflowWind_x, InflowWind_xd, InflowWind_z, InflowWind_OtherState, & InflowWind_y2, InflowWind_MiscVars, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -898,7 +898,7 @@ PROGRAM InflowWind_Driver InflowWind_x, InflowWind_xd, InflowWind_z, InflowWind_OtherState, & InflowWind_y3, InflowWind_MiscVars, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) diff --git a/modules/inflowwind/src/InflowWind_Subs.f90 b/modules/inflowwind/src/InflowWind_Subs.f90 index 3041c710a2..001e7b18ea 100644 --- a/modules/inflowwind/src/InflowWind_Subs.f90 +++ b/modules/inflowwind/src/InflowWind_Subs.f90 @@ -462,7 +462,7 @@ SUBROUTINE InflowWind_ParseInputFileInfo( InputFileData, InFileInfo, PriPath, In ! if (Failed()) return !---------------------------------------------------------------------------------------------- - !> Read the _Mean wind profile paramters (added to HAWC-format files) [used only for WindType = 5]_ subsection + !> Read the _Mean wind profile parameters (added to HAWC-format files) [used only for WindType = 5]_ subsection !---------------------------------------------------------------------------------------------- CurLine = CurLine + 1 ! Skip section break diff --git a/modules/lindyn/src/LinDyn.f90 b/modules/lindyn/src/LinDyn.f90 index 3bb9f0f292..799c0d2fd3 100644 --- a/modules/lindyn/src/LinDyn.f90 +++ b/modules/lindyn/src/LinDyn.f90 @@ -179,10 +179,10 @@ subroutine LD_SetInitialConditions(x, x0, xd0, p, OtherState, m, errStat, errMsg nx = int(size(x%q)/2) errStat = ErrID_Fatal if (size(x0)/=size(xd0)) then - errMsg ='Shape of x0 and xd0 should match when setting intial conditions'; return + errMsg ='Shape of x0 and xd0 should match when setting initial conditions'; return endif if (size(x0)/=nx) then - errMsg ='Shape of x0 should match nx when setting intial conditions'; return + errMsg ='Shape of x0 should match nx when setting initial conditions'; return endif errMsg = '' errStat = ErrID_None diff --git a/modules/map/src/bstring/bstrlib.h b/modules/map/src/bstring/bstrlib.h index 1292a38cb9..0887977a90 100644 --- a/modules/map/src/bstring/bstrlib.h +++ b/modules/map/src/bstring/bstrlib.h @@ -1506,7 +1506,7 @@ bseof(const struct bStream *s); /* Static constant block parameter pair */ /** - * The bsStaticBlkParms macro emits a pair of comma seperated parameters + * The bsStaticBlkParms macro emits a pair of comma separated parameters * corresponding to the block parameters for the block functions in Bstrlib * (i.e., blk2bstr, bcatblk, blk2tbstr, bisstemeqblk, bisstemeqcaselessblk). * @@ -1521,7 +1521,7 @@ bseof(const struct bStream *s); * * These are faster than using bfromcstr() and bcatcstr() respectively * because the length of the inline string is known as a compile time - * constant. Also note that seperate struct tagbstring declarations for + * constant. Also note that separate struct tagbstring declarations for */ #define bsStaticBlkParms(q) \ ((void *)("" q "")), ((int)sizeof(q) -1) diff --git a/modules/map/src/freedata.c b/modules/map/src/freedata.c index f875db98d0..062564d132 100644 --- a/modules/map/src/freedata.c +++ b/modules/map/src/freedata.c @@ -56,8 +56,8 @@ MAP_ERROR_CODE free_outlist(Domain* domain, char* map_msg, MAP_ERROR_CODE* ierr) list_iterator_stop(&domain->y_list->out_list_ptr); // @rm y_list->out_list no longer exists/is useful ? - list_destroy(&domain->y_list->out_list); /* destroy output lists for writting information to output file */ - list_destroy(&domain->y_list->out_list_ptr); /* destroy output lists for writting information to output file */ + list_destroy(&domain->y_list->out_list); /* destroy output lists for writing information to output file */ + list_destroy(&domain->y_list->out_list_ptr); /* destroy output lists for writing information to output file */ }; MAPFREE(domain->y_list); return MAP_SAFE; diff --git a/modules/map/src/lineroutines.c b/modules/map/src/lineroutines.c index ba89c7b5bd..de5f61939f 100644 --- a/modules/map/src/lineroutines.c +++ b/modules/map/src/lineroutines.c @@ -350,7 +350,7 @@ MAP_ERROR_CODE line_solve_sequence(Domain* domain, MAP_ParameterType_t* p_type, success = set_line_variables_pre_solve(domain, map_msg, ierr); success = reset_node_force_to_zero(domain, map_msg, ierr); success = solve_line(domain, t, map_msg, ierr); CHECKERRQ(MAP_FATAL_88); - // /* prematurely terminating the the line solve routine to return back to the + // /* prematurely terminating the line solve routine to return back to the // caller function. Do a back tracking on the solution and attempt recovery */ // if (success==MAP_FATAL) { // return MAP_FATAL_59; diff --git a/modules/map/src/mapapi.c b/modules/map/src/mapapi.c index ec86d8402a..69d47714b1 100644 --- a/modules/map/src/mapapi.c +++ b/modules/map/src/mapapi.c @@ -151,7 +151,7 @@ MAP_EXTERNCALL void map_init(MAP_InitInputType_t* init_type, MAP_END_ERROR_LOG; - /* the next functions are called in a seperate do-loop to log information to the + /* the next functions are called in a separate do-loop to log information to the * summary file even if a fatal error is encountered. This guarantees the summary * file is written even if garbage is recorded. */ @@ -159,7 +159,7 @@ MAP_EXTERNCALL void map_init(MAP_InitInputType_t* init_type, free_init_data(init_data, map_msg, ierr); MAP_InitInput_Delete(init_data); - if (*ierr!=MAP_SAFE) printf("Intialization: %s\n", map_msg); + if (*ierr!=MAP_SAFE) printf("Initialization: %s\n", map_msg); // checkpoint(); // printf("In initialization: %p\n",z_type); diff --git a/modules/map/src/mapapi.h b/modules/map/src/mapapi.h index 5d7134b1bf..4111f818e1 100644 --- a/modules/map/src/mapapi.h +++ b/modules/map/src/mapapi.h @@ -98,7 +98,7 @@ MAP_EXTERNCALL int free_init_data (MAP_InitializationData_t init, char* map_msg, /** * @brief Set the water depth. Should be called before {@link map_init()} - * @param p_type paramter type, native C struct {@link MAP_ParameterType_t} + * @param p_type parameter type, native C struct {@link MAP_ParameterType_t} * @param depth water depth [m] * * Example Fortran usage: @@ -123,7 +123,7 @@ MAP_EXTERNCALL void map_set_sea_depth(MAP_Parameter_t p_type, const double depth /** * @brief Set the water density. Should be called before {@link map_init()} - * @param p_type paramter type, native C struct {@link MAP_ParameterType_t} + * @param p_type parameter type, native C struct {@link MAP_ParameterType_t} * @param rho water density [kg/m^3] * * Example Fortran usage: @@ -148,7 +148,7 @@ MAP_EXTERNCALL void map_set_sea_density(MAP_Parameter_t p_type, const double rho /** * @brief Set the gravitational constant. Should be called before {@link map_init()} - * @param p_type paramter type, native C struct {@link MAP_ParameterType_t} + * @param p_type parameter type, native C struct {@link MAP_ParameterType_t} * @param grtavity gravitational acceleration [m/s^2] * * Example Fortran usage: diff --git a/modules/map/src/mapinit.h b/modules/map/src/mapinit.h index 2693c26171..bd3063827d 100644 --- a/modules/map/src/mapinit.h +++ b/modules/map/src/mapinit.h @@ -210,7 +210,7 @@ MAP_ERROR_CODE check_help_flag(bstring list); * inner_ftol * * @param list, a character array structure - * @param ftol, pointer to the FTOL paramter for minpack + * @param ftol, pointer to the FTOL parameter for minpack * @see set_model_options_list(), map_init() * @return MAP error code */ @@ -230,7 +230,7 @@ MAP_ERROR_CODE check_inner_f_tol_flag(struct bstrList* list, double* ftol); * inner_gtol * * @param list, a character array structure - * @param gtol, pointer to the GTOL paramter for minpack + * @param gtol, pointer to the GTOL parameter for minpack * @see set_model_options_list(), map_init() * @return MAP error code */ @@ -249,7 +249,7 @@ MAP_ERROR_CODE check_inner_g_tol_flag(struct bstrList* list, double* gtol); * inner_xtol * * @param list, a character array structure - * @param xtol, pointer to the XTOL paramter for minpack + * @param xtol, pointer to the XTOL parameter for minpack * @see set_model_options_list(), map_init() * @return MAP error code */ @@ -302,7 +302,7 @@ MAP_ERROR_CODE check_outer_max_its_flag(struct bstrList* list, int* max_its); * outer_tol * * @param list, a character array structure - * @param outer_tol, pointer to the tolerance paramter + * @param outer_tol, pointer to the tolerance parameter * @see set_model_options_list(), map_init() * @return MAP error code */ diff --git a/modules/map/src/simclist/simclist.h b/modules/map/src/simclist/simclist.h index c6463a8719..32b2a13d99 100644 --- a/modules/map/src/simclist/simclist.h +++ b/modules/map/src/simclist/simclist.h @@ -97,7 +97,7 @@ typedef int (*element_comparator)(const void *a, const void *b); typedef int (*element_seeker)(const void *el, const void *indicator); /** - * an element lenght meter. + * an element length meter. * * An element meter is a function that: * -# receives the reference to an element el diff --git a/modules/moordyn/src/MoorDyn.f90 b/modules/moordyn/src/MoorDyn.f90 index 0e1f1ae812..824002b248 100644 --- a/modules/moordyn/src/MoorDyn.f90 +++ b/modules/moordyn/src/MoorDyn.f90 @@ -2317,7 +2317,7 @@ SUBROUTINE MD_Init(InitInp, u, p, x, xd, z, other, y, m, DTcoupling, InitOut, Er ! rRef and OrMatRef or the position and orientation matrix of the ! coupled object relative to the platform, based on the input file. ! They are used to set the "reference" pose of each coupled mesh - ! entry before the intial offsets from PtfmInit are applied. + ! entry before the initial offsets from PtfmInit are applied. J = 0 ! this is the counter through the mesh points for each turbine @@ -2424,7 +2424,7 @@ SUBROUTINE MD_Init(InitInp, u, p, x, xd, z, other, y, m, DTcoupling, InitOut, Er end do ! iTurb - ! >>>>>> ensure the output mesh includes all elements from u%(Farm)CoupledKinematics, OR make a seperate array of output meshes for each turbine <<<<<<<<< + ! >>>>>> ensure the output mesh includes all elements from u%(Farm)CoupledKinematics, OR make a separate array of output meshes for each turbine <<<<<<<<< CALL CheckError( ErrStat2, ErrMsg2 ) @@ -2593,7 +2593,7 @@ SUBROUTINE MD_Init(InitInp, u, p, x, xd, z, other, y, m, DTcoupling, InitOut, Er ! if log file, compute and write some object properties ! ------------------------------------------------------------------- if (p%writeLog > 1) then - write(p%UnLog, '(A)' ) "Values after intialization before dynamic relaxation" + write(p%UnLog, '(A)' ) "Values after initialization before dynamic relaxation" write(p%UnLog, '(A)' ) " Bodies:" DO l = 1,p%nBodies write(p%UnLog, '(A)' ) " Body"//trim(num2lstr(l))//":" @@ -3859,7 +3859,7 @@ END SUBROUTINE MD_End !-------------------------------------------------------------- SUBROUTINE MD_RK2 ( t, dtM, u_interp, u, t_array, p, x, xd, z, other, m, ErrStat, ErrMsg ) - REAL(DbKi) , INTENT(INOUT) :: t ! intial time (s) for this integration step + REAL(DbKi) , INTENT(INOUT) :: t ! initial time (s) for this integration step REAL(DbKi) , INTENT(IN ) :: dtM ! single time step size (s) for this integration step TYPE( MD_InputType ) , INTENT(INOUT) :: u_interp ! interpolated instantaneous input values to be calculated for each mooring time step TYPE( MD_InputType ) , INTENT(INOUT) :: u(:) ! INTENT(IN ) @@ -4131,7 +4131,7 @@ SUBROUTINE MD_JacobianPInput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrM ! get central difference: ! we may have had an error allocating memory, so we'll check if(Failed()) return - ! get central difference (state entries are mapped the the dXdu column in routine): + ! get central difference (state entries are mapped to the dXdu column in routine): call MD_Compute_dX( p, x_p, x_m, delta_p, dXdu(:,i) ) end do END IF ! dXdu diff --git a/modules/moordyn/src/MoorDyn_Driver.f90 b/modules/moordyn/src/MoorDyn_Driver.f90 index 1e7e5950f7..9a2d97b528 100644 --- a/modules/moordyn/src/MoorDyn_Driver.f90 +++ b/modules/moordyn/src/MoorDyn_Driver.f90 @@ -108,8 +108,8 @@ PROGRAM MoorDyn_Driver REAL(ReKi) :: PrevClockTime !< Previous clock time in seconds past midnight INTEGER :: SimStrtTime (8) !< An array containing the elements of the start time (after initialization). INTEGER :: ProgStrtTime (8) !< An array containing the elements of the program start time (before initialization). - REAL(ReKi) :: SimStrtCPU !< User CPU time for simulation (without intialization) - REAL(ReKi) :: ProgStrtCPU !< User CPU time for program (with intialization) + REAL(ReKi) :: SimStrtCPU !< User CPU time for simulation (without initialization) + REAL(ReKi) :: ProgStrtCPU !< User CPU time for program (with initialization) CHARACTER(20) :: FlagArg ! flag argument from command line diff --git a/modules/moordyn/src/MoorDyn_Misc.f90 b/modules/moordyn/src/MoorDyn_Misc.f90 index bf26a7ab1b..39da747167 100644 --- a/modules/moordyn/src/MoorDyn_Misc.f90 +++ b/modules/moordyn/src/MoorDyn_Misc.f90 @@ -189,7 +189,7 @@ SUBROUTINE TransformKinematics(rRelBody, r_in, TransMat, rd_in, r_out, rd_out) ! rd_in should be in global orientation frame ! note: it's okay if r_out and rd_out are 6-size. Only the first 3 will be written, and 4-6 will - ! already be correct or can be assigned seperately from r_in and rd_in (assuming orientation frames are identical) + ! already be correct or can be assigned separately from r_in and rd_in (assuming orientation frames are identical) ! locations (unrotated reference frame) about platform reference point (2021-01-05: just transposed TransMat, it was incorrect before) @@ -246,7 +246,7 @@ SUBROUTINE TransformKinematicsA(rRelBody, r_in, TransMat, v_in, a_in, r_out, v_o ! rd_in should be in global orientation frame ! note: it's okay if r_out and rd_out are 6-size. Only the first 3 will be written, and 4-6 will - ! already be correct or can be assigned seperately from r_in and rd_in (assuming orientation frames are identical) + ! already be correct or can be assigned separately from r_in and rd_in (assuming orientation frames are identical) ! locations about ref point in *unrotated* reference frame @@ -1306,7 +1306,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) INTEGER(IntKi) :: NStepWave ! INTEGER(IntKi) :: NStepWave2 ! - REAL(SiKi) :: WaveTMax ! max wave elevation time series duration after optimizing lenght for FFT + REAL(SiKi) :: WaveTMax ! max wave elevation time series duration after optimizing length for FFT REAL(SiKi) :: WaveDOmega REAL(SiKi) :: SinWaveDir ! SIN( WaveDirArr(I) ) -- Each wave frequency has a unique wave direction. REAL(SiKi) :: CosWaveDir ! COS( WaveDirArr(I) ) -- Each wave frequency has a unique wave direction. @@ -1589,11 +1589,11 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ! Initialize the FFT CALL InitFFT ( NStepWave, FFT_Data, .FALSE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName); if(Failed()) return + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName); if(Failed()) return ! Apply the forward FFT to get the real and imaginary parts of the frequency information. CALL ApplyFFT_f ( TmpFFTWaveElev(:), FFT_Data, ErrStatTmp ) ! Note that the TmpFFTWaveElev now contains the real and imaginary bits. - CALL SetErrStat(ErrStatTmp,'Error occured while applying the forwards FFT to TmpFFTWaveElev array.',ErrStat,ErrMsg,RoutineName); if(Failed()) return + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the forwards FFT to TmpFFTWaveElev array.',ErrStat,ErrMsg,RoutineName); if(Failed()) return ! Copy the resulting TmpFFTWaveElev(:) data over to the WaveElevC0 array DO I=1,NStepWave2-1 @@ -1603,7 +1603,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) WaveElevC0(:,NStepWave2) = 0.0_SiKi CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName); if(Failed()) return + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName); if(Failed()) return IF (ALLOCATED( WaveElev0 )) DEALLOCATE( WaveElev0 , STAT=ErrStatTmp) @@ -1641,7 +1641,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ! set up FFTer for doing IFFTs CALL InitFFT ( NStepWave, FFT_Data, .TRUE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.', ErrStat, ErrMsg, routineName); if(Failed()) return + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.', ErrStat, ErrMsg, routineName); if(Failed()) return ! Loop through all points where the incident wave kinematics will be computed do ix = 1,p%nxWave @@ -1683,7 +1683,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ! could also reproduce the wave elevation at 0,0,0 on a separate channel for verification... CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the IFFTs.', ErrStat,ErrMsg,RoutineName); if(Failed()) return + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the IFFTs.', ErrStat,ErrMsg,RoutineName); if(Failed()) return end if ! p%WaveKin == 3 diff --git a/modules/moordyn/src/MoorDyn_Registry.txt b/modules/moordyn/src/MoorDyn_Registry.txt index a6c9beb996..0dde564a9f 100644 --- a/modules/moordyn/src/MoorDyn_Registry.txt +++ b/modules/moordyn/src/MoorDyn_Registry.txt @@ -96,7 +96,7 @@ typedef ^ ^ IntKi nAttachedC - typedef ^ ^ IntKi nAttachedR - - - "number of attached rods" typedef ^ ^ DbKi rPointRel {3}{30} - - "relative position of point on body" typedef ^ ^ DbKi r6RodRel {6}{30} - - "relative position and orientation of rod on body" -typedef ^ ^ DbKi bodyM - - - "body mass (seperate from attached objects)" "[kg]" +typedef ^ ^ DbKi bodyM - - - "body mass (separate from attached objects)" "[kg]" typedef ^ ^ DbKi bodyV - - - "body volume (for buoyancy calculation)" "[m^3]" typedef ^ ^ DbKi bodyI {3} - - "body 3x3 inertia matrix diagonals" "[kg-m^2]" typedef ^ ^ DbKi bodyCdA {6} - - "product of drag force and frontal area of body" "[m^2]" diff --git a/modules/moordyn/src/MoorDyn_Types.f90 b/modules/moordyn/src/MoorDyn_Types.f90 index 601ff63433..70975aa5d3 100644 --- a/modules/moordyn/src/MoorDyn_Types.f90 +++ b/modules/moordyn/src/MoorDyn_Types.f90 @@ -113,7 +113,7 @@ MODULE MoorDyn_Types INTEGER(IntKi) :: nAttachedR = 0_IntKi !< number of attached rods [-] REAL(DbKi) , DIMENSION(1:3,1:30) :: rPointRel = 0.0_R8Ki !< relative position of point on body [-] REAL(DbKi) , DIMENSION(1:6,1:30) :: r6RodRel = 0.0_R8Ki !< relative position and orientation of rod on body [-] - REAL(DbKi) :: bodyM = 0.0_R8Ki !< body mass (seperate from attached objects) [[kg]] + REAL(DbKi) :: bodyM = 0.0_R8Ki !< body mass (separate from attached objects) [[kg]] REAL(DbKi) :: bodyV = 0.0_R8Ki !< body volume (for buoyancy calculation) [[m^3]] REAL(DbKi) , DIMENSION(1:3) :: bodyI = 0.0_R8Ki !< body 3x3 inertia matrix diagonals [[kg-m^2]] REAL(DbKi) , DIMENSION(1:6) :: bodyCdA = 0.0_R8Ki !< product of drag force and frontal area of body [[m^2]] diff --git a/modules/nwtc-library/src/NWTC_IO.f90 b/modules/nwtc-library/src/NWTC_IO.f90 index 241a7bc672..204db312bf 100644 --- a/modules/nwtc-library/src/NWTC_IO.f90 +++ b/modules/nwtc-library/src/NWTC_IO.f90 @@ -7456,7 +7456,7 @@ SUBROUTINE WrMatrix2R8( A, Un, ReFmt, MatName ) END SUBROUTINE WrMatrix2R8 !======================================================================= !> Based on nwtc_io::wrmatrix, this routine writes a matrix to an already-open text file. It allows -!! the user to omit rows and columns of A in the the file. +!! the user to omit rows and columns of A in the file. !! Use WrPartialMatrix (nwtc_io::wrpartialmatrix) instead of directly calling a specific routine in the generic interface. SUBROUTINE WrPartialMatrix1R8( A, Un, ReFmt, MatName, UseCol, UseAllCols, ExtCol ) diff --git a/modules/nwtc-library/src/NWTC_Num.f90 b/modules/nwtc-library/src/NWTC_Num.f90 index 97284cde29..928321affb 100644 --- a/modules/nwtc-library/src/NWTC_Num.f90 +++ b/modules/nwtc-library/src/NWTC_Num.f90 @@ -1490,7 +1490,7 @@ END SUBROUTINE DCM_logMapR !! Use DCM_SetLogMapForInterp (nwtc_num::dcm_setlogmapforinterp) instead of directly calling a specific routine in the generic interface. SUBROUTINE DCM_SetLogMapForInterpD( tensor ) - REAL(DbKi), INTENT(INOUT) :: tensor(:,:) !< a 3xn matrix, whose columns represent individual skew-symmmetric matrices. On exit, + REAL(DbKi), INTENT(INOUT) :: tensor(:,:) !< a 3xn matrix, whose columns represent individual skew-symmetric matrices. On exit, !! each column will be within \f$2\pi\f$ of the previous column, allowing for interpolation !! of the quantities. @@ -2814,7 +2814,7 @@ FUNCTION GetSmllRotAngsR ( DCMat, ErrStat, ErrMsg ) END FUNCTION GetSmllRotAngsR !======================================================================= -!> This funtion returns the non-dimensional (-1:+1) location of the given Gauss-Legendre Quadrature point and its weight. +!> This function returns the non-dimensional (-1:+1) location of the given Gauss-Legendre Quadrature point and its weight. !! It works for NPts \f$\in \left[{1,6\right]\f$. !! The values came from Carnahan, Brice; Luther, H.A.; Wilkes, James O. (1969) "Applied Numerical Methods." SUBROUTINE GL_Pts ( IPt, NPts, Loc, Wt, ErrStat, ErrMsg ) @@ -2937,7 +2937,7 @@ SUBROUTINE GL_Pts ( IPt, NPts, Loc, Wt, ErrStat, ErrMsg ) RETURN END SUBROUTINE GL_Pts ! ( IPt, NPts, Loc, Wt [, ErrStat] ) !======================================================================= -!> This funtion returns an integer index such that CAry(IndexCharAry) = CVal. If +!> This function returns an integer index such that CAry(IndexCharAry) = CVal. If !! no element in the array matches CVal, the value -1 is returned. The routine !! performs a binary search on the input array to determine if CVal is an !! element of the array; thus, CAry must be sorted and stored in increasing @@ -3002,7 +3002,7 @@ FUNCTION IndexCharAry( CVal, CAry ) END FUNCTION IndexCharAry !======================================================================= -!> This funtion returns a y-value that corresponds to an input x-value by interpolating into the arrays. +!> This function returns a y-value that corresponds to an input x-value by interpolating into the arrays. !! It uses a binary interpolation scheme that takes about log(AryLen) / log(2) steps to converge. !! It returns the first or last YAry() value if XVal is outside the limits of XAry(). !! @@ -3131,7 +3131,7 @@ FUNCTION InterpBinReal( XVal, XAry, YAry, ILo, AryLen ) RETURN END FUNCTION InterpBinReal ! ( XVal, XAry, YAry, ILo, AryLen ) !======================================================================= -!> This funtion returns a y-value that corresponds to an input x-value by interpolating into the arrays. +!> This function returns a y-value that corresponds to an input x-value by interpolating into the arrays. !! It uses the passed index as the starting point and does a stepwise interpolation from there. This is !! especially useful when the calling routines save the value from the last time this routine was called !! for a given case where XVal does not change much from call to call. When there is no correlation @@ -3505,7 +3505,7 @@ FUNCTION InterpStpReal8( XVal, XAry, YAry, Ind, AryLen ) END FUNCTION InterpStpReal8 !======================================================================= -!> This funtion returns a y-value array that corresponds to an input x-value by interpolating into the arrays. +!> This function returns a y-value array that corresponds to an input x-value by interpolating into the arrays. !! It uses the passed index as the starting point and does a stepwise interpolation from there. This is !! especially useful when the calling routines save the value from the last time this routine was called !! for a given case where XVal does not change much from call to call. @@ -3568,7 +3568,7 @@ SUBROUTINE InterpStpMat4( XVal, XAry, Y, Ind, AryLen, yInterp ) RETURN END SUBROUTINE InterpStpMat4 !======================================================================= -!> This funtion returns a y-value array that corresponds to an input x-value by interpolating into the arrays. +!> This function returns a y-value array that corresponds to an input x-value by interpolating into the arrays. !! It uses the passed index as the starting point and does a stepwise interpolation from there. This is !! especially useful when the calling routines save the value from the last time this routine was called !! for a given case where XVal does not change much from call to call. @@ -3869,7 +3869,7 @@ SUBROUTINE InterpStpReal3D( InCoord, Dataset, x, y, z, LastIndex, InterpData ) END SUBROUTINE InterpStpReal3D !======================================================================= -!> This funtion returns a y-value that corresponds to an input x-value which is wrapped back +!> This function returns a y-value that corresponds to an input x-value which is wrapped back !! into the range [0-XAry(AryLen)] by interpolating into the arrays. !! It is assumed that XAry is sorted in ascending order. !! It uses the passed index as the starting point and does a stepwise interpolation from there. This is @@ -4674,7 +4674,7 @@ FUNCTION PSF ( Npsf, NumPrimes, subtract ) ELSE - NPr = NPrime(IPR) ! The small prime number we will try to find the the factorization of NTR + NPr = NPrime(IPR) ! The small prime number we will try to find the factorization of NTR DO NT = NTR/NPr ! Doing some modular arithmetic to see if @@ -5420,7 +5420,7 @@ SUBROUTINE RunTimes( StrtTime, UsrTime1, SimStrtTime, UsrTime2, ZTime, UnSum, Us INTEGER , INTENT(IN) :: StrtTime (8) !< Start time of simulation (including initialization) INTEGER , INTENT(IN) :: SimStrtTime (8) !< Start time of simulation (after initialization) REAL(ReKi), INTENT(IN) :: UsrTime1 !< User CPU time for simulation initialization. - REAL(ReKi), INTENT(IN) :: UsrTime2 !< User CPU time for simulation (without intialization) + REAL(ReKi), INTENT(IN) :: UsrTime2 !< User CPU time for simulation (without initialization) REAL(DbKi), INTENT(IN) :: ZTime !< The final simulation time (not necessarially TMax) INTEGER(IntKi), INTENT(IN), OPTIONAL:: UnSum !< optional unit number of file. If present and > 0, REAL(ReKi), INTENT(OUT),OPTIONAL:: UsrTime_out !< User CPU time for entire run - optional value returned to calling routine @@ -5634,7 +5634,7 @@ SUBROUTINE SimStatus_FirstTime( PrevSimTime, PrevClockTime, SimStrtTime, UsrTime REAL(DbKi), INTENT( OUT) :: PrevSimTime !< Previous time message was written to screen (s > 0) REAL(ReKi), INTENT( OUT) :: PrevClockTime !< Previous clock time in seconds past midnight INTEGER, INTENT( OUT) :: SimStrtTime (8) !< An array containing the elements of the start time. - REAL(ReKi), INTENT( OUT) :: UsrTimeSim !< User CPU time for simulation (without intialization) + REAL(ReKi), INTENT( OUT) :: UsrTimeSim !< User CPU time for simulation (without initialization) CHARACTER(*), INTENT(IN), OPTIONAL :: DescStrIn !< optional additional string to print for SimStatus diff --git a/modules/nwtc-library/src/NetLib/scalapack/dlasrt2.f b/modules/nwtc-library/src/NetLib/scalapack/dlasrt2.f index b134da5c36..c063a923b7 100644 --- a/modules/nwtc-library/src/NetLib/scalapack/dlasrt2.f +++ b/modules/nwtc-library/src/NetLib/scalapack/dlasrt2.f @@ -75,7 +75,7 @@ SUBROUTINE DLASRT2( ID, N, D, KEY, INFO ) * .. * .. Executable Statements .. * -* Test the input paramters. +* Test the input parameters. * * INFO = 0 diff --git a/modules/nwtc-library/src/NetLib/scalapack/slasrt2.f b/modules/nwtc-library/src/NetLib/scalapack/slasrt2.f index 7c4b9ce2d2..fa725eb506 100644 --- a/modules/nwtc-library/src/NetLib/scalapack/slasrt2.f +++ b/modules/nwtc-library/src/NetLib/scalapack/slasrt2.f @@ -75,7 +75,7 @@ SUBROUTINE SLASRT2( ID, N, D, KEY, INFO ) * .. * .. Executable Statements .. * -* Test the input paramters. +* Test the input parameters. * * INFO = 0 diff --git a/modules/openfast-library/src/FAST_Registry.txt b/modules/openfast-library/src/FAST_Registry.txt index 2cbaa53e41..64c972b54d 100644 --- a/modules/openfast-library/src/FAST_Registry.txt +++ b/modules/openfast-library/src/FAST_Registry.txt @@ -817,8 +817,8 @@ typedef ^ FAST_MiscVarType DbKi t_global - - - "Current simulation time (for glo typedef ^ FAST_MiscVarType DbKi NextJacCalcTime - - - "Time between calculating Jacobians in the HD-ED and SD-ED simulations" (s) typedef ^ FAST_MiscVarType ReKi PrevClockTime - - - "Clock time at start of simulation in seconds" (s) typedef ^ FAST_MiscVarType ReKi UsrTime1 - - - "User CPU time for simulation initialization" (s) -typedef ^ FAST_MiscVarType ReKi UsrTime2 - - - "User CPU time for simulation (without intialization)" (s) -typedef ^ FAST_MiscVarType INTEGER StrtTime {8} - - "Start time of simulation (including intialization)" +typedef ^ FAST_MiscVarType ReKi UsrTime2 - - - "User CPU time for simulation (without initialization)" (s) +typedef ^ FAST_MiscVarType INTEGER StrtTime {8} - - "Start time of simulation (including initialization)" typedef ^ FAST_MiscVarType INTEGER SimStrtTime {8} - - "Start time of simulation (after initialization)" #typedef ^ FAST_MiscVarType IntKi n_t_global - - - "simulation time step, loop counter for global (FAST) simulation" (s) typedef ^ FAST_MiscVarType Logical calcJacobian - - - "Should we calculate Jacobians in Option 1?" (flag) diff --git a/modules/openfast-library/src/FAST_Solver.f90 b/modules/openfast-library/src/FAST_Solver.f90 index 618d53ee01..4d0ee9910f 100644 --- a/modules/openfast-library/src/FAST_Solver.f90 +++ b/modules/openfast-library/src/FAST_Solver.f90 @@ -4602,7 +4602,7 @@ SUBROUTINE InitModuleMappings(p_FAST, ED, SED, BD, AD, ADsk, ExtLd, HD, SD, ExtP RETURN END IF - ! Create the the mesh mapping for mapping between ED and ExtLoad blade root meshes + ! Create the mesh mapping for mapping between ED and ExtLoad blade root meshes DO K=1,NumBl CALL MeshMapCreate( ED%y%BladeRootMotion(K), ExtLd%u%BladeRootMotion(K), MeshMapData%ED_P_2_ExtLd_P_R(K), ErrStat2, ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName//':ED_P_2_ExtLd_P_R('//TRIM(Num2LStr(K))//')' ) diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index 1b0050734c..79f5f7c4f2 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -198,7 +198,7 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, SED, BD, S END IF ! ... Open and read input files ... - ! also, set applicable farm paramters and turbine reference position also for graphics output + ! also, set applicable farm parameters and turbine reference position also for graphics output p_FAST%UseSC = .FALSE. if (PRESENT(ExternInitData)) then p_FAST%FarmIntegration = ExternInitData%FarmIntegration @@ -2479,7 +2479,7 @@ SUBROUTINE FAST_InitOutput( p_FAST, y_FAST, Init, ErrStat, ErrMsg ) !...................................................... ! Set the number of output columns from each module !...................................................... - y_FAST%numOuts = 0 ! Inintialize entire array + y_FAST%numOuts = 0 ! Initialize entire array IF ( ALLOCATED( Init%OutData_IfW%WriteOutputHdr ) ) y_FAST%numOuts(Module_IfW) = SIZE(Init%OutData_IfW%WriteOutputHdr) IF ( ALLOCATED( Init%OutData_ExtInfw%WriteOutputHdr ) ) y_FAST%numOuts(Module_ExtInfw) = SIZE(Init%OutData_ExtInfw%WriteOutputHdr) diff --git a/modules/openfast-library/src/FAST_Types.f90 b/modules/openfast-library/src/FAST_Types.f90 index 125d2a0643..3c78cd659f 100644 --- a/modules/openfast-library/src/FAST_Types.f90 +++ b/modules/openfast-library/src/FAST_Types.f90 @@ -827,8 +827,8 @@ MODULE FAST_Types REAL(DbKi) :: NextJacCalcTime = 0.0_R8Ki !< Time between calculating Jacobians in the HD-ED and SD-ED simulations [(s)] REAL(ReKi) :: PrevClockTime = 0.0_ReKi !< Clock time at start of simulation in seconds [(s)] REAL(ReKi) :: UsrTime1 = 0.0_ReKi !< User CPU time for simulation initialization [(s)] - REAL(ReKi) :: UsrTime2 = 0.0_ReKi !< User CPU time for simulation (without intialization) [(s)] - INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime = 0_IntKi !< Start time of simulation (including intialization) [-] + REAL(ReKi) :: UsrTime2 = 0.0_ReKi !< User CPU time for simulation (without initialization) [(s)] + INTEGER(IntKi) , DIMENSION(1:8) :: StrtTime = 0_IntKi !< Start time of simulation (including initialization) [-] INTEGER(IntKi) , DIMENSION(1:8) :: SimStrtTime = 0_IntKi !< Start time of simulation (after initialization) [-] LOGICAL :: calcJacobian = .false. !< Should we calculate Jacobians in Option 1? [(flag)] TYPE(FAST_ExternInputType) :: ExternInput !< external input values [-] diff --git a/modules/orcaflex-interface/src/OrcaDriver.f90 b/modules/orcaflex-interface/src/OrcaDriver.f90 index 667e588cd4..5addc01640 100644 --- a/modules/orcaflex-interface/src/OrcaDriver.f90 +++ b/modules/orcaflex-interface/src/OrcaDriver.f90 @@ -355,7 +355,7 @@ PROGRAM OrcaDriver Orca_y, Orca_m, Settings%DT, Orca_InitOut, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -447,7 +447,7 @@ PROGRAM OrcaDriver - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -505,7 +505,7 @@ PROGRAM OrcaDriver Orca_y, Orca_m, ErrStat, ErrMsg) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -535,7 +535,7 @@ PROGRAM OrcaDriver TimeNow, Orca_InitOut, Orca_p, Orca_u, Orca_y, ErrStat, ErrMsg ) CLOSE(TmpUnit) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -583,7 +583,7 @@ PROGRAM OrcaDriver IF ( SettingsFlags%AddedMassFile ) THEN CALL AddedMass_OutputWrite( Settings, SettingsFlags%AddedMassOutputInit, & Orca_m%PtfmAM, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) @@ -611,7 +611,7 @@ PROGRAM OrcaDriver Orca_x, Orca_xd, Orca_z, Orca_OtherState, & Orca_y, Orca_m, ErrStat, ErrMsg ) - ! Make sure no errors occured that give us reason to terminate now. + ! Make sure no errors occurred that give us reason to terminate now. IF ( ErrStat >= AbortErrLev ) THEN CALL DriverCleanup() CALL ProgAbort( ErrMsg ) diff --git a/modules/seastate/src/SeaState_DriverCode.f90 b/modules/seastate/src/SeaState_DriverCode.f90 index 885a1f50e7..53e33165f3 100644 --- a/modules/seastate/src/SeaState_DriverCode.f90 +++ b/modules/seastate/src/SeaState_DriverCode.f90 @@ -89,11 +89,11 @@ program SeaStateDriver character(1024) :: drvrFilename ! Filename and path for the driver input file. This is passed in as a command line argument when running the Driver exe. type(SeaSt_Drvr_InitInput) :: drvrInitInp ! Initialization data for the driver program - integer :: StrtTime (8) ! Start time of simulation (including intialization) + integer :: StrtTime (8) ! Start time of simulation (including initialization) integer :: SimStrtTime (8) ! Start time of simulation (after initialization) real(ReKi) :: PrevClockTime ! Clock time at start of simulation in seconds real(ReKi) :: UsrTime1 ! User CPU time for simulation initialization - real(ReKi) :: UsrTime2 ! User CPU time for simulation (without intialization) + real(ReKi) :: UsrTime2 ! User CPU time for simulation (without initialization) real(DbKi) :: TiLstPrn ! The simulation time of the last print real(DbKi) :: t_global ! Current simulation time (for global/FAST simulation) real(DbKi) :: SttsTime ! Amount of time between screen status messages (sec) diff --git a/modules/seastate/src/UserWaves.f90 b/modules/seastate/src/UserWaves.f90 index 1ff95fef81..454ad5ca7c 100644 --- a/modules/seastate/src/UserWaves.f90 +++ b/modules/seastate/src/UserWaves.f90 @@ -367,7 +367,7 @@ SUBROUTINE UserWaveElevations_Init ( InitInp, InitOut, WaveField, ErrStat, ErrMs ! Initialize the FFT CALL InitFFT ( WaveField%NStepWave, FFT_Data, .FALSE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -375,7 +375,7 @@ SUBROUTINE UserWaveElevations_Init ( InitInp, InitOut, WaveField, ErrStat, ErrMs ! Apply the forward FFT to get the real and imaginary parts of the frequency information. CALL ApplyFFT_f ( TmpFFTWaveElev(:), FFT_Data, ErrStatTmp ) ! Note that the TmpFFTWaveElev now contains the real and imaginary bits. - CALL SetErrStat(ErrStatTmp,'Error occured while applying the forwards FFT to TmpFFTWaveElev array.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the forwards FFT to TmpFFTWaveElev array.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -389,7 +389,7 @@ SUBROUTINE UserWaveElevations_Init ( InitInp, InitOut, WaveField, ErrStat, ErrMs WaveField%WaveElevC0(:,WaveField%NStepWave2) = 0.0_SiKi CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN diff --git a/modules/seastate/src/Waves.f90 b/modules/seastate/src/Waves.f90 index 405b35e2ab..f4580fa0f7 100644 --- a/modules/seastate/src/Waves.f90 +++ b/modules/seastate/src/Waves.f90 @@ -900,7 +900,7 @@ SUBROUTINE VariousWaves_Init ( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) ! make sure this is called before calling ConstrainedNewWaves CALL InitFFT ( WaveField%NStepWave, FFT_Data, .TRUE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -1106,7 +1106,7 @@ SUBROUTINE VariousWaves_Init ( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) END IF CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -1319,7 +1319,7 @@ logical function Failed0(TmpName) end function logical function FailedFFT(TmpName) character(*), intent(in) :: TmpName - CALL SetErrStat( ErrStatTmp, 'Error occured while applying the FFT to '//trim(TmpName), ErrStat, ErrMsg, RoutineName ) + CALL SetErrStat( ErrStatTmp, 'Error occurred while applying the FFT to '//trim(TmpName), ErrStat, ErrMsg, RoutineName ) FailedFFT = ErrStat >= AbortErrLev if (FailedFFT) CALL Cleanup() end function @@ -1355,7 +1355,7 @@ SUBROUTINE WaveElevTimeSeriesAtXY(Xcoord,Ycoord, WaveElevAtXY, WaveElevCAtXY, tm ENDDO CALL ApplyFFT_cx ( WaveElevAtXY(0:WaveField%NStepWave-1), tmpComplexArr, FFT_Data, ErrStatLcl2 ) - CALL SetErrStat(ErrStatLcl2,'Error occured while applying the FFT.',ErrStatLcl,ErrMsgLcl,'WaveElevTimeSeriesAtXY') + CALL SetErrStat(ErrStatLcl2,'Error occurred while applying the FFT.',ErrStatLcl,ErrMsgLcl,'WaveElevTimeSeriesAtXY') WaveElevCAtXY( 1,: ) = REAL(tmpComplexArr(:)) WaveElevCAtXY( 2,: ) = AIMAG(tmpComplexArr(:)) @@ -2239,7 +2239,7 @@ SUBROUTINE ConstrainedNewWaves(InitInp, InitOut, WaveField, OmegaArr, WaveS1SddA tmpComplexArr = CMPLX( WaveField%WaveElevC0(1,:) + Crest * tmpArr, & WaveField%WaveElevC0(2,:)) CALL ApplyFFT_cx ( WaveField%WaveElev0 (0:WaveField%NStepWave-1), tmpComplexArr (: ), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) RETURN ! Find the preceding or following trough, whichever is lower @@ -2254,7 +2254,7 @@ SUBROUTINE ConstrainedNewWaves(InitInp, InitOut, WaveField, OmegaArr, WaveS1SddA tmpComplexArr = CMPLX( WaveField%WaveElevC0(1,:) + (Crest+CrestHeightTol) * tmpArr, & WaveField%WaveElevC0(2,:)) CALL ApplyFFT_cx ( WaveField%WaveElev0 (0:WaveField%NStepWave-1), tmpComplexArr (: ), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to WaveElev0.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) RETURN diff --git a/modules/seastate/src/Waves2.f90 b/modules/seastate/src/Waves2.f90 index f7edb77883..b8c985dafb 100644 --- a/modules/seastate/src/Waves2.f90 +++ b/modules/seastate/src/Waves2.f90 @@ -395,7 +395,7 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) !-------------------------------------------------------------------------------- CALL InitFFT ( WaveField%NStepWave, FFT_Data, .FALSE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while initializing the FFT.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -495,7 +495,7 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) i = mod(k-1, InitInp%NGrid(1)) + 1 j = (k-1) / InitInp%NGrid(1) + 1 CALL WaveElevTimeSeriesAtXY_Diff(InitInp%WaveKinGridxi(k), InitInp%WaveKinGridyi(k), TmpTimeSeries, ErrStatTmp, ErrMsgTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to WaveField%WaveElev2.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to WaveField%WaveElev2.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -639,21 +639,21 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) !> ### Apply the inverse FFT to each of the components to get the time domain result ### !> * \f$ V(t) = 2 \operatorname{IFFT}\left[H^-\right] \f$ CALL ApplyFFT_cx( WaveVel2xDiff(:), WaveVel2xCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2yDiff(:), WaveVel2yCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2zDiff(:), WaveVel2zCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2xDiff(:), WaveAcc2xCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2yDiff(:), WaveAcc2yCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2zDiff(:), WaveAcc2zCDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveDynP2Diff(:), WaveDynP2CDiff(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) @@ -858,7 +858,7 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) i = mod(k-1, InitInp%NGrid(1)) + 1 j = (k-1) / InitInp%NGrid(1) + 1 CALL WaveElevTimeSeriesAtXY_Sum(InitInp%WaveKinGridxi(k), InitInp%WaveKinGridyi(k), TmpTimeSeries, ErrStatTmp, ErrMsgTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT to WaveField%WaveElev2.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT to WaveField%WaveElev2.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -1124,38 +1124,38 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) !> * \f$ V^{(2)+}(t) = \operatorname{IFFT}\left[K^+\right] !! + 2\operatorname{IFFT}\left[H^+\right] \f$ CALL ApplyFFT_cx( WaveVel2xSumT1(:), WaveVel2xCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2ySumT1(:), WaveVel2yCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2zSumT1(:), WaveVel2zCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2xSumT1(:), WaveAcc2xCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2ySumT1(:), WaveAcc2yCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2zSumT1(:), WaveAcc2zCSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveDynP2SumT1(:), WaveDynP2CSumT1(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2xSumT2(:), WaveVel2xCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2ySumT2(:), WaveVel2yCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveVel2zSumT2(:), WaveVel2zCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on V_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2xSumT2(:), WaveAcc2xCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_x.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2ySumT2(:), WaveAcc2yCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_y.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveAcc2zSumT2(:), WaveAcc2zCSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on Acc_z.',ErrStat,ErrMsg,RoutineName) CALL ApplyFFT_cx( WaveDynP2SumT2(:), WaveDynP2CSumT2(:), FFT_Data, ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occured while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while applying the FFT on DynP2.',ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() @@ -1236,7 +1236,7 @@ SUBROUTINE Waves2_Init( InitInp, InitOut, WaveField, ErrStat, ErrMsg ) CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occured while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) + CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName) IF ( ErrStat >= AbortErrLev ) THEN CALL CleanUp() RETURN @@ -1376,7 +1376,7 @@ SUBROUTINE WaveElevTimeSeriesAtXY_Diff(Xcoord,Ycoord, WaveElevSeriesAtXY, ErrSta !> ### Apply the inverse FFT to each of the components to get the time domain result ### !> * \f$ \eta(t) = \operatorname{IFFT}\left[2 H^-\right] \f$ CALL ApplyFFT_cx( WaveElevSeriesAtXY(:), TmpFreqSeries(:), FFT_Data, ErrStatLcl2 ) - CALL SetErrStat(ErrStatLcl2,'Error occured while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Diff') + CALL SetErrStat(ErrStatLcl2,'Error occurred while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Diff') ! Append first datapoint as the last as aid for repeated wave data WaveElevSeriesAtXY(WaveField%NStepWave) = WaveElevSeriesAtXY(0) @@ -1563,9 +1563,9 @@ SUBROUTINE WaveElevTimeSeriesAtXY_Sum(Xcoord,Ycoord, WaveElevSeriesAtXY, ErrStat !> * \f$ \eta^{(2)+}(t) = \operatorname{IFFT}\left[K^+\right] !! + 2\operatorname{IFFT}\left[H^+\right] \f$ CALL ApplyFFT_cx( WaveElevSeriesAtXY(:), TmpFreqSeries(:), FFT_Data, ErrStatLcl2 ) - CALL SetErrStat(ErrStatLcl2,'Error occured while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Sum') + CALL SetErrStat(ErrStatLcl2,'Error occurred while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Sum') CALL ApplyFFT_cx( TmpTimeSeries2(:), TmpFreqSeries2(:), FFT_Data, ErrStatLcl2 ) - CALL SetErrStat(ErrStatLcl2,'Error occured while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Sum') + CALL SetErrStat(ErrStatLcl2,'Error occurred while applying the FFT on WaveElevSeriesAtXY.',ErrStatLcl,ErrMsgLcl,'WaveElevSeriesAtXY_Sum') ! Add the two terms together DO Ctr=0,WaveField%NStepWave diff --git a/modules/servodyn/src/BladedInterface_EX.f90 b/modules/servodyn/src/BladedInterface_EX.f90 index 37e77d0978..4eee05fe9e 100644 --- a/modules/servodyn/src/BladedInterface_EX.f90 +++ b/modules/servodyn/src/BladedInterface_EX.f90 @@ -680,10 +680,10 @@ subroutine Retrieve_EXavrSWAP_StControls () ! Retrieve StC control channels here do I=1,p%NumStC_Control J=StCCtrl_StartIdx + ((I-1)*StCCtrl_ChanPerSet-1) ! Index into the full avrSWAP (minus 1 so counting is simpler) - dll_data%StCCmdStiff(1:3,I) = dll_data%avrswap(J+ 7:J+ 9) ! StC commmanded stiffness -- StC_Stiff_X, StC_Stiff_Y, StC_Stiff_Z (N/m) - dll_data%StCCmdDamp( 1:3,I) = dll_data%avrswap(J+10:J+12) ! StC commmanded damping -- StC_Damp_X, StC_Damp_Y, StC_Damp_Z (N/(m/s)) - dll_data%StCCmdBrake(1:3,I) = dll_data%avrswap(J+13:J+15) ! StC commmanded brake -- StC_Brake_X, StC_Brake_Y, StC_Brake_Z (N) - dll_data%StCCmdForce(1:3,I) = dll_data%avrswap(J+16:J+18) ! StC commmanded brake -- StC_Force_X, StC_Force_Y, StC_Force_Z (N) + dll_data%StCCmdStiff(1:3,I) = dll_data%avrswap(J+ 7:J+ 9) ! StC commanded stiffness -- StC_Stiff_X, StC_Stiff_Y, StC_Stiff_Z (N/m) + dll_data%StCCmdDamp( 1:3,I) = dll_data%avrswap(J+10:J+12) ! StC commanded damping -- StC_Damp_X, StC_Damp_Y, StC_Damp_Z (N/(m/s)) + dll_data%StCCmdBrake(1:3,I) = dll_data%avrswap(J+13:J+15) ! StC commanded brake -- StC_Brake_X, StC_Brake_Y, StC_Brake_Z (N) + dll_data%StCCmdForce(1:3,I) = dll_data%avrswap(J+16:J+18) ! StC commanded brake -- StC_Force_X, StC_Force_Y, StC_Force_Z (N) enddo end subroutine Retrieve_EXavrSWAP_StControls diff --git a/modules/servodyn/src/ServoDyn.f90 b/modules/servodyn/src/ServoDyn.f90 index 6866cd3241..9c2d9d86b6 100644 --- a/modules/servodyn/src/ServoDyn.f90 +++ b/modules/servodyn/src/ServoDyn.f90 @@ -1664,7 +1664,7 @@ subroutine StC_CtrlChan_Setup(m,p,CtrlChanInitInfo,UnSum,ErrStat,ErrMsg) ErrMsg = "" ! NOTE: For now we only have the option of the StC requesting the bladed interface - ! at the the ServoDyn level. If we later add a Simulink interface, the logic + ! at the ServoDyn level. If we later add a Simulink interface, the logic ! below for checking if the DLL interface was requested will need updating. ! At that point it might be necessary to set an array for the p%StCCMode so ! it is possible to tell which channel is from Simulink and which is from @@ -2183,7 +2183,7 @@ SUBROUTINE SrvD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMsg CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None ! Local variables - REAL(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels + REAL(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels INTEGER(IntKi) :: I ! Generic loop index INTEGER(IntKi) :: K ! Blade index INTEGER(IntKi) :: J ! Structural control instance at location @@ -2856,7 +2856,7 @@ subroutine Jac_BStC_dYdu( n, sgn, u_perturb, delta, y_perturb, ErrStat3, ErrMsg3 integer(IntKi) :: i,j,k ! Generic indices type(StC_InputType) :: u_StC ! copy of the StC inputs for StC_CalcOutput call type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_u_indx array. This allows us to simplify the number of calls dramatically k = p%Jac_u_indx(n,4) ! this blade @@ -2900,7 +2900,7 @@ subroutine Jac_NStC_dYdu( n, sgn, u_perturb, delta, y_perturb, ErrStat3, ErrMsg3 integer(IntKi) :: i,j,k ! Generic indices type(StC_InputType) :: u_StC ! copy of the StC inputs for StC_CalcOutput call type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_u_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_u_indx(n,3) ! this instance @@ -2944,7 +2944,7 @@ subroutine Jac_TStC_dYdu( n, sgn, u_perturb, delta, y_perturb, ErrStat3, ErrMsg3 integer(IntKi) :: i,j,k ! Generic indices type(StC_InputType) :: u_StC ! copy of the StC inputs for StC_CalcOutput call type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_u_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_u_indx(n,3) ! this instance @@ -2988,7 +2988,7 @@ subroutine Jac_SStC_dYdu( n, sgn, u_perturb, delta, y_perturb, ErrStat3, ErrMsg3 integer(IntKi) :: i,j,k ! Generic indices type(StC_InputType) :: u_StC ! copy of the StC inputs for StC_CalcOutput call type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_u_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_u_indx(n,3) ! this instance @@ -3770,7 +3770,7 @@ subroutine Jac_BStC_dYdx( n, sgn, x_perturb, delta, y_perturb, ErrStat3, ErrMsg3 character(ErrMsgLen), intent( out) :: ErrMsg3 integer(IntKi) :: i,j,k ! Generic indices type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_x_indx array. This allows us to simplify the number of calls dramatically k = p%Jac_x_indx(n,4) ! this blade @@ -3807,7 +3807,7 @@ subroutine Jac_NStC_dYdx( n, sgn, x_perturb, delta, y_perturb, ErrStat3, ErrMsg3 character(ErrMsgLen), intent( out) :: ErrMsg3 integer(IntKi) :: i,j ! Generic indices type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_x_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_x_indx(n,3) ! this instance @@ -3843,7 +3843,7 @@ subroutine Jac_TStC_dYdx( n, sgn, x_perturb, delta, y_perturb, ErrStat3, ErrMsg3 character(ErrMsgLen), intent( out) :: ErrMsg3 integer(IntKi) :: i,j ! Generic indices type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_x_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_x_indx(n,3) ! this instance @@ -3879,7 +3879,7 @@ subroutine Jac_SStC_dYdx( n, sgn, x_perturb, delta, y_perturb, ErrStat3, ErrMsg3 character(ErrMsgLen), intent( out) :: ErrMsg3 integer(IntKi) :: i,j ! Generic indices type(StC_OutputType) :: y_StC ! copy of the StC outputs for StC_CalcOutput call - real(ReKi) :: AllOuts(0:MaxOutPts) ! All the the available output channels - perturbed (ReKi since WriteOutput is ReKi) + real(ReKi) :: AllOuts(0:MaxOutPts) ! All the available output channels - perturbed (ReKi since WriteOutput is ReKi) ! Since this is acting on only a single blade within a single StC instance, we can look up exactly which one ! from the Jac_x_indx array. This allows us to simplify the number of calls dramatically j = p%Jac_x_indx(n,3) ! this instance diff --git a/modules/servodyn/src/ServoDyn_IO.f90 b/modules/servodyn/src/ServoDyn_IO.f90 index a98b3dc14d..2a618589b4 100644 --- a/modules/servodyn/src/ServoDyn_IO.f90 +++ b/modules/servodyn/src/ServoDyn_IO.f90 @@ -769,7 +769,7 @@ subroutine Set_SrvD_Outs( p, y, m, AllOuts ) type(SrvD_ParameterType), intent(in ) :: p !< Parameters type(SrvD_OutputType), intent(in ) :: y !< Outputs computed at Time type(SrvD_MiscVarType), intent(inout) :: m !< Misc (optimization) variables - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: K !............................................................................................................................... @@ -803,7 +803,7 @@ subroutine Set_NStC_Outs( p_SrvD, x, m, y, AllOuts ) ! Nacelle type(StC_ContinuousStateType), allocatable,intent(in ) :: x(:) !< Continuous states at t type(StC_MiscVarType), allocatable,intent(in ) :: m(:) !< Misc (optimization) variables type(StC_OutputType), allocatable,intent(in ) :: y(:) !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: i if (allocated(x) .and. allocated(m) .and. allocated(y)) then do i=1,min(p_SrvD%NumNStC,MaxStC) ! in case we have more Nacelle StCs than the outputs are set for @@ -817,7 +817,7 @@ subroutine Set_NStC_Outs_Instance( i, x, m, y, AllOuts ) ! Nacelle single St type(StC_ContinuousStateType), intent(in ) :: x !< Continuous states at t type(StC_MiscVarType), intent(in ) :: m !< Misc (optimization) variables type(StC_OutputType), intent(in ) :: y !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: j j=1 if (i < MaxStC) then @@ -847,7 +847,7 @@ subroutine Set_TStC_Outs( p_SrvD, x, m, y, AllOuts ) ! Tower type(StC_ContinuousStateType), allocatable,intent(in ) :: x(:) !< Continuous states at t type(StC_MiscVarType), allocatable,intent(in ) :: m(:) !< Misc (optimization) variables type(StC_OutputType), allocatable,intent(in ) :: y(:) !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: i if (allocated(x) .and. allocated(m) .and. allocated(y)) then do i=1,min(p_SrvD%NumTStC,MaxStC) ! in case we have more Nacelle StCs than the outputs are set for @@ -861,7 +861,7 @@ subroutine Set_TStC_Outs_Instance( i, x, m, y, AllOuts ) ! Tower single StC type(StC_ContinuousStateType), intent(in ) :: x !< Continuous states at t type(StC_MiscVarType), intent(in ) :: m !< Misc (optimization) variables type(StC_OutputType), intent(in ) :: y !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: j j=1 if (i < MaxStC) then @@ -891,7 +891,7 @@ subroutine Set_BStC_Outs( p_SrvD, x, m, y, AllOuts ) ! Blades type(StC_ContinuousStateType), allocatable,intent(in ) :: x(:) !< Continuous states at t type(StC_MiscVarType), allocatable,intent(in ) :: m(:) !< Misc (optimization) variables type(StC_OutputType), allocatable,intent(in ) :: y(:) !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: i if (allocated(x) .and. allocated(m) .and. allocated(y)) then do i=1,min(p_SrvD%NumBStC,MaxStC) ! in case we have more Blade StCs than the outputs are set for @@ -906,7 +906,7 @@ subroutine Set_BStC_Outs_Instance( i, numBl, x, m, y, AllOuts ) ! Single type(StC_ContinuousStateType), intent(in ) :: x !< Continuous states at t type(StC_MiscVarType), intent(in ) :: m !< Misc (optimization) variables type(StC_OutputType), intent(in ) :: y !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: j if (i < MaxStC) then do j=1,min(NumBl,MaxBlOuts) @@ -937,7 +937,7 @@ subroutine Set_SStC_Outs( p_SrvD, x, m, y, AllOuts ) ! Platform type(StC_ContinuousStateType), allocatable,intent(in ) :: x(:) !< Continuous states at t type(StC_MiscVarType), allocatable,intent(in ) :: m(:) !< Misc (optimization) variables type(StC_OutputType), allocatable,intent(in ) :: y(:) !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: i if (allocated(x) .and. allocated(m) .and. allocated(y)) then do i=1,min(p_SrvD%NumSStC,MaxStC) ! in case we have more Nacelle StCs than the outputs are set for @@ -951,7 +951,7 @@ subroutine Set_SStC_Outs_Instance( i, x, m, y, AllOuts ) ! Platform type(StC_ContinuousStateType), intent(in ) :: x !< Continuous states at t type(StC_MiscVarType), intent(in ) :: m !< Misc (optimization) variables type(StC_OutputType), intent(in ) :: y !< Outputs computed at Time - real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the the available output channels + real(ReKi), intent(inout) :: AllOuts(0:MaxOutPts) ! All the available output channels integer :: j j=1 if (i < MaxStC) then diff --git a/modules/subdyn/src/SubDyn_Output.f90 b/modules/subdyn/src/SubDyn_Output.f90 index 76d470711c..37b1bac1b2 100644 --- a/modules/subdyn/src/SubDyn_Output.f90 +++ b/modules/subdyn/src/SubDyn_Output.f90 @@ -54,7 +54,7 @@ MODULE SubDyn_Output SUBROUTINE SDOut_Init( Init, y, p, misc, InitOut, WtrDpth, ErrStat, ErrMsg ) TYPE(SD_InitType), INTENT( INOUT ) :: Init ! data needed to initialize the output module TYPE(SD_OutputType), INTENT( INOUT ) :: y ! SubDyn module's output data - TYPE(SD_ParameterType), target, INTENT( INOUT ) :: p ! SubDyn module paramters + TYPE(SD_ParameterType), target, INTENT( INOUT ) :: p ! SubDyn module parameters TYPE(SD_MiscVarType), INTENT( INOUT ) :: misc ! SubDyn misc/optimization variables TYPE(SD_InitOutputType ), INTENT( INOUT ) :: InitOut ! SubDyn module initialization output data REAL(ReKi), INTENT( IN ) :: WtrDpth ! water depth from initialization routine diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index 4500610412..511c36b0ee 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -736,7 +736,7 @@ def read_ElastoDynTower(self, tower_file): f.readline() f.readline() - # General Tower Paramters + # General Tower Parameters f.readline() self.fst_vt['ElastoDynTower']['NTwInpSt'] = int(f.readline().split()[0]) self.fst_vt['ElastoDynTower']['TwrFADmp1'] = float_read(f.readline().split()[0]) diff --git a/openfast_io/openfast_io/FAST_writer.py b/openfast_io/openfast_io/FAST_writer.py index 89917a8af5..c7f57ac0da 100644 --- a/openfast_io/openfast_io/FAST_writer.py +++ b/openfast_io/openfast_io/FAST_writer.py @@ -253,7 +253,7 @@ def execute(self): if 'option_names' in self.fst_vt['MoorDyn'] and 'WATERKIN' in self.fst_vt['MoorDyn']['option_names']: self.write_WaterKin(os.path.join(self.FAST_runDirectory,self.fst_vt['MoorDyn']['WaterKin_file'])) - # # look at if the the self.fst_vt['BeamDyn'] is an array, if so, loop through the array + # # look at if the self.fst_vt['BeamDyn'] is an array, if so, loop through the array # # if its a dictionary, just write the same BeamDyn file if isinstance(self.fst_vt['BeamDyn'], list): diff --git a/openfast_io/openfast_io/turbsim_file.py b/openfast_io/openfast_io/turbsim_file.py index 02b8887cff..3434ac7e51 100644 --- a/openfast_io/openfast_io/turbsim_file.py +++ b/openfast_io/openfast_io/turbsim_file.py @@ -367,7 +367,7 @@ def normalPlane(ts, t=None, it0=None, removeMean=False): def vertProfile(self, y_span='full'): """ Vertical profile of the box INPUTS: - - y_span: if 'full', average the vertical profile accross all y-values + - y_span: if 'full', average the vertical profile across all y-values if 'mid', average the vertical profile at the middle y value """ if y_span=='full': @@ -1053,7 +1053,7 @@ def fitPowerLaw(ts, z_ref=None, y_span='full', U_guess=10, alpha_guess=0.1): Fit power law to vertical profile INPUTS: - z_ref: reference height used to define the "U_ref" - - y_span: if 'full', average the vertical profile accross all y-values + - y_span: if 'full', average the vertical profile across all y-values if 'mid', average the vertical profile at the middle y value """ if z_ref is None: diff --git a/reg_tests/executeUnsteadyAeroRegressionCase.py b/reg_tests/executeUnsteadyAeroRegressionCase.py index 2e441c4abc..53c8bf567e 100644 --- a/reg_tests/executeUnsteadyAeroRegressionCase.py +++ b/reg_tests/executeUnsteadyAeroRegressionCase.py @@ -158,7 +158,7 @@ def Error(msg): sys.exit(0) else: print('---------- UNSTEADY AERODYNAMICS DRIVER TEST: {} --------'.format(caseName)) - print('The following errors occured:') + print('The following errors occurred:') for e in errors: print(e) sys.exit(1) diff --git a/reg_tests/lib/rtestlib.py b/reg_tests/lib/rtestlib.py index e90ca95820..ed952f25ec 100644 --- a/reg_tests/lib/rtestlib.py +++ b/reg_tests/lib/rtestlib.py @@ -64,7 +64,7 @@ def validateExeOrExit(path): def copyTree(src, dst, excludeExt=None, renameDict=None, renameExtDict=None, includeExt=None): """ - Copy a directory to another one, overwritting files if necessary. + Copy a directory to another one, overwriting files if necessary. copy_tree from distutils and copytree from shutil fail on Windows (in particular on git files) INPUTS: - src: source directory diff --git a/share/discon/DISCON.F90 b/share/discon/DISCON.F90 index c37070c7ea..b2f8c728d9 100644 --- a/share/discon/DISCON.F90 +++ b/share/discon/DISCON.F90 @@ -69,7 +69,7 @@ SUBROUTINE DISCON ( avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) BIND (C, N REAL(4), PARAMETER :: OnePlusEps = 1.0 + EPSILON(OnePlusEps) ! The number slighty greater than unity in single precision. REAL(4), PARAMETER :: PC_DT = 0.000125 !JASON:THIS CHANGED FOR ITI BARGE: 0.0001 ! Communication interval for pitch controller, sec. REAL(4), PARAMETER :: PC_KI = 0.008068634 ! Integral gain for pitch controller at rated pitch (zero), (-). -REAL(4), PARAMETER :: PC_KK = 0.1099965 ! Pitch angle where the the derivative of the aerodynamic power w.r.t. pitch has increased by a factor of two relative to the derivative at rated pitch (zero), rad. +REAL(4), PARAMETER :: PC_KK = 0.1099965 ! Pitch angle where the derivative of the aerodynamic power w.r.t. pitch has increased by a factor of two relative to the derivative at rated pitch (zero), rad. REAL(4), PARAMETER :: PC_KP = 0.01882681 ! Proportional gain for pitch controller at rated pitch (zero), sec. REAL(4), PARAMETER :: PC_MaxPit = 1.570796 ! Maximum pitch setting in pitch controller, rad. REAL(4), PARAMETER :: PC_MaxRat = 0.1396263 ! Maximum pitch rate (in absolute value) in pitch controller, rad/s. @@ -316,7 +316,7 @@ SUBROUTINE DISCON ( avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) BIND (C, N ! Main control calculations: -IF ( ( iStatus >= 0 ) .AND. ( aviFAIL >= 0 ) ) THEN ! Only compute control calculations if no error has occured and we are not on the last time step +IF ( ( iStatus >= 0 ) .AND. ( aviFAIL >= 0 ) ) THEN ! Only compute control calculations if no error has occurred and we are not on the last time step From 2c537cc5520af9b277b76e0e7fba26cb39c21de4 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 16 May 2025 15:56:20 -0600 Subject: [PATCH 44/63] Make StC inputs relative to ServoDyn --- openfast_io/openfast_io/FAST_reader.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index 4500610412..227d733cba 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -1717,7 +1717,10 @@ def read_StC(self,filename): ''' StC_vt = {} - with open(os.path.join(self.FAST_directory, filename)) as f: + # Inputs should be relative to ServoDyn, like in OpenFAST + SvD_dir = os.path.dirname(self.fst_vt['Fst']['ServoFile']) + + with open(os.path.join(self.FAST_directory, SvD_dir, filename)) as f: f.readline() f.readline() From 621a2d9fcd5d5d32894ad68aa1ababfd706d53c1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 16 May 2025 15:56:40 -0600 Subject: [PATCH 45/63] Let WaterKin = 0, make INTERTIALF an int --- openfast_io/openfast_io/FAST_reader.py | 3 ++- openfast_io/openfast_io/FAST_writer.py | 14 +++++++++----- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index 227d733cba..b8dbc4199d 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -3194,7 +3194,8 @@ def read_MoorDyn(self, moordyn_file): if option_name.upper() == 'WATERKIN': self.fst_vt['MoorDyn']['WaterKin'] = option_value.strip('"') WaterKin_file = os.path.normpath(os.path.join(os.path.dirname(moordyn_file), self.fst_vt['MoorDyn']['WaterKin'])) - self.read_WaterKin(WaterKin_file) + if self.fst_vt['MoorDyn']['WaterKin'].upper() not in ['0','UNUSED']: + self.read_WaterKin(WaterKin_file) self.fst_vt['MoorDyn']['option_values'].append(float_read(option_value.strip('"'))) # some options values can be strings or floats self.fst_vt['MoorDyn']['option_names'].append(option_name) diff --git a/openfast_io/openfast_io/FAST_writer.py b/openfast_io/openfast_io/FAST_writer.py index 89917a8af5..e61474d112 100644 --- a/openfast_io/openfast_io/FAST_writer.py +++ b/openfast_io/openfast_io/FAST_writer.py @@ -65,9 +65,9 @@ def int_default_out(val, trim = False): """ if type(val) is float: if trim: - return '{:d}'.format(val) + return '{:d}'.format(int(val)) else: - return '{:<22d}'.format(val) + return '{:<22d}'.format(int(val)) else: if trim: return '{:}'.format(val) @@ -250,7 +250,7 @@ def execute(self): self.write_MAP() elif self.fst_vt['Fst']['CompMooring'] == 3: self.write_MoorDyn() - if 'option_names' in self.fst_vt['MoorDyn'] and 'WATERKIN' in self.fst_vt['MoorDyn']['option_names']: + if self.fst_vt['WaterKin']: # will be empty if not read self.write_WaterKin(os.path.join(self.FAST_runDirectory,self.fst_vt['MoorDyn']['WaterKin_file'])) # # look at if the the self.fst_vt['BeamDyn'] is an array, if so, loop through the array @@ -2497,10 +2497,14 @@ def write_MoorDyn(self): f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') for i in range(len(self.fst_vt['MoorDyn']['option_values'])): - if 'WATERKIN' in self.fst_vt['MoorDyn']['option_names'][i]: + if self.fst_vt['MoorDyn']['option_names'][i].upper() == 'WATERKIN' and self.fst_vt['WaterKin']: + # WATERKIN needs to be a string, and should have already been read in and part of fst_vt self.fst_vt['MoorDyn']['WaterKin_file'] = self.FAST_namingOut + '_WaterKin.dat' f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['MoorDyn']['WaterKin_file']+'"', self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_descriptions'][i]+'\n')) - else: # if not waterkin handle normally + elif self.fst_vt['MoorDyn']['option_names'][i].upper() in ['INERTIALF','WATERKIN']: + # These options need to be an integer + f.write('{:<22} {:<11} {:}'.format(int_default_out(self.fst_vt['MoorDyn']['option_values'][i]), self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_descriptions'][i]+'\n')) + else: # if not handle normally f.write('{:<22} {:<11} {:}'.format(float_default_out(self.fst_vt['MoorDyn']['option_values'][i]), self.fst_vt['MoorDyn']['option_names'][i], self.fst_vt['MoorDyn']['option_descriptions'][i]+'\n')) f.write('------------------------ OUTPUTS --------------------------------------------\n') From e4935e7e4b9efaee30e1427fdf40b04ac46c12e6 Mon Sep 17 00:00:00 2001 From: Derek Slaughter Date: Wed, 21 May 2025 22:40:46 +0000 Subject: [PATCH 46/63] Use new github actions for regression tests --- .github/workflows/automated-dev-tests.yml | 878 ++++++---------------- 1 file changed, 227 insertions(+), 651 deletions(-) diff --git a/.github/workflows/automated-dev-tests.yml b/.github/workflows/automated-dev-tests.yml index 723b585dad..2b3de8db5d 100644 --- a/.github/workflows/automated-dev-tests.yml +++ b/.github/workflows/automated-dev-tests.yml @@ -21,68 +21,12 @@ env: C_COMPILER: gcc-12 GCOV_EXE: gcov-12 CMAKE_BUILD_PARALLEL_LEVEL: 8 - CTEST_PARALLEL_LEVEL: 2 - + CTEST_PARALLEL_LEVEL: 4 jobs: ### BUILD JOBS - - build-all-debug: - # Tests compiling in debug mode. - # Also compiles the Registry and generates new types files. - # Debug more speeds up the build. - runs-on: ubuntu-22.04 - steps: - - name: Checkout - uses: actions/checkout@v4 - with: - submodules: recursive - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Set up MATLAB - uses: matlab-actions/setup-matlab@v2 - with: - products: Simulink - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - - name: Setup workspace - run: cmake -E make_directory ${{runner.workspace}}/openfast/build - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ - -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ - -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ - -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBLA_VENDOR:STRING=OpenBLAS \ - -DCMAKE_BUILD_TYPE:STRING=DEBUG \ - -DBUILD_SHARED_LIBS:BOOL=OFF \ - -DGENERATE_TYPES=ON \ - -DVARIABLE_TRACKING=OFF \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - -DBUILD_OPENFAST_SIMULINK_API=ON \ - ${GITHUB_WORKSPACE} - # -DDOUBLE_PRECISION=OFF \ - - name: Build all - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target all - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-all-debug-${{ github.sha }} - build-all-debug-single: # Tests compiling in debug mode with single precision. # This workspace is not used by any other subtests, it checks type errors of the type ReKi/R8Ki @@ -91,476 +35,43 @@ jobs: steps: - name: Checkout uses: actions/checkout@v4 - with: - submodules: recursive - - name: Install dependencies - run: | - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev - - name: Setup workspace - run: cmake -E make_directory ${{runner.workspace}}/openfast/build - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ - -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ - -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ - -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBLA_VENDOR:STRING=OpenBLAS \ - -DCMAKE_BUILD_TYPE:STRING=DEBUG \ - -DBUILD_SHARED_LIBS:BOOL=OFF \ - -DVARIABLE_TRACKING=OFF \ - -DDOUBLE_PRECISION:BOOL=OFF \ - ${GITHUB_WORKSPACE} - - name: Build all - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target all - - - - build-drivers-release: - runs-on: ubuntu-22.04 - steps: - - name: Checkout - uses: actions/checkout@v4 - with: - submodules: recursive - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - - name: Setup workspace - run: cmake -E make_directory ${{runner.workspace}}/openfast/build - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ - -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ - -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ - -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBLA_VENDOR:STRING=OpenBLAS \ - -DCMAKE_BUILD_TYPE:STRING=RelWithDebInfo \ - -DVARIABLE_TRACKING=OFF \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - ${GITHUB_WORKSPACE} - - name: Build module drivers - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target regression_test_module_drivers - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-drivers-release-${{ github.sha }} - - - build-postlib-release: - runs-on: ubuntu-22.04 - steps: - - name: Checkout - uses: actions/checkout@v4 - with: - submodules: recursive - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Set up MATLAB - uses: matlab-actions/setup-matlab@v2 - with: - products: Simulink - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev # gcovr - - name: Setup workspace - run: cmake -E make_directory ${{runner.workspace}}/openfast/build - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ - -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ - -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ - -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBLA_VENDOR:STRING=OpenBLAS \ - -DCMAKE_BUILD_TYPE:STRING=RELWITHDEBINFO \ - -DOPENMP:BOOL=ON \ - -DDOUBLE_PRECISION=ON \ - -DVARIABLE_TRACKING=OFF \ - -DBUILD_FASTFARM:BOOL=ON \ - -DBUILD_OPENFAST_CPP_API:BOOL=ON \ - -DBUILD_OPENFAST_LIB_DRIVER:BOOL=ON \ - -DBUILD_OPENFAST_CPP_DRIVER:BOOL=ON \ - -DBUILD_SHARED_LIBS:BOOL=OFF \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - -DBUILD_OPENFAST_SIMULINK_API=ON \ - ${GITHUB_WORKSPACE} - - name: Build openfast-postlib - working-directory: ${{runner.workspace}}/openfast/build - run: cmake --build . --target openfast_postlib - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-postlib-release-${{ github.sha }} - - - build-interfaces-release: - runs-on: ubuntu-22.04 - needs: build-postlib-release - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-postlib-release-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - ${GITHUB_WORKSPACE} - - name: Build OpenFAST C-Interfaces - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target openfastlib openfast_lib_driver openfastcpp aerodyn_inflow_c_binding moordyn_c_binding ifw_c_binding hydrodyn_c_binding regression_test_controllers - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-interfaces-release-${{ github.sha }} - - - build-openfast-release: - runs-on: ubuntu-22.04 - needs: build-postlib-release - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-postlib-release-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - ${GITHUB_WORKSPACE} - - name: Build OpenFAST glue-code - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target openfast - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} - - - build-fastfarm-release: - runs-on: ubuntu-22.04 - needs: build-postlib-release - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-postlib-release-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - ${GITHUB_WORKSPACE} - - name: Build FAST.Farm - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target FAST.Farm - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-fastfarm-release-${{ github.sha }} - - - - ### BUILD AND TEST JOBS - - build-test-uadriver-debug: - # UA driver used to require -DUA_OUTS - runs-on: ubuntu-22.04 - steps: - - name: Checkout - uses: actions/checkout@v4 - with: - submodules: recursive - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - name: Install dependencies run: | - pip install -r requirements.txt sudo apt-get update -y - sudo apt-get install -y libopenblas-dev + sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - name: Setup workspace run: cmake -E make_directory ${{runner.workspace}}/openfast/build - - name: Configure build - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ - -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ - -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ - -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DCMAKE_BUILD_TYPE:STRING=DEBUG \ - -DBUILD_SHARED_LIBS:BOOL=OFF \ - -DGENERATE_TYPES=ON \ - -DVARIABLE_TRACKING=OFF \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - ${GITHUB_WORKSPACE} - - name: Build all - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake --build . --target unsteadyaero_driver - - - name: Run UnsteadyAero tests - working-directory: ${{runner.workspace}}/openfast/build - shell: bash - run: | - ctest -VV -R "^ua_" - - - name: Failing test artifacts - uses: actions/upload-artifact@v4 - if: failure() - with: - name: rtest-uadriver - path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules/unsteadyaero - - - - ### TEST JOBS - - rtest-module-drivers: - runs-on: ubuntu-22.04 - needs: build-drivers-release - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-drivers-release-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure Tests - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - ${GITHUB_WORKSPACE} - - name: Run AeroDyn tests - uses: ./.github/actions/tests-module-aerodyn - with: - test-target: regression - - name: Run BeamDyn tests - uses: ./.github/actions/tests-module-beamdyn - with: - test-target: regression - - name: Run HydroDyn tests - uses: ./.github/actions/tests-module-hydrodyn - - name: Run InflowWind tests - uses: ./.github/actions/tests-module-inflowwind - with: - test-target: regression - - name: Run MoorDyn tests - uses: ./.github/actions/tests-module-moordyn - - name: Run SeaState tests - uses: ./.github/actions/tests-module-seastate - - name: Run SubDyn tests - uses: ./.github/actions/tests-module-subdyn - - name: Failing test artifacts - uses: actions/upload-artifact@v4 - if: failure() - with: - name: rtest-module-drivers - path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules - - - rtest-modules-debug: - runs-on: ubuntu-22.04 - needs: build-all-debug - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-all-debug-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure Tests - working-directory: ${{runner.workspace}}/openfast/build - run: | - cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ - ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run AeroDyn tests - uses: ./.github/actions/tests-module-aerodyn - with: - # Don't run regression tests here since they currently fail inconsistently - test-target: unit - - name: Run BeamDyn tests - uses: ./.github/actions/tests-module-beamdyn - - name: Run HydroDyn tests - uses: ./.github/actions/tests-module-hydrodyn - - name: Run InflowWind tests - uses: ./.github/actions/tests-module-inflowwind - - name: Run MoorDyn tests - uses: ./.github/actions/tests-module-moordyn - - name: Run NWTC Library tests - uses: ./.github/actions/tests-module-nwtclibrary - - name: Run SeaState tests - uses: ./.github/actions/tests-module-seastate - - name: Run SubDyn tests - uses: ./.github/actions/tests-module-subdyn - - name: Run VersionInfo tests - uses: ./.github/actions/tests-module-version - - name: Failing test artifacts - uses: actions/upload-artifact@v4 - if: failure() - with: - name: rtest-modules-debug - path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules - ${{runner.workspace}}/openfast/build/unit_tests - - - rtest-interfaces: - runs-on: ubuntu-22.04 - needs: build-interfaces-release - steps: - - name: Cache the workspace - uses: actions/cache@v4 - with: - path: ${{runner.workspace}} - key: build-interfaces-release-${{ github.sha }} - - name: Setup Python - uses: actions/setup-python@v5 - with: - python-version: '3.11' - - name: Install dependencies - run: | - pip install -r requirements.txt - sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure Tests + - name: Configure build working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ - -DBUILD_TESTING:BOOL=ON \ - -DCTEST_PLOT_ERRORS:BOOL=ON \ + -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ + -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ + -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ + -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ + -DBLA_VENDOR:STRING=OpenBLAS \ + -DCMAKE_BUILD_TYPE:STRING=DEBUG \ + -DVARIABLE_TRACKING:BOOL=OFF \ + -DDOUBLE_PRECISION:BOOL=OFF \ + -DBUILD_OPENFAST_CPP_API:BOOL=ON \ + -DBUILD_OPENFAST_LIB_DRIVER:BOOL=ON \ + -DBUILD_OPENFAST_CPP_DRIVER:BOOL=ON \ + -DBUILD_FASTFARM:BOOL=ON \ ${GITHUB_WORKSPACE} - - name: Run Interface / API tests + - name: Build all working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L "cpp|python|fastlib" \ - -LE "openfast_io" - - name: Failing test artifacts - uses: actions/upload-artifact@v4 - if: failure() - with: - name: rtest-interfaces - path: | - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast-cpp - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/python - ${{runner.workspace}}/openfast/build/reg_tests/modules/aerodyn - ${{runner.workspace}}/openfast/build/reg_tests/modules/moordyn - ${{runner.workspace}}/openfast/build/reg_tests/modules/inflowwind - ${{runner.workspace}}/openfast/build/reg_tests/modules/hydrodyn - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast-cpp/5MW_Baseline + cmake --build . --target all - rtest-OF: + build-all-release: runs-on: ubuntu-22.04 - needs: build-openfast-release steps: - - name: Cache the workspace - uses: actions/cache@v4 + - name: Checkout + uses: actions/checkout@v4 with: - path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + submodules: recursive - name: Setup Python uses: actions/setup-python@v5 with: @@ -569,48 +80,55 @@ jobs: run: | pip install -r requirements.txt sudo apt-get update -y - sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Configure Tests + sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev + - name: Setup workspace + run: cmake -E make_directory ${{runner.workspace}}/openfast/build + - name: Configure build working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ + -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ + -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ + -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ + -DBUILD_SHARED_LIBS:BOOL=OFF \ + -DBLA_VENDOR:STRING=OpenBLAS \ + -DCMAKE_BUILD_TYPE:STRING=RelWithDebInfo \ + -DVARIABLE_TRACKING:BOOL=OFF \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ + -DOPENMP:BOOL=ON \ + -DDOUBLE_PRECISION=ON \ + -DBUILD_OPENFAST_CPP_API:BOOL=ON \ + -DBUILD_OPENFAST_LIB_DRIVER:BOOL=ON \ + -DBUILD_OPENFAST_CPP_DRIVER:BOOL=ON \ + -DBUILD_FASTFARM:BOOL=ON \ ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run 5MW tests + - name: Build all working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -j4 \ - -L openfast \ - -LE "cpp|linear|python|fastlib|aeromap" \ - -E "5MW_OC4Semi_WSt_WavesWN|5MW_OC3Mnpl_DLL_WTurb_WavesIrr|5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth|5MW_OC3Trpd_DLL_WSt_WavesReg|5MW_Land_BD_DLL_WTurb" - - name: Failing test artifacts - uses: actions/upload-artifact@v4 - if: failure() + cmake --build . --target all + - name: Cache the workspace + uses: actions/cache@v4 with: - name: rtest-OF - path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AWT27 - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/SWRT - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline + path: ${{runner.workspace}} + key: build-all-release-${{ github.sha }} - rtest-openfast_io: + + + ### BUILD AND TEST JOBS + + build-all-test-modules-debug: + # Tests compiling in debug mode. + # Also compiles the Registry and generates new types files. + # Debug more speeds up the build. runs-on: ubuntu-22.04 - needs: build-openfast-release steps: - - name: Cache the workspace - uses: actions/cache@v4 + - name: Checkout + uses: actions/checkout@v4 with: - path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + submodules: recursive - name: Setup Python uses: actions/setup-python@v5 with: @@ -620,57 +138,100 @@ jobs: pip install -r requirements.txt sudo apt-get update -y sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - - name: Install openfast_io - working-directory: ${{runner.workspace}}/openfast/openfast_io - run: | - pip install -e . - - name: Configure Tests + - name: Setup workspace + run: cmake -E make_directory ${{runner.workspace}}/openfast/build + - name: Configure build working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ + -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ + -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ + -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ + -DBLA_VENDOR:STRING=OpenBLAS \ + -DCMAKE_BUILD_TYPE:STRING=DEBUG \ + -DGENERATE_TYPES:BOOL=ON \ + -DVARIABLE_TRACKING:BOOL=OFF \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run openfast_io tests + # -DDOUBLE_PRECISION=OFF \ + - name: Build all + working-directory: ${{runner.workspace}}/openfast/build + run: | + cmake --build . --target all + - name: Run UnsteadyAero tests working-directory: ${{runner.workspace}}/openfast/build + shell: bash run: | - ctest -VV -j4 \ - -L openfast_io + ctest -VV -R "^ua_" + - name: Run AeroDyn tests + uses: ./.github/actions/tests-module-aerodyn + with: + # Don't run regression tests here since they currently fail inconsistently + test-target: unit + - name: Run BeamDyn tests + uses: ./.github/actions/tests-module-beamdyn + - name: Run HydroDyn tests + uses: ./.github/actions/tests-module-hydrodyn + - name: Run InflowWind tests + uses: ./.github/actions/tests-module-inflowwind + - name: Run MoorDyn tests + uses: ./.github/actions/tests-module-moordyn + - name: Run NWTC Library tests + uses: ./.github/actions/tests-module-nwtclibrary + - name: Run SeaState tests + uses: ./.github/actions/tests-module-seastate + - name: Run SubDyn tests + uses: ./.github/actions/tests-module-subdyn + - name: Run VersionInfo tests + uses: ./.github/actions/tests-module-version - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-openfast_io + name: rtest-modules-debug path: | - ${{runner.workspace}}/openfast/build/reg_tests/openfast_io + ${{runner.workspace}}/openfast/build/reg_tests/modules + ${{runner.workspace}}/openfast/build/unit_tests - rtest-OF-simulink: + build-test-OF-simulink: runs-on: ubuntu-22.04 - needs: build-openfast-release steps: - - name: Cache the workspace - uses: actions/cache@v4 + - name: Checkout + uses: actions/checkout@v4 with: - path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + submodules: recursive - name: Install dependencies run: | sudo apt-get update -y - sudo apt-get install -y libhdf5-dev libopenmpi-dev libyaml-cpp-dev libopenblas-dev libopenblas-openmp-dev + sudo apt-get install -y libopenblas-dev - name: Set up MATLAB uses: matlab-actions/setup-matlab@v2 with: products: Simulink - - name: Build FAST_SFunc + - name: Setup workspace + run: cmake -E make_directory ${{runner.workspace}}/openfast/build + - name: Configure build working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ + -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/openfast/install \ + -DCMAKE_Fortran_COMPILER:STRING=${{env.FORTRAN_COMPILER}} \ + -DCMAKE_CXX_COMPILER:STRING=${{env.CXX_COMPILER}} \ + -DCMAKE_C_COMPILER:STRING=${{env.C_COMPILER}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ + -DBUILD_OPENFAST_SIMULINK_API:BOOL=ON \ -DUSE_LOCAL_STATIC_LAPACK:BOOL=ON \ + -DCMAKE_BUILD_TYPE:STRING=DEBUG \ + -DGENERATE_TYPES:BOOL=ON \ + -DVARIABLE_TRACKING:BOOL=OFF \ ${GITHUB_WORKSPACE} + - name: Build FAST_SFunc + working-directory: ${{runner.workspace}}/openfast/build + run: | cmake --build . --target FAST_SFunc - name: Run MATLAB tests and generate artifacts uses: matlab-actions/run-tests@v2 @@ -679,68 +240,79 @@ jobs: test-results-junit: test-results/results.xml code-coverage-cobertura: code-coverage/coverage.xml + ### TEST JOBS - rtest-OF-5MW_Land_AeroMap: + rtest-module-drivers: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: python-version: '3.11' - name: Install dependencies run: | - python -m pip install --upgrade pip - pip install numpy "Bokeh>=2.4,!=3.0.0,!=3.0.1,!=3.0.2,!=3.0.3" + pip install -r requirements.txt sudo apt-get update -y sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev - sudo apt-get install -y libhdf5-dev libopenmpi-dev libyaml-cpp-dev + sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev - name: Configure Tests working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - - name: Run 5MW aero map tests - working-directory: ${{runner.workspace}}/openfast/build - run: | - ctest -VV -L aeromap -LE "cpp|linear|python" -R 5MW_Land_AeroMap + - name: Run AeroDyn tests + uses: ./.github/actions/tests-module-aerodyn + with: + test-target: regression + - name: Run BeamDyn tests + uses: ./.github/actions/tests-module-beamdyn + with: + test-target: regression + - name: Run HydroDyn tests + uses: ./.github/actions/tests-module-hydrodyn + - name: Run InflowWind tests + uses: ./.github/actions/tests-module-inflowwind + with: + test-target: regression + - name: Run MoorDyn tests + uses: ./.github/actions/tests-module-moordyn + - name: Run SeaState tests + uses: ./.github/actions/tests-module-seastate + - name: Run SubDyn tests + uses: ./.github/actions/tests-module-subdyn - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_Land_AeroMap + name: rtest-module-drivers path: | ${{runner.workspace}}/openfast/build/reg_tests/modules - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AWT27 - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/SWRT - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline - rtest-OF-5MW_OC4Semi_WSt_WavesWN: + rtest-interfaces: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release + env: + OMP_NUM_THREADS: 1 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: - python-version: '3.10' + python-version: '3.11' - name: Install dependencies run: | pip install -r requirements.txt @@ -751,40 +323,42 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run 5MW tests + - name: Run Interface / API tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L openfast -LE "cpp|linear|python" -R 5MW_OC4Semi_WSt_WavesWN + ctest -VV \ + -L "cpp|python|fastlib" \ + -LE "openfast_io" - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_OC4Semi_WSt_WavesWN + name: rtest-interfaces path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AWT27 - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/SWRT - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline + ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast-cpp + ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/python + ${{runner.workspace}}/openfast/build/reg_tests/modules/aerodyn + ${{runner.workspace}}/openfast/build/reg_tests/modules/moordyn + ${{runner.workspace}}/openfast/build/reg_tests/modules/inflowwind + ${{runner.workspace}}/openfast/build/reg_tests/modules/hydrodyn + !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast-cpp/5MW_Baseline - rtest-OF-5MW_OC3Mnpl_DLL_WTurb_WavesIrr: + rtest-OF: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release + env: + OMP_NUM_THREADS: 1 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -799,7 +373,7 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} @@ -807,14 +381,15 @@ jobs: - name: Run 5MW tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L openfast -LE "cpp|linear|python" -R 5MW_OC3Mnpl_DLL_WTurb_WavesIrr -j1 + ctest -VV \ + -L openfast \ + -LE "cpp|linear|python|fastlib|offshore" - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_OC3Mnpl_DLL_WTurb_WavesIrr + name: rtest-OF path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC @@ -824,15 +399,15 @@ jobs: !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline - rtest-OF-5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth: + rtest-OF-offshore: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -847,7 +422,7 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} @@ -855,14 +430,15 @@ jobs: - name: Run 5MW tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L openfast -LE "cpp|linear|python" -R 5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth + ctest -VV \ + -L openfast -L offshore \ + -LE "cpp|linear|python|fastlib" - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth + name: rtest-OF-offshore path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC @@ -871,16 +447,18 @@ jobs: !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline - - rtest-OF-5MW_OC3Trpd_DLL_WSt_WavesReg: + + rtest-OF-linearization: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release + env: + OMP_NUM_THREADS: 1 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -895,22 +473,20 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run 5MW tests + - name: Run OpenFAST linearization tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L openfast -LE "cpp|linear|python" -R 5MW_OC3Trpd_DLL_WSt_WavesReg + ctest -VV -L linear - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_OC3Trpd_DLL_WSt_WavesReg + name: rtest-OF-linearization path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC @@ -919,16 +495,17 @@ jobs: !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline - - rtest-OF-5MW_Land_BD_DLL_WTurb: + rtest-OF-aeromap: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release + env: + OMP_NUM_THREADS: 1 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -943,22 +520,20 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - cmake --build . --target regression_test_controllers - - name: Run 5MW tests + - name: Run aero map tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L openfast -LE "cpp|linear|python" -R 5MW_Land_BD_DLL_WTurb + ctest -VV -L aeromap -LE "cpp|linear|python" - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-5MW_Land_BD_DLL_WTurb + name: rtest-OF-aeromap path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC @@ -968,15 +543,17 @@ jobs: !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline - rtest-OF-linearization: + rtest-openfast_io: runs-on: ubuntu-22.04 - needs: build-openfast-release + needs: build-all-release + env: + OMP_NUM_THREADS: 1 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-openfast-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -987,43 +564,43 @@ jobs: sudo apt-get update -y sudo apt-get install -y libopenblas-dev libopenblas-openmp-dev sudo apt-get install -y libhdf5-dev libnetcdf-dev libopenmpi-dev libyaml-cpp-dev + - name: Install openfast_io + working-directory: ${{runner.workspace}}/openfast/openfast_io + run: | + pip install -e . - name: Configure Tests working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} - - name: Run OpenFAST linearization tests + cmake --build . --target regression_test_controllers + - name: Run openfast_io tests working-directory: ${{runner.workspace}}/openfast/build run: | - ctest -VV -L linear + ctest -VV -L openfast_io - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() with: - name: rtest-OF-linearization + name: rtest-openfast_io path: | - ${{runner.workspace}}/openfast/build/reg_tests/modules - ${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/5MW_Baseline - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AOC - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/AWT27 - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/SWRT - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/UAE_VI - !${{runner.workspace}}/openfast/build/reg_tests/glue-codes/openfast/WP_Baseline + ${{runner.workspace}}/openfast/build/reg_tests/openfast_io rtest-FF: runs-on: ubuntu-22.04 - needs: build-fastfarm-release + needs: build-all-release + env: + OMP_NUM_THREADS: 2 steps: - name: Cache the workspace uses: actions/cache@v4 with: path: ${{runner.workspace}} - key: build-fastfarm-release-${{ github.sha }} + key: build-all-release-${{ github.sha }} - name: Setup Python uses: actions/setup-python@v5 with: @@ -1038,7 +615,7 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build run: | cmake \ - -DPython_ROOT_DIR:STRING=${{env.pythonLocation}} \ + -DPython_ROOT_DIR:PATH=${{env.pythonLocation}} \ -DBUILD_TESTING:BOOL=ON \ -DCTEST_PLOT_ERRORS:BOOL=ON \ ${GITHUB_WORKSPACE} @@ -1047,8 +624,7 @@ jobs: working-directory: ${{runner.workspace}}/openfast/build shell: bash run: | - set OMP_NUM_THREADS=2 - ctest -VV -L fastfarm --verbose + ctest -VV -j1 -L fastfarm --verbose - name: Failing test artifacts uses: actions/upload-artifact@v4 if: failure() From 92e39c96d287fb48f81dec1477c69067628ae8d1 Mon Sep 17 00:00:00 2001 From: Derek Slaughter Date: Thu, 22 May 2025 13:12:22 +0000 Subject: [PATCH 47/63] Add offshore label to MHK tests --- reg_tests/CTestList.cmake | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/reg_tests/CTestList.cmake b/reg_tests/CTestList.cmake index bdcaa6e0b4..ed3c20c7bd 100644 --- a/reg_tests/CTestList.cmake +++ b/reg_tests/CTestList.cmake @@ -344,9 +344,9 @@ of_regression("5MW_OC4Jckt_ExtPtfm" "openfast;elastodyn;extpt of_regression("HelicalWake_OLAF" "openfast;aerodyn;olaf") of_regression("EllipticalWing_OLAF" "openfast;aerodyn;olaf") of_regression("StC_test_OC4Semi" "openfast;servodyn;hydrodyn;moordyn;offshore;stc") -of_regression("MHK_RM1_Fixed" "openfast;elastodyn;aerodyn;mhk") -of_regression("MHK_RM1_Floating" "openfast;elastodyn;aerodyn;hydrodyn;moordyn;mhk") -of_regression("MHK_RM1_Floating_wNacDrag" "openfast;elastodyn;aerodyn;hydrodyn;moordyn;mhk") +of_regression("MHK_RM1_Fixed" "openfast;elastodyn;aerodyn;mhk;offshore") +of_regression("MHK_RM1_Floating" "openfast;elastodyn;aerodyn;hydrodyn;moordyn;mhk;offshore") +of_regression("MHK_RM1_Floating_wNacDrag" "openfast;elastodyn;aerodyn;hydrodyn;moordyn;mhk;offshore") of_regression("Tailfin_FreeYaw1DOF_PolarBased" "openfast;elastodyn;aerodyn") of_regression("Tailfin_FreeYaw1DOF_Unsteady" "openfast;elastodyn;aerodyn") of_regression("5MW_Land_DLL_WTurb_ADsk" "openfast;elastodyn;aerodisk") From bb2ab49a6cd5ab63beb468e9236202adcadbde20 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 20 May 2025 10:37:34 -0600 Subject: [PATCH 48/63] bugfix: SD maximum number of output channels was incorrect A user had a case where they wanted to output ~8000 channels from _SD_. However, there was an inconsisntency in how the `MaxOutPts` was set. To fix this: - uncomment `MaxOutPts` to `SubDyn_Output_Param.f90` - remove `MaxOutPts` from `SubDyn_Output.f90` so it is in the autogenerated file instead - remove `MaxOutChs` from `SD_FEM.f90` and use `MaxOutPts` instead --- modules/subdyn/src/SD_FEM.f90 | 1 - modules/subdyn/src/SubDyn.f90 | 3 ++- modules/subdyn/src/SubDyn_Output.f90 | 5 +---- modules/subdyn/src/SubDyn_Output_Params.f90 | 2 +- 4 files changed, 4 insertions(+), 7 deletions(-) diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index 27e72964b0..b8bbf9dcc5 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -24,7 +24,6 @@ MODULE SD_FEM INTEGER(IntKi), PARAMETER :: MaxMemJnt = 20 ! Maximum number of members at one joint - INTEGER(IntKi), PARAMETER :: MaxOutChs = 2000 ! Max number of Output Channels to be read in INTEGER(IntKi), PARAMETER :: nDOFL_TP = 6 !TODO rename me ! 6 degrees of freedom (length of u subarray [UTP]) ! values of these parameters are ordered by their place in SubDyn input file: diff --git a/modules/subdyn/src/SubDyn.f90 b/modules/subdyn/src/SubDyn.f90 index 26f1a1d44c..cacf60ec06 100644 --- a/modules/subdyn/src/SubDyn.f90 +++ b/modules/subdyn/src/SubDyn.f90 @@ -25,6 +25,7 @@ Module SubDyn USE NWTC_Library USE SubDyn_Types + USE SubDyn_Output_Params, only: MaxOutPts USE SubDyn_Output USE SubDyn_Tests USE SD_FEM @@ -1511,7 +1512,7 @@ SUBROUTINE SD_Input(SDInputFile, Init, p, ErrStat,ErrMsg) ! OutList - list of requested parameters to output to a file CALL ReadCom( UnIn, SDInputFile, 'SSOutList',ErrStat2, ErrMsg2, UnEc ); if(Failed()) return -ALLOCATE(Init%SSOutList(MaxOutChs), STAT=ErrStat2) +ALLOCATE(Init%SSOutList(MaxOutPts + p%OutAllInt*p%OutAllDims), STAT=ErrStat2) If (Check( ErrStat2 /= ErrID_None ,'Error allocating SSOutList arrays')) return CALL ReadOutputList ( UnIn, SDInputFile, Init%SSOutList, p%NumOuts, 'SSOutList', 'List of outputs requested', ErrStat2, ErrMsg2, UnEc ); if(Failed()) return CALL CleanUp() diff --git a/modules/subdyn/src/SubDyn_Output.f90 b/modules/subdyn/src/SubDyn_Output.f90 index 76d470711c..4a57fd6c3d 100644 --- a/modules/subdyn/src/SubDyn_Output.f90 +++ b/modules/subdyn/src/SubDyn_Output.f90 @@ -22,13 +22,10 @@ MODULE SubDyn_Output USE SubDyn_Types USE SD_FEM USE SubDyn_Output_Params, only: MNfmKe, MNfmMe, MNTDss, MNRDe, MNTRAe, IntfSS, IntfTRss, IntfTRAss, ReactSS, OutStrLenM1 - USE SubDyn_Output_Params, only: ParamIndxAry, ParamUnitsAry, ValidParamAry, SSqm01, SSqmd01, SSqmdd01 + USE SubDyn_Output_Params, only: ParamIndxAry, ParamUnitsAry, ValidParamAry, SSqm01, SSqmd01, SSqmdd01, MaxOutPts IMPLICIT NONE - ! The maximum number of output channels which can be output by the code. - INTEGER(IntKi),PUBLIC, PARAMETER :: MaxOutPts = 21705 - PRIVATE ! ..... Public Subroutines ................................................................................................... PUBLIC :: SDOut_CloseSum diff --git a/modules/subdyn/src/SubDyn_Output_Params.f90 b/modules/subdyn/src/SubDyn_Output_Params.f90 index f530c38508..f789c117fc 100644 --- a/modules/subdyn/src/SubDyn_Output_Params.f90 +++ b/modules/subdyn/src/SubDyn_Output_Params.f90 @@ -21757,7 +21757,7 @@ module SubDyn_Output_Params ! The maximum number of output channels which can be output by the code. - !INTEGER(IntKi), PARAMETER :: MaxOutPts = 21705 + INTEGER(IntKi), PARAMETER :: MaxOutPts = 21705 INTEGER(IntKi), PARAMETER ::MNfmKe(6,9,99) = reshape((/ & From 09db6a01ed32364040288539bf0db140dd434e36 Mon Sep 17 00:00:00 2001 From: Mayank Chetan Date: Thu, 22 May 2025 14:19:39 -0600 Subject: [PATCH 49/63] updated outlist reading using read_outlist and read_outlist_freeForm --- openfast_io/openfast_io/FAST_reader.py | 227 +++++++++---------------- openfast_io/pyproject.toml | 3 +- reg_tests/r-test | 2 +- 3 files changed, 80 insertions(+), 152 deletions(-) diff --git a/openfast_io/openfast_io/FAST_reader.py b/openfast_io/openfast_io/FAST_reader.py index b8dbc4199d..24047417a9 100644 --- a/openfast_io/openfast_io/FAST_reader.py +++ b/openfast_io/openfast_io/FAST_reader.py @@ -236,7 +236,7 @@ def loop_dict(vartree, search_var, branch): var = var.replace(' ', '') loop_dict(vartree_head, var, []) - def read_outlist_freeForm(self,f,module): + def read_outlist_freeForm(self, f, module): ''' Replacement for set_outlist that doesn't care about whether the channel is in the outlist vartree Easier, but riskier because OpenFAST can crash @@ -244,37 +244,78 @@ def read_outlist_freeForm(self,f,module): Inputs: f - file handle module - of OpenFAST, e.g. SubDyn, SeaState (these modules use this) ''' + all_channels = [] data = f.readline() - while data.split()[0] != 'END': - pattern = r'"?(.*?)"?' # grab only the text between quotes - data = re.findall(pattern, data)[0] - channels = data.split(',') # split on commas - channels = [c.strip() for c in channels] # strip whitespace - for c in channels: - self.fst_vt['outlist'][module][c] = True + + # Handle the case if there are blank lines before actual data + while data.strip() == '': + data = f.readline() + + while not data.strip().startswith('END'): + # Get part before the dash (comment) + line = data.split('-')[0] + + # Replace all delimiters with spaces + for delim in ['"', "'", ',', ';', '\t']: + line = line.replace(delim, ' ') + + # Split into words and add non-empty ones to the channel list + line_channels = [word.strip() for word in line.split() if word.strip()] + if line_channels: + all_channels.extend(line_channels) + + # Read next line data = f.readline() + + # Handle the case if there are blank lines + while data.strip() == '': + data = f.readline() + + # Store all channels in the outlist + for channel in all_channels: + self.fst_vt['outlist'][module][channel] = True - def read_outlist(self,f,module): + def read_outlist(self, f, module): ''' - Read the outlist section of the FAST input file, genralized for most modules + Read the outlist section of the FAST input file, generalized for most modules Inputs: f - file handle module - of OpenFAST, e.g. ElastoDyn, ServoDyn, AeroDyn, AeroDisk, etc. + Returns: List of channel names ''' - data = f.readline().split()[0] # to counter if we dont have any quotes - while data != 'END': - if data.find('"')>=0: - channels = data.split('"') - channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - channel_list = [row_string[0].split('\n')[0]] - else: - channel_list = row_string - self.set_outlist(self.fst_vt['outlist'][module], channel_list) - data = f.readline().split()[0] # to counter if we dont have any quotes + all_channels = [] + data = f.readline() + + # Handle the case if there are blank lines before actual data + while data.strip() == '': + data = f.readline() + + while not data.strip().startswith('END'): + # Get part before the dash (comment) + line = data.split('-')[0] + + # Replace all delimiters with spaces + for delim in ['"', "'", ',', ';', '\t']: + line = line.replace(delim, ' ') + + # Split into words and add non-empty ones to the channel list + line_channels = [word.strip() for word in line.split() if word.strip()] + if line_channels: + all_channels.extend(line_channels) + + # Read next line + data = f.readline() + + # Handle the case if there are blank lines + while data.strip() == '': + data = f.readline() + + # Store all channels in the outlist + if all_channels: + self.set_outlist(self.fst_vt['outlist'][module], all_channels) + + return all_channels def read_MainInput(self): # Main FAST v8.16-v8.17 Input File @@ -557,38 +598,10 @@ def read_ElastoDyn(self, ed_file): self.fst_vt['ElastoDyn']['BldGagNd'] = read_array(f,self.fst_vt['ElastoDyn']['NBlGages'], array_type=int) else: self.fst_vt['ElastoDyn']['BldGagNd'] = 0 - f.readline() - - # Loop through output channel lines + + f.readline() - data = f.readline() - # if data != '': - # while data.split()[0] != 'END': - # channels = data.split('"') - # channel_list = channels[1].split(',') - # self.set_outlist(self.fst_vt['outlist']['ElastoDyn'], channel_list) - - # data = f.readline() - # else: - # # there is a blank line between the outlist and the END of the file - # f.readline() - - # Handle the case if there are blank lines before the END statement, check if blank line - while data.split().__len__() == 0: - data = f.readline() - - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - channel_list = row_string[0].split('\n')[0] - else: - channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['ElastoDyn'], channel_list) - data = f.readline() + self.read_outlist(f,'ElastoDyn') # ElastoDyn optional outlist try: @@ -597,19 +610,7 @@ def read_ElastoDyn(self, ed_file): self.fst_vt['ElastoDyn']['BldNd_BlOutNd'] = f.readline().split()[0] f.readline() - data = f.readline() - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - opt_channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - opt_channel_list = row_string[0].split('\n')[0] - else: - opt_channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['ElastoDyn_Nodes'], opt_channel_list) - data = f.readline() + self.read_outlist(f,'ElastoDyn') except: # The optinal outlist does not exist. None @@ -856,13 +857,9 @@ def read_BeamDyn(self, bd_file, BladeNumber = 0): self.fst_vt['BeamDyn'][BladeNumber]['OutNd'] = [idx.strip() for idx in f.readline().split('OutNd')[0].split(',')] # BeamDyn Outlist f.readline() - data = f.readline() - while data.split()[0] != 'END': - channels = data.split('"') - channel_list = channels[1].split(',') - self.set_outlist(self.fst_vt['outlist']['BeamDyn'], channel_list) - data = f.readline() - + + self.read_outlist(f,'BeamDyn') + # BeamDyn optional outlist try: f.readline() @@ -870,19 +867,8 @@ def read_BeamDyn(self, bd_file, BladeNumber = 0): self.fst_vt['BeamDyn'][BladeNumber]['BldNd_BlOutNd'] = f.readline().split()[0] f.readline() - data = f.readline() - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - opt_channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - opt_channel_list = row_string[0].split('\n')[0] - else: - opt_channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['BeamDyn_Nodes'], opt_channel_list) - data = f.readline() + + self.read_outlist(f,'BeamDyn_Nodes') except: # The optinal outlist does not exist. None @@ -1025,19 +1011,7 @@ def read_InflowWind(self): # InflowWind Outlist f.readline() - data = f.readline() - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - channel_list = row_string[0].split('\n')[0] - else: - channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['InflowWind'], channel_list) - data = f.readline() + self.read_outlist(f,'InflowWind') f.close() @@ -1194,25 +1168,9 @@ def read_AeroDyn(self): # AeroDyn Outlist f.readline() - data = f.readline() - - # Handle the case if there are blank lines before the END statement, check if blank line - while data.split().__len__() == 0: - data = f.readline() + self.read_outlist(f,'AeroDyn') - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - channel_list = row_string[0].split('\n')[0] - else: - channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['AeroDyn'], channel_list) - data = f.readline() # AeroDyn optional outlist try: @@ -1221,19 +1179,7 @@ def read_AeroDyn(self): self.fst_vt['AeroDyn']['BldNd_BlOutNd'] = f.readline().split()[0] f.readline() - data = f.readline() - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - opt_channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - opt_channel_list = row_string[0].split('\n')[0] - else: - opt_channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['AeroDyn_Nodes'], opt_channel_list) - data = f.readline() + self.read_outlist(f,'AeroDyn_Nodes') except: # The optinal outlist does not exist. None @@ -1702,12 +1648,7 @@ def read_ServoDyn(self): # ServoDyn Outlist f.readline() - data = f.readline() - while data.split()[0] != 'END': - channels = data.split('"') - channel_list = channels[1].split(',') - self.set_outlist(self.fst_vt['outlist']['ServoDyn'], channel_list) - data = f.readline() + self.read_outlist(f,'ServoDyn') f.close() @@ -2230,19 +2171,7 @@ def read_HydroDyn(self, hd_file): # HydroDyn Outlist f.readline() - data = f.readline() - while data.split()[0] != 'END': - if data.find('"')>=0: - channels = data.split('"') - channel_list = channels[1].split(',') - else: - row_string = data.split(',') - if len(row_string)==1: - channel_list = row_string[0].split('\n')[0] - else: - channel_list = row_string - self.set_outlist(self.fst_vt['outlist']['AeroDyn'], channel_list) - data = f.readline() + self.read_outlist(f, 'HydroDyn') f.close() diff --git a/openfast_io/pyproject.toml b/openfast_io/pyproject.toml index 6eb3e86f8d..dff12fefa0 100644 --- a/openfast_io/pyproject.toml +++ b/openfast_io/pyproject.toml @@ -5,7 +5,7 @@ build-backend = "hatchling.build" [project] name = "openfast_io" # dynamic = ["version"] -version = "4.0.4" +version = "4.0.5" description = "Readers and writers for OpenFAST files." license = {file = "../LICENSE"} authors = [ @@ -39,7 +39,6 @@ classifiers = [ # Optional # Specify the Python versions you support here. In particular, ensure # that you indicate you support Python 3. These classifiers are *not* # checked by "pip install". See instead "python_requires" below. - "Programming Language :: Python :: 3.9", "Programming Language :: Python :: 3.10", "Programming Language :: Python :: 3.11", "Programming Language :: Python :: 3.12", diff --git a/reg_tests/r-test b/reg_tests/r-test index df9ee7dae9..1a507acf7f 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit df9ee7dae97c20aa9664f11dc9daafd73f12ab3a +Subproject commit 1a507acf7f055fc49f9127274eb4d7e304ec60f6 From 0cb48572aa0c4bf54a4a72ee910bb5a8c0d23731 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Thu, 22 May 2025 14:59:41 -0600 Subject: [PATCH 50/63] FF: typo in SeaState names in MD_Shared .fst files Co-authored-by: Yuksel-Rudy --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index df9ee7dae9..a4b4fdb20a 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit df9ee7dae97c20aa9664f11dc9daafd73f12ab3a +Subproject commit a4b4fdb20a1a97554eb7c8fabfbbcb147a05150e From 539700b449e7b7ed4dddf593f578f74271add541 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Thu, 22 May 2025 17:07:53 -0600 Subject: [PATCH 51/63] [BugFix] OF: VTK_fps=0 triggers failing code --- modules/openfast-library/src/FAST_Subs.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/openfast-library/src/FAST_Subs.f90 b/modules/openfast-library/src/FAST_Subs.f90 index 1b0050734c..e42fb02a37 100644 --- a/modules/openfast-library/src/FAST_Subs.f90 +++ b/modules/openfast-library/src/FAST_Subs.f90 @@ -3717,7 +3717,7 @@ SUBROUTINE FAST_ReadPrimaryFile( InputFile, p, m_FAST, OverrideAbortErrLev, ErrS IF (p%WrVTK == VTK_ModeShapes) THEN p%n_VTKTime = 1 ELSE IF (TmpTime > p%TMax) THEN - p%n_VTKTime = HUGE(p%n_VTKTime) + p%n_VTKTime = NINT( p%TMax / p%DT ) ! write at init and last step only ELSE p%n_VTKTime = NINT( TmpTime / p%DT ) ! I'll warn if p%n_VTKTime*p%DT is not TmpTime From b17ddd8d62876115021bd36e4a81a286dade681e Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Fri, 23 May 2025 13:52:30 -0600 Subject: [PATCH 52/63] Update r-test pointer --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index 1a507acf7f..4e984dadfb 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit 1a507acf7f055fc49f9127274eb4d7e304ec60f6 +Subproject commit 4e984dadfb38b88d57f4970eb968651c40546745 From 0d788a03168c7aa34eee84c960c30a16ce4d6e9f Mon Sep 17 00:00:00 2001 From: Mayank Chetan Date: Fri, 23 May 2025 14:59:15 -0600 Subject: [PATCH 53/63] update pointer --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index 4e984dadfb..60ff5f7edb 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit 4e984dadfb38b88d57f4970eb968651c40546745 +Subproject commit 60ff5f7edb0f938f1bc127c4bae17de54789a68b From d6433237c7f8cbe80b3336ff1abfa8f2d8395d36 Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Thu, 5 Jun 2025 10:16:24 -0600 Subject: [PATCH 54/63] Bug fix: remove spaces in OLAF's UA summary file name UA summary file names had spaces when generated with OLAF simulations. The wing/blade number was 11 characters, so most files had 10 spaces in the middle of the file name: .W<11 character number with spaces>.UA.sum --- modules/aerodyn/src/FVW.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/aerodyn/src/FVW.f90 b/modules/aerodyn/src/FVW.f90 index 92b43acfbb..5b519f14c8 100644 --- a/modules/aerodyn/src/FVW.f90 +++ b/modules/aerodyn/src/FVW.f90 @@ -1601,7 +1601,7 @@ subroutine UA_Init_Wrapper(AFInfo, InitInp, interval, p, x, xd, OtherState, m, E do i = 1,InitInp%numBladeNodes InitInp%UA_Init%c(i,1) = p%W(iW)%chord_LL(i) ! NOTE: InitInp chord move-allocd to p end do - InitInp%UA_Init%OutRootName = trim(InitInp%RootName)//'W'//num2lstr(iW)//'.UA' + InitInp%UA_Init%OutRootName = trim(InitInp%RootName)//'W'//trim(num2lstr(iW))//'.UA' InitInp%UA_Init%ShedEffect = .False. ! Important, when coupling UA wih vortex code, shed vorticity is inherently accounted for InitInp%UA_Init%UAOff_innerNode(1) = InitInp%W(iW)%UAOff_innerNode From c7529628d1c7b8ebdbcac6b8153539f7ea3ef20e Mon Sep 17 00:00:00 2001 From: Bonnie Jonkman Date: Thu, 5 Jun 2025 10:16:24 -0600 Subject: [PATCH 55/63] Bug fix: remove spaces in OLAF's UA summary file name UA summary file names had spaces when generated with OLAF simulations. The wing/blade number was 11 characters, so most files had 10 spaces in the middle of the file name: .W<11 character number with spaces>.UA.sum --- modules/aerodyn/src/FVW.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/aerodyn/src/FVW.f90 b/modules/aerodyn/src/FVW.f90 index 2c55f4dc27..7f2bc8a9e5 100644 --- a/modules/aerodyn/src/FVW.f90 +++ b/modules/aerodyn/src/FVW.f90 @@ -1601,7 +1601,7 @@ subroutine UA_Init_Wrapper(AFInfo, InitInp, interval, p, x, xd, OtherState, m, E do i = 1,InitInp%numBladeNodes InitInp%UA_Init%c(i,1) = p%W(iW)%chord_LL(i) ! NOTE: InitInp chord move-allocd to p end do - InitInp%UA_Init%OutRootName = trim(InitInp%RootName)//'W'//num2lstr(iW)//'.UA' + InitInp%UA_Init%OutRootName = trim(InitInp%RootName)//'W'//trim(num2lstr(iW))//'.UA' InitInp%UA_Init%ShedEffect = .False. ! Important, when coupling UA wih vortex code, shed vorticity is inherently accounted for InitInp%UA_Init%UAOff_innerNode(1) = InitInp%W(iW)%UAOff_innerNode From 9fc2da5daa3b8866e84d1353c466bf45ff24e923 Mon Sep 17 00:00:00 2001 From: leopardracer <136604165+leopardracer@users.noreply.github.com> Date: Wed, 11 Jun 2025 11:22:16 +0300 Subject: [PATCH 56/63] Update intermittentCrushing.F90 --- modules/icefloe/src/icefloe/intermittentCrushing.F90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/icefloe/src/icefloe/intermittentCrushing.F90 b/modules/icefloe/src/icefloe/intermittentCrushing.F90 index e88caf4172..feb3601701 100644 --- a/modules/icefloe/src/icefloe/intermittentCrushing.F90 +++ b/modules/icefloe/src/icefloe/intermittentCrushing.F90 @@ -80,7 +80,7 @@ subroutine initInterCrushing (iceInput, myIceParams, iceLog) end subroutine initInterCrushing !**************************************************************************** -! Continuous crushing uses the standard inerpolation routine +! Continuous crushing uses the standard interpolation routine ! of the precalculated time series function outputInterCrushLoad (myIceParams, iceLog, time) result(iceLoads) type(iceFloe_ParameterType), intent(in) :: myIceParams @@ -91,4 +91,4 @@ function outputInterCrushLoad (myIceParams, iceLog, time) result(iceLoads) iceLoads = outputCrushLoadISO (myIceParams, iceLog, time) end function outputInterCrushLoad -end module iceIntermittentCrushing \ No newline at end of file +end module iceIntermittentCrushing From e507ac8bb5185908b10408c7a011e6845a62a14c Mon Sep 17 00:00:00 2001 From: leopardracer <136604165+leopardracer@users.noreply.github.com> Date: Wed, 11 Jun 2025 11:22:57 +0300 Subject: [PATCH 57/63] Update randomCrushing.F90 --- modules/icefloe/src/icefloe/randomCrushing.F90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/icefloe/src/icefloe/randomCrushing.F90 b/modules/icefloe/src/icefloe/randomCrushing.F90 index 9996a40321..c55af26098 100644 --- a/modules/icefloe/src/icefloe/randomCrushing.F90 +++ b/modules/icefloe/src/icefloe/randomCrushing.F90 @@ -163,7 +163,7 @@ end subroutine randomCrushLoadTimeSeries end subroutine initRandomCrushing ! containing subroutine !**************************************************************************** -! Continuous crushing uses the standard inerpolation routine +! Continuous crushing uses the standard interpolation routine ! of the precalculated time series function outputRandomCrushLoad (myIceParams, iceLog, time) result(iceLoads) type(iceFloe_ParameterType), intent(in) :: myIceParams @@ -174,4 +174,4 @@ function outputRandomCrushLoad (myIceParams, iceLog, time) result(iceLoads) iceLoads = outputCrushLoadISO (myIceParams, iceLog, time) end function outputRandomCrushLoad -end module randomCrushing \ No newline at end of file +end module randomCrushing From c3e9c8a0d96c47d21366e92580b4a3d39c100924 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 10 Jun 2025 12:04:27 -0600 Subject: [PATCH 58/63] rc4.0.5: update release notes and version info --- docs/changelogs/v4.0.5.md | 109 ++++++++++++++++++++++++++++++++ docs/conf.py | 2 +- docs/source/user/api_change.rst | 6 ++ 3 files changed, 116 insertions(+), 1 deletion(-) create mode 100644 docs/changelogs/v4.0.5.md diff --git a/docs/changelogs/v4.0.5.md b/docs/changelogs/v4.0.5.md new file mode 100644 index 0000000000..067cba5283 --- /dev/null +++ b/docs/changelogs/v4.0.5.md @@ -0,0 +1,109 @@ +**Feature or improvement description** +Pull request to merge `rc-4.0.5` into `main` and create a tagged release for v4.0.5 + +See the milestone and project pages for additional information + + https://github.com/OpenFAST/openfast/milestone/22 + +Test results, if applicable +See GitHub Actions + +### Release checklist: +- [ ] Update the documentation version in docs/conf.py +- [ ] Update the versions in docs/source/user/api\_change.rst +- [ ] Update version info in openfast\_io/pyproject.toml +- [ ] Verify readthedocs builds correctly +- [ ] Create an annotated tag in OpenFAST during merge (mark as most recent if necessary) +- [ ] Create a merge commit in r-test and add a corresponding annotated tag +- [ ] Upload Docker image +- [ ] Compile executables for Windows builds + - [ ] `AeroDisk_Driver_x64.exe` + - [ ] `AeroDyn_Driver_x64.exe` + - [ ] `AeroDyn_Driver_x64_OpenMP.exe` + - [ ] `AeroDyn_Inflow_c_binding_x64.dll` + - [ ] `AeroDyn_Inflow_c_binding_x64_OpenMP.dll` + - [ ] `BeamDyn_Driver_x64.exe` + - [ ] `DISCON.dll (x64)` + - [ ] `DISCON_ITIBarge.dll (x64)` + - [ ] `DISCON_OC3Hywind.dll (x64)` + - [ ] `DISCON_SC.dll (x64)` + - [ ] `FAST.Farm_x64.exe` + - [ ] `FAST.Farm_x64_OMP.exe` + - [ ] `FAST_SFunc.mexw64` + - [ ] `HydroDynDriver_x64.exe` + - [ ] `HydroDyn_C_Binding_x64.dll` + - [ ] `IinflowWind_c_binding_x64.dll` + - [ ] `InflowWind_Driver_x64.exe` + - [ ] `InflowWind_Driver_x64_OpenMP.exe` + - [ ] `MoorDyn_Driver_x64.exe` + - [ ] `MoorDyn_c_binding_x64.dll` + - [ ] `OpenFAST-Simulink_x64.dll` + - [ ] `openfast_x64.exe` + - [ ] `SeaStateDriver_x64.exe` + - [ ] `SimpleElastoDyn_x64.exe` + - [ ] `SubDyn_x64.exe` + - [ ] `Turbsim_x64.exe` + - [ ] `UnsteadyAero_x64.exe` + +# Changelog + +## Overview + +This release includes several bug fixes and improvements for _OpenFAST_, GitHub actions, and _openfast\_io_. + +## General + +### CMake build system + +### GitHub actions + +#2825 Simplify GitHub Action for regression tests (backport from dev-tc) (@deslaughter) + + +### openfast_io + +#2828 updated outlist reading in openfast\_io (@mayankchetan) + +#2818 OpenFAST IO updates: MoorDyn and StC (@dzalkind) + +## Solvers + +### OpenFAST + +#2831 [BugFix] WrVTK with VTK\_fps fails (@andrew-platt) + + +## Interfaces + +### cpp interface + +#2792 Fix openfastcpp restart parsing of file name (@marchdf) + +#2804 Add a checkError in openfast cpp (@marchdf) + +#2815 Fix restart parsing of file name (backport of #2792 and #2793) (@marchdf) + + +## Module changes + +### AeroDyn + +#2853 Backport #2848 (@bjonkman) + + +### BeamDyn + +#2811 BD: new output - aero only loads mapped to the root (@andrew-platt) + + +### SubDyn + +#2821 bugfix: SD maximum number of output channels was incorrectly set (@andrew-platt) + + +## Input file changes + +No input file changes since v4.0.0 + +#2829 FF: typo in SeaState names in `MD_Shared` .fst files - this is not an API change (@andrew-platt) + diff --git a/docs/conf.py b/docs/conf.py index 6e5c983e0f..893919751f 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -138,7 +138,7 @@ def runDoxygen(sourcfile, doxyfileIn, doxyfileOut): # The short X.Y version. version = u'4.0' # The full version, including alpha/beta/rc tags. -release = u'v4.0.4' +release = u'v4.0.5' # The language for content autogenerated by Sphinx. Refer to documentation # for a list of supported languages. diff --git a/docs/source/user/api_change.rst b/docs/source/user/api_change.rst index 054ac176ea..fc8460442b 100644 --- a/docs/source/user/api_change.rst +++ b/docs/source/user/api_change.rst @@ -10,6 +10,12 @@ The line number corresponds to the resulting line number after all changes are i Thus, be sure to implement each in order so that subsequent line numbers are correct. +OpenFAST v4.0.4 to OpenFAST v4.0.5 +---------------------------------- + +No input file changes were made. + + OpenFAST v4.0.3 to OpenFAST v4.0.4 ---------------------------------- From ff23a38aa66469480895cb172b01c862a31e6256 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Wed, 11 Jun 2025 09:30:29 -0600 Subject: [PATCH 59/63] release notes: include PR 2855 --- docs/changelogs/v4.0.5.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/docs/changelogs/v4.0.5.md b/docs/changelogs/v4.0.5.md index 067cba5283..11173b3121 100644 --- a/docs/changelogs/v4.0.5.md +++ b/docs/changelogs/v4.0.5.md @@ -66,6 +66,8 @@ This release includes several bug fixes and improvements for _OpenFAST_, GitHub #2818 OpenFAST IO updates: MoorDyn and StC (@dzalkind) + + ## Solvers ### OpenFAST @@ -96,6 +98,11 @@ This release includes several bug fixes and improvements for _OpenFAST_, GitHub #2811 BD: new output - aero only loads mapped to the root (@andrew-platt) +### IceFlow + +#2855 Fix Typo in "interpolation" in Ice Crushing Modules (@leopardracer) + + ### SubDyn #2821 bugfix: SD maximum number of output channels was incorrectly set (@andrew-platt) From bd0d00dc100ae3db3b7a1ce86add50d7e85ede66 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 16 Jun 2025 11:17:53 -0600 Subject: [PATCH 60/63] Manual apply PR 2816 from 4.0.5 to MoorDyn_Misc --- modules/moordyn/src/MoorDyn_Misc.f90 | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/modules/moordyn/src/MoorDyn_Misc.f90 b/modules/moordyn/src/MoorDyn_Misc.f90 index 92aec168ed..53d41b8a81 100644 --- a/modules/moordyn/src/MoorDyn_Misc.f90 +++ b/modules/moordyn/src/MoorDyn_Misc.f90 @@ -1669,10 +1669,10 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ENDDO ! Initialize the FFT - CALL InitFFT ( NStepWave, FFT_Data, .FALSE., ErrStat2 ); ErrMsg2 = 'Error occured while initializing the FFT.'; IF(Failed()) RETURN + CALL InitFFT ( NStepWave, FFT_Data, .FALSE., ErrStat2 ); ErrMsg2 = 'Error occurred while initializing the FFT.'; IF(Failed()) RETURN ! Apply the forward FFT on the wave elevation timeseries to get the real and imaginary parts of the frequency information. - CALL ApplyFFT_f ( TmpFFTWaveElev(:), FFT_Data, ErrStat2 ); ErrMsg2 = 'Error occured while applying the forwards FFT to TmpFFTWaveElev array.'; IF(Failed()) RETURN ! Note that the TmpFFTWaveElev now contains the real and imaginary bits. + CALL ApplyFFT_f ( TmpFFTWaveElev(:), FFT_Data, ErrStat2 ); ErrMsg2 = 'Error occurred while applying the forwards FFT to TmpFFTWaveElev array.'; IF(Failed()) RETURN ! Note that the TmpFFTWaveElev now contains the real and imaginary bits. ! Copy the resulting TmpFFTWaveElev(:) data over to the WaveElevC0 array DO I=1,NStepWave2-1 @@ -1681,7 +1681,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ENDDO WaveElevC0(:,NStepWave2) = 0.0_SiKi - CALL ExitFFT(FFT_Data, ErrStat2); ErrMsg2 = 'Error occured while cleaning up after the FFTs.'; IF(Failed()) RETURN + CALL ExitFFT(FFT_Data, ErrStat2); ErrMsg2 = 'Error occurred while cleaning up after the FFTs.'; IF(Failed()) RETURN IF (ALLOCATED( WaveElev0 )) DEALLOCATE( WaveElev0 , STAT=ErrStat2); ErrMsg2 = 'Cannot deallocate WaveElev0.' ; IF (Failed0()) RETURN IF (ALLOCATED( TmpFFTWaveElev )) DEALLOCATE( TmpFFTWaveElev, STAT=ErrStat2); ErrMsg2 = 'Cannot deallocate TmpFFTWaveElev.'; IF (Failed0()) RETURN @@ -1726,7 +1726,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) END DO ! set up FFTer for doing IFFTs - CALL InitFFT ( NStepWave, FFT_Data, .TRUE., ErrStat2 ); ErrMsg2 = 'Error occured while initializing the FFT.'; IF(Failed()) RETURN + CALL InitFFT ( NStepWave, FFT_Data, .TRUE., ErrStat2 ); ErrMsg2 = 'Error occurred while initializing the FFT.'; IF(Failed()) RETURN ! Loop through all points where the incident wave kinematics will be computed DO ix = 1,p%nxWave @@ -1767,7 +1767,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ! could also reproduce the wave elevation at 0,0,0 on a separate channel for verIFication... - CALL ExitFFT(FFT_Data, ErrStat2); ErrMsg2 = 'Error occured while cleaning up after the IFFTs.'; IF(Failed()) RETURN + CALL ExitFFT(FFT_Data, ErrStat2); ErrMsg2 = 'Error occurred while cleaning up after the IFFTs.'; IF(Failed()) RETURN end if ! p%WaveKin == 3 From d02f50c6af82cd6731116eaa6ddb4e07d5cdc376 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 16 Jun 2025 11:23:59 -0600 Subject: [PATCH 61/63] Update r-test pointer (added __pycache__ to .gitignore) --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index 4e2953e797..a470bfa7b0 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit 4e2953e797d0408814acf62a3636074673180a5d +Subproject commit a470bfa7b0e51663015243d8639907ff6431a7da From 72adfa79489d9672ddca4b1ecd85ad3823b367be Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 16 Jun 2025 11:57:07 -0600 Subject: [PATCH 62/63] Bad merge of MoorDyn_Misc.f90 --- modules/moordyn/src/MoorDyn_Misc.f90 | 54 +--------------------------- 1 file changed, 1 insertion(+), 53 deletions(-) diff --git a/modules/moordyn/src/MoorDyn_Misc.f90 b/modules/moordyn/src/MoorDyn_Misc.f90 index 53d41b8a81..4454c207f0 100644 --- a/modules/moordyn/src/MoorDyn_Misc.f90 +++ b/modules/moordyn/src/MoorDyn_Misc.f90 @@ -1189,58 +1189,8 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) FileName = trim(WaterKinString) END IF - ! Set the values - TmpFFTWaveElev = 0.0_DbKi - WaveElevC0(:,:) = 0.0_DbKi - ! Copy values over - DO I=0, MIN(SIZE(WaveElev0), NStepWave)-1 - TmpFFTWaveElev(I) = WaveElev0(I) - ENDDO - - ! Initialize the FFT - CALL InitFFT ( NStepWave, FFT_Data, .FALSE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.',ErrStat,ErrMsg,RoutineName); if(Failed()) return - - ! Apply the forward FFT to get the real and imaginary parts of the frequency information. - CALL ApplyFFT_f ( TmpFFTWaveElev(:), FFT_Data, ErrStatTmp ) ! Note that the TmpFFTWaveElev now contains the real and imaginary bits. - CALL SetErrStat(ErrStatTmp,'Error occurred while applying the forwards FFT to TmpFFTWaveElev array.',ErrStat,ErrMsg,RoutineName); if(Failed()) return - - ! Copy the resulting TmpFFTWaveElev(:) data over to the WaveElevC0 array - DO I=1,NStepWave2-1 - WaveElevC0 (1,I) = TmpFFTWaveElev(2*I-1) - WaveElevC0 (2,I) = TmpFFTWaveElev(2*I) - ENDDO - WaveElevC0(:,NStepWave2) = 0.0_SiKi - - CALL ExitFFT(FFT_Data, ErrStatTmp) - CALL SetErrStat(ErrStatTmp,'Error occurred while cleaning up after the FFTs.', ErrStat,ErrMsg,RoutineName); if(Failed()) return - - - IF (ALLOCATED( WaveElev0 )) DEALLOCATE( WaveElev0 , STAT=ErrStatTmp) - IF (ALLOCATED( TmpFFTWaveElev )) DEALLOCATE( TmpFFTWaveElev, STAT=ErrStatTmp) - - - - ! note: following is a very streamlined adaptation from from Waves.v90 VariousWaves_Init - - ! allocate all the wave kinematics FFT arrays - ALLOCATE( WaveNmbr (0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveNmbr. ',ErrStat,ErrMsg,RoutineName) - ALLOCATE( tmpComplex(0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate tmpComplex.',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveElevC (0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveElevC .',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveDynPC (0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveDynPC .',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveVelCHx(0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveVelCHx.',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveVelCHy(0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveVelCHy.',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveVelCV (0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveVelCV .',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveAccCHx(0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveAccCHx.',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveAccCHy(0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveAccCHy.',ErrStat,ErrMsg,RoutineName) - ALLOCATE( WaveAccCV (0:NStepWave2), STAT=ErrStatTmp); CALL SetErrStat(ErrStatTmp,'Cannot allocate WaveAccCV .',ErrStat,ErrMsg,RoutineName) - - ! allocate time series grid data arrays (now that we know the number of time steps coming from the IFFTs) - CALL allocateKinematicsArrays() - - UnEcho=-1 CALL GetNewUnit( UnIn ) CALL OpenFInpFile( UnIn, FileName, ErrStat2, ErrMsg2); IF(Failed()) RETURN @@ -1431,9 +1381,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) ! ------------------- start with wave kinematics ----------------------- - ! set up FFTer for doing IFFTs - CALL InitFFT ( NStepWave, FFT_Data, .TRUE., ErrStatTmp ) - CALL SetErrStat(ErrStatTmp,'Error occurred while initializing the FFT.', ErrStat, ErrMsg, routineName); if(Failed()) return + IF (p%WaveKin > 0) THEN ! Check that all wave grid z values are below the water line, otherwise COSHNumOvrCOSHDen calcs will nan DO I=1,p%nzWave From 582aa525901020ec4dedf2183b34a425520166c5 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Mon, 16 Jun 2025 12:00:37 -0600 Subject: [PATCH 63/63] MD: fix bad merge, try 2 --- modules/moordyn/src/MoorDyn_Misc.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/moordyn/src/MoorDyn_Misc.f90 b/modules/moordyn/src/MoorDyn_Misc.f90 index 4454c207f0..4466718db2 100644 --- a/modules/moordyn/src/MoorDyn_Misc.f90 +++ b/modules/moordyn/src/MoorDyn_Misc.f90 @@ -1717,7 +1717,7 @@ SUBROUTINE setupWaterKin(WaterKinString, p, Tmax, ErrStat, ErrMsg) CALL ExitFFT(FFT_Data, ErrStat2); ErrMsg2 = 'Error occurred while cleaning up after the IFFTs.'; IF(Failed()) RETURN - end if ! p%WaveKin == 3 + END IF ! p%WaveKin > 0 ! --------------------------------- now do currents --------------------------------