From f40b0de14400d3c2f47b049b84b61e486ff88f6d Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Tue, 9 May 2017 14:26:04 -0600 Subject: [PATCH 001/386] Updated initialization of Vx_wake --- .../wakedynamics/src/WakeDynamics.f90 | 63 +++++++++++++++++-- 1 file changed, 57 insertions(+), 6 deletions(-) diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index c481e59dfc..1672086115 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -585,7 +585,7 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! Check if we are fully initialized if ( OtherState%firstPass ) then - call InitStatesWithInputs(p%NumPlanes, p%NumRadii, u, p, xd, errStat2, errMsg2) + call InitStatesWithInputs(p%NumPlanes, p%NumRadii, u, p, xd, m, errStat2, errMsg2) call SetErrStat(errStat2, errMsg2, errStat, errMsg, RoutineName) OtherState%firstPass = .false. if (errStat >= AbortErrLev) then @@ -995,17 +995,19 @@ subroutine WD_CalcConstrStateResidual( Time, u, p, x, xd, z, OtherState, m, z_re end subroutine WD_CalcConstrStateResidual -subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, errStat, errMsg) +subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMsg) integer(IntKi), intent(in ) :: numPlanes integer(IntKi), intent(in ) :: numRadii TYPE(WD_InputType), intent(in ) :: u !< Inputs at Time TYPE(WD_ParameterType), intent(in ) :: p !< Parameters TYPE(WD_DiscreteStateType), intent(inout) :: xd !< Discrete states at Time + type(WD_MiscVarType), intent(inout) :: m !< Misc/optimization variables INTEGER(IntKi), intent( out) :: errStat !< Error status of the operation CHARACTER(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None character(*), parameter :: RoutineName = 'InitStatesWithInputs' - integer(IntKi) :: i + integer(IntKi) :: i,j, ILo + real(ReKi) :: a_interp integer(intKi) :: ErrStat2 character(ErrMsgLen) :: ErrMsg2 real(ReKi) :: correction(3) @@ -1034,9 +1036,8 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, errStat, errMsg) xd%Vx_wind_disk_filt(i) = u%Vx_wind_disk xd%TI_amb_filt (i) = u%TI_amb xd%D_rotor_filt (i) = u%D_rotor - ! Vx_wake and Vr_wake are already initialized to zero so we do not need to do that here. - !xd%Vx_wake(j,i) = 0.0_ReKi - !xd%Vr_wake(j,i) = 0.0_ReKi + + end do ! Only need to set the 0 index because everything else is already initialized to zero. @@ -1047,6 +1048,56 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, errStat, errMsg) xd%Ct_azavg_filt (i) = u%Ct_azavg(i) end do + + m%r_wake(0) = 0.0_ReKi + + do j=0,p%NumRadii-1 + + xd%Ct_azavg_filt (j) = u%Ct_azavg(j) + + ! compute m%a using the [n+1] values of Ct_azavg_filt + if ( xd%Ct_azavg_filt(j) > 2.0_ReKi ) then + ! THROW ERROR because we are in the prop-brake region + ! TEST: E5 + call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., u%Ct_azavg(j) > 2.0.', errStat, errMsg, RoutineName) + + return + else if ( xd%Ct_azavg_filt(j) >= 24.0_ReKi/25.0_ReKi ) then + m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*xd%Ct_azavg_filt(j)-12.0_ReKi))/14.0_ReKi + else + m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-xd%Ct_azavg_filt(j)) + end if + + if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then + ! TEST: E6 + call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) + + return + end if + + if (j > 0) then + m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) + end if + + end do + + ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake + + ! Use the [n+1] version of xd%Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) + xd%Vx_wake(0,0) = - xd%Vx_rel_disk_filt*p%C_Nearwake*m%a(0) + xd%Vx_wake(0,1) = xd%Vx_wake(0,0) + + ILo = 0 + do j=1, p%NumRadii-1 + + ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation + a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + + ! [n+1] + xd%Vx_wake(j,0) = -xd%Vx_rel_disk_filt*p%C_NearWake*a_interp + xd%Vx_wake(j,1) = xd%Vx_wake(j,0) + end do + end subroutine InitStatesWithInputs !---------------------------------------------------------------------------------------------------------------------------------- From 620a8e07734636e60372914afb5a92dbb00587c3 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Tue, 9 May 2017 16:53:40 -0600 Subject: [PATCH 002/386] Updated initialization of Vx_wake Now also in WD_CalcOutput --- .../wakedynamics/src/WakeDynamics.f90 | 63 ++++++++++++++++--- 1 file changed, 53 insertions(+), 10 deletions(-) diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index 1672086115..e2cc8fc625 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -855,12 +855,13 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) integer, parameter :: indx = 1 - integer(intKi) :: n, i, j + integer(intKi) :: n, i, j, ILo integer(intKi) :: ErrStat2 character(ErrMsgLen) :: ErrMsg2 character(*), parameter :: RoutineName = 'WD_CalcOutput' real(ReKi) :: correction(3) real(ReKi) :: x_plane + real(ReKi) :: a_interp errStat = ErrID_None errMsg = "" @@ -895,13 +896,57 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) return end if - do j = 0, p%NumRadii - 1 - y%Vx_wake(j,i) = 0.0_ReKi - y%Vr_wake(j,i) = 0.0_ReKi - end do - end do + + + ! Initialze Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. + + m%r_wake(0) = 0.0_ReKi + do j=0,p%NumRadii-1 + + ! compute m%a using the [n+1] values of Ct_azavg_filt + if ( u%Ct_azavg(j) > 2.0_ReKi ) then + ! THROW ERROR because we are in the prop-brake region + ! TEST: E5 + call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., u%Ct_azavg(j) > 2.0.', errStat, errMsg, RoutineName) + + return + else if ( u%Ct_azavg(j) >= 24.0_ReKi/25.0_ReKi ) then + m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*u%Ct_azavg(j)-12.0_ReKi))/14.0_ReKi + else + m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-u%Ct_azavg(j)) + end if + + if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then + ! TEST: E6 + call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) + + return + end if + + if (j > 0) then + m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) + end if + + end do + + ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake + + ! Use the [n+1] version of xd%Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) + y%Vx_wake(0,0) = - u%Vx_rel_disk*p%C_Nearwake*m%a(0) + y%Vx_wake(0,1) = y%Vx_wake(0,0) + + ILo = 0 + do j=1, p%NumRadii-1 + + ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation + a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + + ! [n+1] + y%Vx_wake(j,0) = -u%Vx_rel_disk*p%C_NearWake*a_interp + y%Vx_wake(j,1) = y%Vx_wake(j,0) + end do return @@ -1044,10 +1089,8 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs xd%Vx_rel_disk_filt = u%Vx_rel_disk - do i = 0, numRadii - 1 - xd%Ct_azavg_filt (i) = u%Ct_azavg(i) - end do - + + ! Initialze Ct_azavg_filt and Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. m%r_wake(0) = 0.0_ReKi From 2821b0c09bb2c3412ff0f5de803afc1e6df04c8c Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Wed, 10 May 2017 17:00:05 -0600 Subject: [PATCH 003/386] Updated FAST.Farm Based on Rev. 13 of the Plan Fixed a bug in the horizontal wake-deflection correction. Added a low-pass time filter to the axial component of the wake meandering to prevent the spacing between wake planes from getting too small. --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 2 +- modules-local/awae/src/AWAE.f90 | 5 -- .../wakedynamics/src/WakeDynamics.f90 | 58 +++++++++++++------ .../src/WakeDynamics_Registry.txt | 1 + 4 files changed, 41 insertions(+), 25 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index b7b95bf19c..0d76ca1ef6 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -6,7 +6,7 @@ module FAST_Farm_IO IMPLICIT NONE ! The maximum number of output channels which can be output by the code. INTEGER(IntKi), PARAMETER :: MaxOutPts = 9423 -TYPE(ProgDesc), PARAMETER :: Farm_Ver = ProgDesc( 'FAST.Farm', 'v0.01.00', '3-Apr-2017' ) !< module date/version information +TYPE(ProgDesc), PARAMETER :: Farm_Ver = ProgDesc( 'FAST.Farm', 'v0.01.00', '10-May-2017' ) !< module date/version information !INTEGER(IntKi), PARAMETER :: ChanLenFF = 14 ! =================================================================================================== ! NOTE: The following lines of code were generated by a Matlab script called "Write_ChckOutLst.m" diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index b479062469..b514d1747c 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -939,9 +939,6 @@ subroutine AWAE_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errM integer(intKi) :: errStat2 ! temporary Error status character(ErrMsgLen) :: errMsg2 ! temporary Error message character(*), parameter :: RoutineName = 'AWAE_UpdateStates' - real(ReKi) :: lstar, dx, Vx_wake_min, r_wake, V_planeDT(3), a_interp, norm2_xhat_plane, EddyTermA, EddyTermB - real(ReKi) :: dy_HWkDfl(3) - integer(intKi) :: i,j, ILo errStat = ErrID_None errMsg = "" @@ -979,8 +976,6 @@ subroutine AWAE_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg integer(intKi) :: errStat2 character(ErrMsgLen) :: errMsg2 character(*), parameter :: RoutineName = 'AWAE_CalcOutput' - real(ReKi) :: correction(3) - real(ReKi) :: x_plane integer(intKi) :: n, n_high CHARACTER(1024) :: FileName INTEGER(IntKi) :: Un ! unit number of opened file diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index e2cc8fc625..b38c31cf2f 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -79,7 +79,11 @@ function GetYawCorrection(yawErr, xhat_disk, dx, p, errStat, errMsg) return end if - GetYawCorrection = ( ( p%C_HWkDfl_x + p%C_HWkDfl_xY*yawErr ) * dx + p%C_HWkDfl_O + p%C_HWkDfl_OY*YawErr ) * ( ( xydisk - yxdisk ) / (xydisknorm) ) + if (EqualRealNos(dx,0.0_ReKi)) then + GetYawCorrection = ( p%C_HWkDfl_O + p%C_HWkDfl_OY*YawErr ) * ( ( xydisk - yxdisk ) / (xydisknorm) ) + else + GetYawCorrection = ( p%C_HWkDfl_x + p%C_HWkDfl_xY*yawErr ) * dx * ( ( xydisk - yxdisk ) / (xydisknorm) ) + end if end function GetYawCorrection @@ -394,6 +398,8 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for xd%xhat_plane.', errStat, errMsg, RoutineName ) allocate ( xd%p_plane (3, 0:p%NumPlanes-1) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for xd%p_plane.', errStat, errMsg, RoutineName ) + allocate ( xd%V_plane_filt (3, 0:p%NumPlanes-1) , STAT=ErrStat2 ) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for xd%V_plane_filt.', errStat, errMsg, RoutineName ) allocate ( xd%Vx_wind_disk_filt(0:p%NumPlanes-1) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for xd%Vx_wind_disk_filt.', errStat, errMsg, RoutineName ) allocate ( xd%x_plane (0:p%NumPlanes-1) , STAT=ErrStat2 ) @@ -417,6 +423,7 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut xd%x_plane = 0.0_ReKi xd%Vx_wake = 0.0_ReKi xd%Vr_wake = 0.0_ReKi + xd%V_plane_filt = 0.0_ReKi xd%Vx_wind_disk_filt = 0.0_ReKi xd%TI_amb_filt = 0.0_ReKi xd%D_rotor_filt = 0.0_ReKi @@ -568,13 +575,12 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg integer(intKi) :: errStat2 ! temporary Error status character(ErrMsgLen) :: errMsg2 ! temporary Error message character(*), parameter :: RoutineName = 'WD_UpdateStates' - real(ReKi) :: lstar, dx, Vx_wake_min, r_wake, V_planeDT(3), a_interp, norm2_xhat_plane, EddyTermA, EddyTermB + real(ReKi) :: lstar, dx, Vx_wake_min, r_wake, a_interp, norm2_xhat_plane, EddyTermA, EddyTermB real(ReKi) :: dy_HWkDfl(3) - integer(intKi) :: i,j, ILo + integer(intKi) :: i,j, ILo, maxPln errStat = ErrID_None errMsg = "" - if ( EqualRealNos(u%D_Rotor,0.0_ReKi) .or. u%D_Rotor < 0.0_ReKi ) then @@ -595,9 +601,22 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg end if + + ! Update V_plane_filt to [n+1]: + + maxPln = min(n,p%NumPlanes-2) + do i = 0,maxPln + xd%V_plane_filt(:,i ) = xd%V_plane_filt(:,i)*p%filtParam + u%V_plane(:,i )*(1.0_ReKi-p%filtParam) + end do + xd%V_plane_filt (:,maxPln+1) = u%V_plane(:,maxPln+1) + + + maxPln = min(n+2,p%NumPlanes-1) + + ! We are going to update Vx_Wake ! The quantities in these loops are all at time [n], so we need to compute prior to updating the states to [n+1] - do i = min(n+2,p%NumPlanes-1), 1, -1 + do i = maxPln, 1, -1 lstar = WakeDiam( p%Mod_WakeDiam, p%numRadii, p%dr, p%r, xd%Vx_wake(:,i-1), xd%Vx_wind_disk_filt(i-1), xd%D_rotor_filt(i-1), p%C_WakeDiam) / 2.0_ReKi @@ -606,15 +625,11 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! dx = xd%x_plane(i) - xd%x_plane(i-1) ! This is equivalent to - V_planeDT(1) = u%V_plane (1,i-1)*p%DT - V_planeDT(2) = u%V_plane (2,i-1)*p%DT - V_planeDT(3) = u%V_plane (3,i-1)*p%DT - - dx = dot_product(xd%xhat_plane(:,i-1),V_planeDT) + dx = dot_product(xd%xhat_plane(:,i-1),xd%V_plane_filt(:,i-1))*p%DT if ( EqualRealNos(dx, 0.0_ReKi) .or. dx < 0.0_ReKi) then ! TEST: E2 - call SetErrStat(ErrID_FATAL, 'Downwind advection speed of a wake plane is not positive, i.e., dot_product(xd%xhat_plane(:,i-1),V_planeDT)<= 0', errStat, errMsg, RoutineName) + call SetErrStat(ErrID_FATAL, 'Downwind advection speed of a wake plane is not positive, i.e., dot_product(xd%xhat_plane(:,i-1),xd%V_plane_filt(:,i-1))*DT<= 0', errStat, errMsg, RoutineName) call Cleanup() return end if @@ -674,7 +689,7 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! Update these states to [n+1] - xd%x_plane (i) = xd%x_plane (i-1) + dx ! dx = dot_product(xd%xhat_plane(:,i-1),V_planeDT), where V_planeDT is V_plane(:,i-1)*p*DT + xd%x_plane (i) = xd%x_plane (i-1) + dx ! dx = dot_product(xd%xhat_plane(:,i-1),xd%V_plane_filt(:,i-1))*p%DT xd%YawErr_filt (i) = xd%YawErr_filt(i-1) xd%xhat_plane(:,i) = xd%xhat_plane(:,i-1) @@ -687,7 +702,8 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg call Cleanup() return end if - xd%p_plane (:,i) = xd%p_plane(:,i-1) + V_planeDT + dy_HWkDfl + xd%p_plane (:,i) = xd%p_plane(:,i-1) + xd%xhat_plane(:,i-1)*dx + dy_HWkDfl & + + ( u%V_plane(:,i-1) - xd%xhat_plane(:,i-1)*dot_product(xd%xhat_plane(:,i-1),u%V_plane(:,i-1)) )*p%DT xd%Vx_wind_disk_filt(i) = xd%Vx_wind_disk_filt(i-1) xd%TI_amb_filt (i) = xd%TI_amb_filt(i-1) @@ -744,7 +760,7 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! NOTE: xd%x_plane(0) was already initialized to zero - xd%p_plane (:,0) = xd%p_plane(:,0)*p%filtParam + u%p_hub(:)*(1.0_ReKi-p%filtParam) + dy_HWkDfl + xd%p_plane (:,0) = xd%p_plane(:,0)*p%filtParam + ( u%p_hub(:) + dy_HWkDfl(:) )*(1.0_ReKi-p%filtParam) xd%Vx_wind_disk_filt(0) = xd%Vx_wind_disk_filt(0)*p%filtParam + u%Vx_wind_disk*(1.0_ReKi-p%filtParam) xd%TI_amb_filt (0) = xd%TI_amb_filt(0)*p%filtParam + u%TI_amb*(1.0_ReKi-p%filtParam) xd%D_rotor_filt (0) = xd%D_rotor_filt(0)*p%filtParam + u%D_rotor*(1.0_ReKi-p%filtParam) @@ -752,7 +768,7 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! TODO: This is a new 3D wake plane crossing check and I'm not sure this is the most efficient implemenation. - do i = 1,min(n+2,p%NumPlanes-1) + do i = 1,maxPln if ( xd%x_plane(i) - xd%x_plane(i-1) <= 0.0_ReKi ) then call SetErrStat(ErrID_FATAL, 'In a 1D sense, wake plane '//trim(num2lstr(i-1))//' is further downstream than wake plane '//trim(num2lstr(i)), errStat, errMsg, RoutineName) call Cleanup() @@ -816,8 +832,9 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg xd%Vx_wake(j,0) = -xd%Vx_rel_disk_filt*p%C_NearWake*a_interp xd%Vr_wake(j,0) = 0.0_ReKi end do + -!Used for debugging: write(51,'(I5,100(1x,ES10.2E2))') n, xd%x_plane(n), xd%x_plane(n)/xd%D_rotor_filt(n), xd%Vx_wind_disk_filt(n) + xd%Vx_wake(:,n), xd%Vr_wake(:,n) + !Used for debugging: write(51,'(I5,100(1x,ES10.2E2))') n, xd%x_plane(n), xd%x_plane(n)/xd%D_rotor_filt(n), xd%Vx_wind_disk_filt(n) + xd%Vx_wake(:,n), xd%Vr_wake(:,n) call Cleanup() @@ -871,10 +888,11 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) if ( OtherState%firstPass ) then ! TODO: This entire block needs to be reviewed + correction = 0.0_ReKi do i = 0, min(n+1,p%NumPlanes-1) x_plane = u%Vx_rel_disk*real(i,ReKi)*real(p%DT,ReKi) - correction = GetYawCorrection(u%YawErr, u%xhat_disk, x_plane, p, errStat2, errMsg2) + correction = correction + GetYawCorrection(u%YawErr, u%xhat_disk, x_plane, p, errStat2, errMsg2) call SetErrStat(errStat2, errMsg2, errStat, errMsg, RoutineName) if (errStat >= AbortErrLev) then ! TEST: E3 @@ -1063,11 +1081,12 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs ErrMsg = "" + correction = 0.0_ReKi do i = 0, 1 xd%x_plane (i) = u%Vx_rel_disk*real(i,ReKi)*real(p%DT,ReKi) xd%YawErr_filt (i) = u%YawErr - correction = GetYawCorrection(u%YawErr, u%xhat_disk, xd%x_plane(i), p, errStat2, errMsg2) + correction = correction + GetYawCorrection(u%YawErr, u%xhat_disk, xd%x_plane(i), p, errStat2, errMsg2) call SetErrStat(errStat2, errMsg2, errStat, errMsg, RoutineName) if (errStat >= AbortErrLev) then ! TEST: E3 @@ -1077,7 +1096,8 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs !correction = ( p%C_HWkDfl_x + p%C_HWkDfl_xY*u%YawErr )*xd%x_plane(i) + correctionA xd%p_plane (:,i) = u%p_hub(:) + xd%x_plane(i)*u%xhat_disk(:) + correction - xd%xhat_plane(:,i) = u%xhat_disk(:) + xd%xhat_plane(:,i) = u%xhat_disk(:) + xd%V_plane_filt(:,i) = u%V_plane(:,i) xd%Vx_wind_disk_filt(i) = u%Vx_wind_disk xd%TI_amb_filt (i) = u%TI_amb xd%D_rotor_filt (i) = u%D_rotor diff --git a/modules-local/wakedynamics/src/WakeDynamics_Registry.txt b/modules-local/wakedynamics/src/WakeDynamics_Registry.txt index a8734564d5..d11b1f44e6 100644 --- a/modules-local/wakedynamics/src/WakeDynamics_Registry.txt +++ b/modules-local/wakedynamics/src/WakeDynamics_Registry.txt @@ -67,6 +67,7 @@ typedef ^ DiscreteStateType ReKi p_plane {:}{:} - - "Center posi typedef ^ DiscreteStateType ReKi x_plane {:} - - "Downwind distance from rotor to each wake plane" m typedef ^ DiscreteStateType ReKi Vx_wake {:}{:} - - "Axial wake velocity deficit at wake planes, distributed radially" m/s typedef ^ DiscreteStateType ReKi Vr_wake {:}{:} - - "Radial wake velocity deficit at wake planes, distributed radially" m/s +typedef ^ DiscreteStateType ReKi V_plane_filt {:}{:} - - "Time-filtered advection, deflection, and meandering velocity of wake planes" m/s typedef ^ DiscreteStateType ReKi Vx_wind_disk_filt {:} - - "Time-filtered rotor-disk-averaged ambient wind speed of wake planes, normal to planes" m/s typedef ^ DiscreteStateType ReKi TI_amb_filt {:} - - "Time-filtered ambient turbulence intensity of wind at wake planes" - typedef ^ DiscreteStateType ReKi D_rotor_filt {:} - - "Time-filtered rotor diameter associated with each wake plane" m From aa72cab98f32daf0d7f7bfd8091fa9b1b70a8c2d Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Wed, 10 May 2017 20:24:51 -0600 Subject: [PATCH 004/386] Eliminated Debug Write-Output in FAST.Farm No longer output p_plane, x_plane, V_plane, and N_Wind automatically. --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 126 +++++++++++----------- 1 file changed, 63 insertions(+), 63 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index 0d76ca1ef6..a9e029dd3a 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9871,26 +9871,26 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) ENDDO ! I !============================================================ ! DEBUG OUTPUTS HERE - - DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEX'//trim(num2lstr(I)) - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEY'//trim(num2lstr(I)) - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEZ'//trim(num2lstr(I)) - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'XPLANE'//trim(num2lstr(I)) - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEX'//trim(num2lstr(I)) - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEY'//trim(num2lstr(I)) - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEZ'//trim(num2lstr(I)) - - IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'N_WIND'//trim(num2lstr(I)) - END IF - - ENDDO ! I - All selected output channels - - +! +! DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEX'//trim(num2lstr(I)) +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEY'//trim(num2lstr(I)) +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') 'PPLANEZ'//trim(num2lstr(I)) +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'XPLANE'//trim(num2lstr(I)) +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEX'//trim(num2lstr(I)) +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEY'//trim(num2lstr(I)) +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'VPLANEZ'//trim(num2lstr(I)) +! +! IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) 'N_WIND'//trim(num2lstr(I)) +! END IF +! +! ENDDO ! I - All selected output channels +! +! ! END DEBUG OUTPUTS !============================================================ WRITE (farm%p%UnOu,'()') @@ -9908,26 +9908,26 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) !============================================================ ! DEBUG OUTPUTS HERE - - DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m) ' - - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' - - IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (-) ' - END IF - - ENDDO ! I - All selected output channels - - +! +! DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO') ' (m) ' +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m) ' +! +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (m/s) ' +! +! IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) ' (-) ' +! END IF +! +! ENDDO ! I - All selected output channels +! +! ! END DEBUG OUTPUTS !============================================================ @@ -10076,29 +10076,29 @@ SUBROUTINE WriteFarmOutputToFile( t_global, farm, ErrStat, ErrMsg ) !============================================================ ! DEBUG OUTPUTS HERE - - DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels - - DO J = 1,3 - WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%WD(1)%y%p_plane(J,I) - CALL WrFileNR( farm%p%UnOu, TmpStr2 ) - ENDDO - - WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%WD(1)%xd%x_plane(I) - CALL WrFileNR( farm%p%UnOu, TmpStr2 ) - - DO J = 1,3 - WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%AWAE%y%V_plane(J,I,1) - CALL WrFileNR( farm%p%UnOu, TmpStr2 ) - ENDDO - - IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN - WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) trim(num2lstr(farm%AWAE%m%N_Wind(I,1))) - END IF - - ENDDO ! I - All selected output channels - - +! +! DO I = 0,farm%WD(1)%p%NumPlanes-1 ! Loop through all selected output channels +! +! DO J = 1,3 +! WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%WD(1)%y%p_plane(J,I) +! CALL WrFileNR( farm%p%UnOu, TmpStr2 ) +! ENDDO +! +! WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%WD(1)%xd%x_plane(I) +! CALL WrFileNR( farm%p%UnOu, TmpStr2 ) +! +! DO J = 1,3 +! WRITE( TmpStr2, '('//trim(farm%p%OutFmt)//')' ) farm%AWAE%y%V_plane(J,I,1) +! CALL WrFileNR( farm%p%UnOu, TmpStr2 ) +! ENDDO +! +! IF ( I < farm%WD(1)%p%NumPlanes-1 ) THEN +! WRITE( farm%p%UnOu,'(A14)',ADVANCE='NO' ) trim(num2lstr(farm%AWAE%m%N_Wind(I,1))) +! END IF +! +! ENDDO ! I - All selected output channels +! +! ! END DEBUG OUTPUTS !============================================================ ! write a new line (advance to the next line) From 4e6ddc0b038ecc78d63857056e82885bcc75ce6b Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Fri, 12 May 2017 07:06:23 -0600 Subject: [PATCH 005/386] Fixed Minor Bug in AWAE Causing FAST.Farm to Crash at Simulation End To complete this fix, the additional calculation of the eddy viscosity at the end of WD_UpdateStates from Rev. 11 of the FAST.Farm must be implemented. This is still to be done. --- modules-local/awae/src/AWAE.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index b514d1747c..de1c287ded 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -410,7 +410,7 @@ subroutine HighResGridCalcOutput(n, u, p, y, m, errStat, errMsg) maxPln = min(n,p%NumPlanes-2) ! We only need one high res file for that last simulation time - if ( n == (p%NumDT-1) ) then + if ( (n/p%n_high_low) == (p%NumDT-1) ) then n_high_low = 1 else n_high_low = p%n_high_low From 1411f63ff218b16208aaf676b937454b62e65396 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Wed, 17 May 2017 16:21:41 -0600 Subject: [PATCH 006/386] Added a yaw-step controller for FAST.Farm calibration --- modules-local/servodyn/src/UserSubs.f90 | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/modules-local/servodyn/src/UserSubs.f90 b/modules-local/servodyn/src/UserSubs.f90 index bd276dcdb3..48774234c3 100644 --- a/modules-local/servodyn/src/UserSubs.f90 +++ b/modules-local/servodyn/src/UserSubs.f90 @@ -426,6 +426,7 @@ SUBROUTINE UserYawCont ( YawPos, YawRate, WindDir, YawError, NumBl, ZTime, DT, D USE Precision +USE NWTC_Library IMPLICIT NONE @@ -451,6 +452,21 @@ SUBROUTINE UserYawCont ( YawPos, YawRate, WindDir, YawError, NumBl, ZTime, DT, D YawPosCom = 0.0 YawRateCom = 0.0 +!JASON: IMPOSE YAW STEP FOR FAST.Farm CALIBRATION CASE - START +IF ( ( ZTime >= 298.0_DbKi ) .AND. ( ZTime < 300.0_DbKi ) ) THEN + YawRateCom = ( 10.0_ReKi/2.0_ReKi )*D2R + YawPosCom = 0.0 + YawRateCom*( ZTime - 298.0_DbKi ) +ELSE IF ( ( ZTime >= 300.0_DbKi ) .AND. ( ZTime < 598.0_DbKi ) ) THEN + YawRateCom = 0.0 + YawPosCom = 10.0_ReKi*D2R +ELSE IF ( ( ZTime >= 598.0_DbKi ) .AND. ( ZTime < 600.0_DbKi ) ) THEN + YawRateCom = ( 15.0_ReKi/2.0_ReKi )*D2R + YawPosCom = 10.0_ReKi*D2R + YawRateCom*( ZTime - 598.0_DbKi ) +ELSE IF ( ( ZTime >= 600.0_DbKi ) ) THEN + YawRateCom = 0.0 + YawPosCom = 25.0_ReKi*D2R +END IF +!JASON: IMPOSE YAW STEP FOR FAST.Farm CALIBRATION CASE - END RETURN From 6f1f125ad5c9eb2a3027996c348b05fbdb8bc2f4 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 18 May 2017 16:39:52 -0600 Subject: [PATCH 007/386] Outline for Binary Fast.Farm file writing Did not finish the implementation because we are using channel names and units which are ChanLenFF long which is not ChanLen long, so this would be a new binary file format. --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 182 ++++++++---------- .../fast-farm/src/FAST_Farm_Registry.txt | 6 + 2 files changed, 91 insertions(+), 97 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index a9e029dd3a..f8eb17b930 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9794,6 +9794,36 @@ module FAST_Farm_IO contains +!---------------------------------------------------------------------------------------------------------------------------------- +!> This function returns a string describing the glue code and some of the compilation options we're using. +FUNCTION GetVersion(ThisProgVer) + + ! Passed Variables: + + TYPE(ProgDesc), INTENT( IN ) :: ThisProgVer !< program name/date/version description + CHARACTER(1024) :: GetVersion !< String containing a description of the compiled precision. + + GetVersion = TRIM(GetNVD(ThisProgVer))//', compiled' + + + GetVersion = TRIM(GetVersion)//' as a '//TRIM(Num2LStr(BITS_IN_ADDR))//'-bit application using' + + ! determine precision + + IF ( ReKi == SiKi ) THEN ! Single precision + GetVersion = TRIM(GetVersion)//' single' + ELSEIF ( ReKi == R8Ki ) THEN ! Double precision + GetVersion = TRIM(GetVersion)// ' double' + ELSE ! Unknown precision + GetVersion = TRIM(GetVersion)//' unknown' + ENDIF + +! GetVersion = TRIM(GetVersion)//' precision with '//OS_Desc + GetVersion = TRIM(GetVersion)//' precision' + + + RETURN +END FUNCTION GetVersion !---------------------------------------------------------------------------------------------------------------------------------- !> This routine initializes the output for the glue code, including writing the header for the primary output file. @@ -9813,7 +9843,7 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) INTEGER(IntKi) :: indxLast ! The index of the last value to be written to an array INTEGER(IntKi) :: indxNext ! The index of the next value to be written to an array INTEGER(IntKi) :: NumOuts ! number of channels to be written to the output file(s) - CHARACTER(1024) :: FileDescLines(3) + @@ -9833,10 +9863,10 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) farm%m%AllOuts = 0.0_ReKi - - FileDescLines(1) = 'Predictions were generated on '//CurDate()//' at '//CurTime()//' using '//TRIM(GetNVD(Farm_Ver)) - FileDescLines(2) = 'linked with ' //' '//TRIM(GetNVD(NWTC_Ver )) ! we'll get the rest of the linked modules in the section below - FileDescLines(3) = 'Description from the FAST.Farm input file: '//TRIM(farm%p%FTitle) + + farm%p%FileDescLines(1) = 'Predictions were generated on '//CurDate()//' at '//CurTime()//' using '//TRIM(GetVersion(Farm_Ver)) + farm%p%FileDescLines(2) = 'linked with ' //' '//TRIM(GetNVD(NWTC_Ver )) ! we'll get the rest of the linked modules in the section below + farm%p%FileDescLines(3) = 'Description from the FAST.Farm input file: '//TRIM(farm%p%FTitle) !...................................................... ! Open the text output file and print the headers @@ -9852,10 +9882,10 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) ! Add some file information: - WRITE (farm%p%UnOu,'(/,A)') TRIM( FileDescLines(1) ) - WRITE (farm%p%UnOu,'(1X,A)') TRIM( FileDescLines(2) ) + WRITE (farm%p%UnOu,'(/,A)') TRIM( farm%p%FileDescLines(1) ) + WRITE (farm%p%UnOu,'(1X,A)') TRIM( farm%p%FileDescLines(2) ) WRITE (farm%p%UnOu,'()' ) !print a blank line - WRITE (farm%p%UnOu,'(A)' ) TRIM( FileDescLines(3) ) + WRITE (farm%p%UnOu,'(A)' ) TRIM( farm%p%FileDescLines(3) ) WRITE (farm%p%UnOu,'()' ) !print a blank line @@ -9942,27 +9972,27 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) !IF (farm%p%WrBinOutFile) THEN ! ! ! calculate the size of the array of outputs we need to store - ! farm%p%NOutSteps = CEILING ( (farm%p%TMax - farm%p%TStart) / farm%p%DT_OUT ) + 1 + ! farm%p%NOutSteps = CEILING ( (farm%p%TMax - farm%p%TStart) / farm%p%DT ) + 1 ! - ! CALL AllocAry( farm%p%AllOutData, farm%p%NumOuts-1, farm%p%NOutSteps, 'AllOutData', ErrStat, ErrMsg ) + ! CALL AllocAry( farm%m%AllOutData, farm%p%NumOuts-1, farm%p%NOutSteps, 'AllOutData', ErrStat, ErrMsg ) ! IF ( ErrStat >= AbortErrLev ) RETURN ! - ! IF ( OutputFileFmtID == FileFmtID_WithoutTime ) THEN + ! ! IF ( OutputFileFmtID == FileFmtID_WithoutTime ) THEN ! - ! CALL AllocAry( farm%p%TimeData, 2_IntKi, 'TimeData', ErrStat, ErrMsg ) + ! CALL AllocAry( farm%m%TimeData, 2_IntKi, 'TimeData', ErrStat, ErrMsg ) ! IF ( ErrStat >= AbortErrLev ) RETURN ! - ! y_FAST%TimeData(1) = 0.0_DbKi ! This is the first output time, which we will set later - ! y_FAST%TimeData(2) = farm%p%DT_out ! This is the (constant) time between subsequent writes to the output file - ! - ! ELSE ! we store the entire time array - ! - ! CALL AllocAry( y_FAST%TimeData, y_FAST%NOutSteps, 'TimeData', ErrStat, ErrMsg ) - ! IF ( ErrStat >= AbortErrLev ) RETURN + ! farm%m%TimeData(1) = 0.0_DbKi ! This is the first output time, which we will set later + ! farm%m%TimeData(2) = farm%p%DT ! This is the (constant) time between subsequent writes to the output file ! - ! END IF + ! !ELSE ! we store the entire time array + ! ! + ! ! CALL AllocAry( farm%m%TimeData, farm%p%NOutSteps, 'TimeData', ErrStat, ErrMsg ) + ! ! IF ( ErrStat >= AbortErrLev ) RETURN + ! ! + ! !END IF ! - ! y_FAST%n_Out = 0 !number of steps actually written to the file + ! farm%m%n_Out = 0 !number of steps actually written to the file ! !END IF @@ -9986,7 +10016,9 @@ SUBROUTINE Farm_EndOutput( farm, ErrStat, ErrMsg ) ! local variables CHARACTER(1024) :: FileDesc ! The description of the run, to be written in the binary output file - + !CHARACTER(ChanLenFF):: ChannelNames(farm%p%NumOuts) + !CHARACTER(ChanLenFF):: ChannelUnits(farm%p%NumOuts) + !INTEGER(IntKi) :: I ! Initialize some values ErrStat = ErrID_None @@ -9995,13 +10027,18 @@ SUBROUTINE Farm_EndOutput( farm, ErrStat, ErrMsg ) !------------------------------------------------------------------------------------------------- ! Write the binary output file if requested !------------------------------------------------------------------------------------------------- - - !IF (farm%p%WrBinOutFile .AND. farm%y%n_Out > 0) THEN + ! TODO: The ChannelNames and ChannelUnits need to be length ChanLenFF for Fast.Farm, but the WrBinFAST subroutine needs these to be ChanLen long! + !IF (farm%p%WrBinOutFile .AND. farm%m%n_Out > 0) THEN ! ! FileDesc = TRIM(farm%p%FileDescLines(1))//' '//TRIM(farm%p%FileDescLines(2))//'; '//TRIM(farm%p%FileDescLines(3)) ! - ! CALL WrBinFAST(TRIM(farm%p%OutFileRoot)//'.outb', OutputFileFmtID, TRIM(FileDesc), & - ! ChannelNames, ChannelUnits, farm%y%TimeData, farm%y%AllOutData(:,1:farm%y%n_Out), ErrStat, ErrMsg) + ! DO I = 1,farm%p%NumOuts + ! ChannelNames(I) = farm%p%OutParam(I)%Name + ! ChannelUnits(I) = farm%p%OutParam(I)%Units + ! END DO + ! + ! CALL WrBinFAST(TRIM(farm%p%OutFileRoot)//'.outb', 2, TRIM(FileDesc), & + ! ChannelNames, ChannelUnits, farm%m%TimeData(:),farm%m%AllOutData(:,1:farm%m%n_Out), ErrStat, ErrMsg) ! ! IF ( ErrStat /= ErrID_None ) CALL WrScr( TRIM(GetErrStr(ErrStat))//' when writing binary output file: '//TRIM(ErrMsg) ) ! @@ -10050,7 +10087,7 @@ SUBROUTINE WriteFarmOutputToFile( t_global, farm, ErrStat, ErrMsg ) CHARACTER(farm%p%TChanLen) :: TmpStr ! temporary string to print the time output as text CHARACTER(ChanLenFF) :: TmpStr2 ! temporary string to print the output as text INTEGER(IntKi) :: I, J ! loop counter - REAL(ReKi) :: val + REAL(ReKi) :: OutputAry(farm%p%NumOuts) ErrStat = ErrID_None ErrMsg = "" @@ -10067,8 +10104,8 @@ SUBROUTINE WriteFarmOutputToFile( t_global, farm, ErrStat, ErrMsg ) ! Generate fast.farm output file DO I = 1,farm%p%NumOuts ! Loop through all selected output channels - val = farm%p%OutParam(I)%SignM * farm%m%AllOuts( farm%p%OutParam(I)%Indx ) - WRITE( TmpStr2, '('//Frmt//')' ) val + OutputAry(I) = farm%p%OutParam(I)%SignM * farm%m%AllOuts( farm%p%OutParam(I)%Indx ) + WRITE( TmpStr2, '('//Frmt//')' ) OutputAry(I) CALL WrFileNR( farm%p%UnOu, TmpStr2 ) @@ -10104,81 +10141,32 @@ SUBROUTINE WriteFarmOutputToFile( t_global, farm, ErrStat, ErrMsg ) ! write a new line (advance to the next line) WRITE (farm%p%UnOu,'()') - ENDIF - - -END SUBROUTINE WriteFarmOutputToFile - -!---------------------------------------------------------------------------------------------------------------------------------- -!> This routine writes the module output to the primary output file(s). -SUBROUTINE WrOutputLine( t, farm, ErrStat, ErrMsg) - - IMPLICIT NONE - - ! Passed variables - REAL(DbKi), INTENT(IN) :: t !< Current simulation time, in seconds - type(All_FastFarm_Data), INTENT(INOUT) :: farm !< FAST.Farm data - INTEGER(IntKi), INTENT(OUT) :: ErrStat !< Error status - CHARACTER(*), INTENT(OUT) :: ErrMsg !< Error message - - ! Local variables. - - CHARACTER(200) :: Frmt ! A string to hold a format specifier - CHARACTER(farm%p%TChanLen) :: TmpStr ! temporary string to print the time output as text - - ! REAL(ReKi) :: OutputAry(SIZE(farm%p%ChannelNames)-1) - - ErrStat = ErrID_None - ErrMsg = '' - - !CALL FillOutputAry(p_Farm, y_Farm, IfWOutput, OpFMOutput, EDOutput, ADOutput, SrvDOutput, HDOutput, SDOutput, ExtPtfmOutput, & - ! MAPOutput, FEAMOutput, MDOutput, OrcaOutput, IceFOutput, y_IceD, y_BD, OutputAry) - - !IF (farm%p%WrTxtOutFile) THEN - - ! Write one line of tabular output: - ! Frmt = '(F8.3,'//TRIM(Num2LStr(p%NumOuts))//'(:,A,'//TRIM( p%OutFmt )//'))' - Frmt = '"'//farm%p%Delim//'"'//farm%p%OutFmt ! format for array elements from individual modules - - ! time - WRITE( TmpStr, '('//trim(farm%p%OutFmt_t)//')' ) t - !CALL WrFileNR( y_Farm%UnOu, TmpStr ) + !IF (farm%p%WrBinOutFile) THEN ! - ! ! write the individual module output (convert to SiKi if necessary, so that we don't need to print so many digits in the exponent) - !CALL WrNumAryFileNR ( y_Farm%UnOu, REAL(OutputAry,SiKi), Frmt, ErrStat, ErrMsg ) - ! !IF ( ErrStat >= AbortErrLev ) RETURN + ! ! Write data to array for binary output file ! - ! ! write a new line (advance to the next line) - !WRITE (y_Farm%UnOu,'()') - - !END IF - - - !IF (farm%p%WrBinOutFile) THEN - - ! Write data to array for binary output file - - !IF ( y_Farm%n_Out == y_Farm%NOutSteps ) THEN - ! CALL ProgWarn( 'Not all data could be written to the binary output file.' ) - ! !this really would only happen if we have an error somewhere else, right? - ! !otherwise, we could allocate a new, larger array and move existing data - !ELSE - ! y_Farm%n_Out = y_Farm%n_Out + 1 + ! IF ( farm%m%n_Out == farm%p%NOutSteps ) THEN + ! CALL ProgWarn( 'Not all data could be written to the binary output file.' ) + ! !this really would only happen if we have an error somewhere else, right? + ! !otherwise, we could allocate a new, larger array and move existing data + ! ELSE + ! farm%m%n_Out = farm%m%n_Out + 1 ! - ! ! store time data - ! IF ( y_Farm%n_Out == 1_IntKi .OR. OutputFileFmtID == FileFmtID_WithTime ) THEN - ! y_Farm%TimeData(y_Farm%n_Out) = t ! Time associated with these outputs - ! END IF + ! ! store time data + ! IF ( farm%m%n_Out == 1_IntKi ) THEN !.OR. OutputFileFmtID == FileFmtID_WithTime ) THEN + ! farm%m%TimeData(farm%m%n_Out) = t_global ! Time associated with these outputs + ! END IF ! - ! ! store individual module data - ! y_Farm%AllOutData(:, y_Farm%n_Out) = OutputAry + ! ! store individual module data + ! farm%m%AllOutData(:, farm%m%n_Out) = OutputAry ! - !END IF + ! END IF + ! + !END IF + ENDIF +END SUBROUTINE WriteFarmOutputToFile - !END IF - RETURN -END SUBROUTINE WrOutputLine logical function PointInAABB(x, y, z, x0, y0, z0, x1, y1, z1) real(ReKi), intent(in) :: x,y,z,x0,y0,z0,x1,y1,z1 diff --git a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt index 7452ff27e9..1151abb2aa 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt +++ b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt @@ -48,6 +48,8 @@ typedef ^ ParameterType ReKi WindVelY {: typedef ^ ParameterType ReKi WindVelZ {:} - - "List of coordinates in the Z direction for wind output [1 to NWindVel]" meters typedef ^ ParameterType OutParmFFType OutParam {:} - - "Names and units (and other characteristics) of all requested output parameters" - typedef ^ ParameterType IntKi NumOuts - - - "Number of user-requested outputs" - +typedef ^ ^ IntKi NOutSteps - - - "Maximum number of output steps" - +typedef ^ ^ CHARACTER(1024) FileDescLines {3} -- "File Description lines" - typedef ^ ParameterType IntKi UnOu - - - "File unit for Fast.Farm output data" - typedef ^ ParameterType ReKi dX_low - - - "The spacing of the low-resolution nodes in X direction" m typedef ^ ParameterType ReKi dY_low - - - "The spacing of the low-resolution nodes in Y direction" m @@ -60,6 +62,10 @@ typedef ^ ParameterType ReKi Y0_low - typedef ^ ParameterType ReKi Z0_low - - - "Z-component of the origin of the low-resolution spatial domain" m # ..... FAST MiscVar data ....................................................................................................... typedef ^ MiscVarType ReKi AllOuts {:} - - "An array holding the value of all of the calculated (not only selected) output channels" "see OutListParameters.xlsx spreadsheet" +typedef ^ ^ DbKi TimeData {:} - - "Array to contain the time output data for the binary file (first output time and a time [fixed] increment)" +typedef ^ ^ ReKi AllOutData {:}{:} - - "Array to contain all the output data (time history of all outputs); Index 1 is NumOuts, Index 2 is Time step" +typedef ^ ^ IntKi n_Out - - - "Time index into the AllOutData array" + # ..... FASTWrapper data ....................................................................................................... typedef ^ FASTWrapper_Data FWrap_ContinuousStateType x - - - "Continuous states" typedef ^ ^ FWrap_DiscreteStateType xd - - - "Discrete states" From 265e4f4043b75180eb69650df102bd417ed115f0 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 18 May 2017 16:42:37 -0600 Subject: [PATCH 008/386] Check that radius formed by center of intersection of adjacent wake planes is > rmax Add error check for m%r_e < rmax or m%r_s < rmax --- modules-local/awae/src/AWAE.f90 | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index de1c287ded..eb26edd443 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -83,6 +83,7 @@ subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) if (s_grid0 == (szs-1)) s_grid1 = s_grid0 ! Handle case where s0 is the last index in the grid, in this case sd = 0.0, so the 2nd term in the interpolation will not contribute ! TODO: Add code to check bounds of requested slice location at INIT and fatal error if out of bounds + ! doing the bounds checks at INIT keeps this algorithm as fast as possible do j = 0,sz2-1 do i = 0,sz1-1 select case (sliceType) @@ -129,6 +130,15 @@ subroutine ComputeLocals(n, u, p, y, m, errStat, errMsg) dp = u%p_plane(:,np+1,nt) - u%p_plane(:,np,nt) m%r_e(np,nt) = dot_product( u%xhat_plane(:,np ,nt), dp ) m%r_s(np,nt) = dot_product( u%xhat_plane(:,np+1,nt), dp ) + if ( m%r_e(np,nt) < rmax ) then + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the ending wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + return + end if + if ( m%r_s(np,nt) < rmax ) then + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the starting wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + return + end if + if ( sinTerm > ( max( m%r_e(np,nt), m%r_s(np,nt) ) / ( 100.0_ReKi*rmax ) ) ) then m%parallelFlag(np,nt) = .false. m%r_e(np,nt) = m%r_e(np,nt) / sinTerm From b81f9e49491bd05a02550ec2c4458ede6579016d Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 18 May 2017 16:47:54 -0600 Subject: [PATCH 009/386] WD error checks and initialization rework Made common code NearWakeCorrection() for Vx_wake calculation added y%x_plane so that we can test x_plane during first timestep when writing outputs Set the last plane's vt_amb, vt_shr, vt_tot to the previous plane's value. This is needed for output channel interpolations. Augmented 3D wake plane crossing check. --- .../wakedynamics/src/WakeDynamics.f90 | 249 +++++++----------- .../src/WakeDynamics_Registry.txt | 1 + 2 files changed, 94 insertions(+), 156 deletions(-) diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index b38c31cf2f..e9d1177790 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -170,6 +170,74 @@ real(ReKi) function WakeDiam( Mod_WakeDiam, nr, dr, rArr, Vx_wake, Vx_wind_disk, end function WakeDiam +!---------------------------------------------------------------------------------------------------------------------------------- +!> This subroutine computes the near wake correction : Vx_wake +subroutine NearWakeCorrection( Ct_azavg_filt, Vx_rel_disk_filt, p, m, Vx_wake, errStat, errMsg ) + real(ReKi), intent(in ) :: Ct_azavg_filt(0:) !< Time-filtered azimuthally averaged thrust force coefficient (normal to disk), distributed radially + real(ReKi), intent(in ) :: Vx_rel_disk_filt !< Time-filtered rotor-disk-averaged relative wind speed (ambient + deficits + motion), normal to disk + type(WD_ParameterType), intent(in ) :: p !< Parameters + type(WD_MiscVarType), intent(inout) :: m !< Initial misc/optimization variables + real(ReKi), intent(inout) :: Vx_wake(0:,0:) !< Axial wake velocity deficit at wake planes, distributed radially + integer(IntKi), intent( out) :: errStat !< Error status of the operation + character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None + real(ReKi) :: a_interp + integer(IntKi) :: j, ILo + character(*), parameter :: RoutineName = 'NearWakeCorrection' + + errStat = ErrID_None + errMsg = '' + + m%r_wake(0) = 0.0_ReKi + + do j=0,p%NumRadii-1 + + ! compute m%a using the [n+1] values of Ct_azavg_filt + if ( Ct_azavg_filt(j) > 2.0_ReKi ) then + ! THROW ERROR because we are in the prop-brake region + ! TEST: E5 + call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., Ct_azavg_filt(j) > 2.0.', errStat, errMsg, RoutineName) + + return + else if ( Ct_azavg_filt(j) >= 24.0_ReKi/25.0_ReKi ) then + m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*Ct_azavg_filt(j)-12.0_ReKi))/14.0_ReKi + else + m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-Ct_azavg_filt(j)) + end if + + if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then + ! TEST: E6 + call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) + + return + end if + + if (j > 0) then + m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) + end if + + end do + + ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake + + ! Use the [n+1] version of Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) + Vx_wake(0,0) = -Vx_rel_disk_filt*p%C_Nearwake*m%a(0) + Vx_wake(0,1) = Vx_wake(0,0) + + ILo = 0 + do j=1, p%NumRadii-1 + + ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation + a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + + ! [n+1] + Vx_wake(j,0) = -Vx_rel_disk_filt*p%C_NearWake*a_interp + Vx_wake(j,1) = Vx_wake(j,0) + end do + +end subroutine NearWakeCorrection + + + !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine solves the tridiagonal linear system for x() using the Thomas algorithm subroutine ThomasAlgorithm(nr, a, b, c, d, x, errStat, errMsg) @@ -469,6 +537,8 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for y%Vr_wake.', errStat, errMsg, RoutineName ) allocate ( y%D_wake (0:p%NumPlanes-1), STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for y%D_wake.', errStat, errMsg, RoutineName ) + allocate ( y%x_plane (0:p%NumPlanes-1), STAT=ErrStat2 ) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for y%x_plane.', errStat, errMsg, RoutineName ) if (errStat /= ErrID_None) return y%xhat_plane = 0.0_Reki @@ -476,6 +546,7 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut y%Vx_wake = 0.0_Reki y%Vr_wake = 0.0_Reki y%D_wake = 0.0_Reki + y%x_plane = 0.0_Reki call Cleanup() @@ -655,6 +726,8 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg m%vt_tot(j,i-1) = m%vt_amb(j,i-1) + m%vt_shr(j,i-1) end do + + ! All of the m%a,m%b,m%c,m%d vectors use states at time increment [n] ! These need to be inside another radial loop because m%dvtdr depends on the j+1 and j-1 indices of m%vt() @@ -725,6 +798,11 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg end do end do ! i = 1,min(n+2,p%NumPlanes-1) + ! Set the last wake plane's eddy viscosity terms equal to the previous wake plane values. This is for output writing purposes only. + m%vt_amb(:,maxPln) = m%vt_amb(:,maxPln-1) + m%vt_shr(:,maxPln) = m%vt_shr(:,maxPln-1) + m%vt_tot(:,maxPln) = m%vt_tot(:,maxPln-1) + ! Update states at disk-plane to [n+1] xd%xhat_plane (:,0) = xd%xhat_plane(:,0)*p%filtParam + u%xhat_disk(:)*(1.0_ReKi-p%filtParam) ! 2-step calculation for xhat_plane at disk @@ -775,7 +853,8 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg return end if - if ( dot_product( xd%xhat_plane(:,i-1), ( xd%p_plane(:,i) -xd%p_plane(:,i-1) ) ) <= 0.0_ReKi ) then + if ( ( dot_product( xd%xhat_plane(:,i-1), ( xd%p_plane(:,i) - xd%p_plane(:,i-1) ) ) <= 0.0_ReKi ) .or. & + ( dot_product( xd%xhat_plane(:,i ), ( xd%p_plane(:,i) - xd%p_plane(:,i-1) ) ) <= 0.0_ReKi ) )then call SetErrStat(ErrID_FATAL, 'In a 3D sense, wake plane '//trim(num2lstr(i-1))//' is further downstream than wake plane '//trim(num2lstr(i)), errStat, errMsg, RoutineName) call Cleanup() return @@ -784,55 +863,9 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ! filtered, azimuthally-averaged Ct values at each radial station + xd%Ct_azavg_filt (:) = xd%Ct_azavg_filt(:)*p%filtParam + u%Ct_azavg(:)*(1.0_ReKi-p%filtParam) - m%r_wake(0) = 0.0_ReKi - - do j=0,p%NumRadii-1 - - xd%Ct_azavg_filt (j) = xd%Ct_azavg_filt(j)*p%filtParam + u%Ct_azavg(j)*(1.0_ReKi-p%filtParam) - - ! compute m%a using the [n+1] values of Ct_azavg_filt - if ( xd%Ct_azavg_filt(j) > 2.0_ReKi ) then - ! THROW ERROR because we are in the prop-brake region - ! TEST: E5 - call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., xd%Ct_azavg_filt(j) > 2.0.', errStat, errMsg, RoutineName) - call Cleanup() - return - else if ( xd%Ct_azavg_filt(j) >= 24.0_ReKi/25.0_ReKi ) then - m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*xd%Ct_azavg_filt(j)-12.0_ReKi))/14.0_ReKi - else - m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-xd%Ct_azavg_filt(j)) - end if - - if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then - ! TEST: E6 - call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) - call Cleanup() - return - end if - - if (j > 0) then - m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) - end if - - end do - - ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake - - ! Use the [n+1] version of xd%Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) - xd%Vx_wake(0,0) = - xd%Vx_rel_disk_filt*p%C_Nearwake*m%a(0) - - ILo = 0 - do j=1, p%NumRadii-1 - - ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation - a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) - - ! [n+1] - xd%Vx_wake(j,0) = -xd%Vx_rel_disk_filt*p%C_NearWake*a_interp - xd%Vr_wake(j,0) = 0.0_ReKi - end do - + call NearWakeCorrection( xd%Ct_azavg_filt, xd%Vx_rel_disk_filt, p, m, xd%Vx_wake, errStat, errMsg ) !Used for debugging: write(51,'(I5,100(1x,ES10.2E2))') n, xd%x_plane(n), xd%x_plane(n)/xd%D_rotor_filt(n), xd%Vx_wind_disk_filt(n) + xd%Vx_wake(:,n), xd%Vr_wake(:,n) @@ -890,16 +923,16 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) correction = 0.0_ReKi do i = 0, min(n+1,p%NumPlanes-1) - x_plane = u%Vx_rel_disk*real(i,ReKi)*real(p%DT,ReKi) + y%x_plane(i) = u%Vx_rel_disk*real(i,ReKi)*real(p%DT,ReKi) - correction = correction + GetYawCorrection(u%YawErr, u%xhat_disk, x_plane, p, errStat2, errMsg2) + correction = correction + GetYawCorrection(u%YawErr, u%xhat_disk, y%x_plane(i), p, errStat2, errMsg2) call SetErrStat(errStat2, errMsg2, errStat, errMsg, RoutineName) if (errStat >= AbortErrLev) then ! TEST: E3 return end if - y%p_plane (:,i) = u%p_hub(:) + x_plane*u%xhat_disk(:) + correction + y%p_plane (:,i) = u%p_hub(:) + y%x_plane(i)*u%xhat_disk(:) + correction y%xhat_plane(:,i) = u%xhat_disk(:) @@ -915,62 +948,15 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) end if end do - - - ! Initialze Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. - - m%r_wake(0) = 0.0_ReKi - - do j=0,p%NumRadii-1 - - ! compute m%a using the [n+1] values of Ct_azavg_filt - if ( u%Ct_azavg(j) > 2.0_ReKi ) then - ! THROW ERROR because we are in the prop-brake region - ! TEST: E5 - call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., u%Ct_azavg(j) > 2.0.', errStat, errMsg, RoutineName) - - return - else if ( u%Ct_azavg(j) >= 24.0_ReKi/25.0_ReKi ) then - m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*u%Ct_azavg(j)-12.0_ReKi))/14.0_ReKi - else - m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-u%Ct_azavg(j)) - end if - - if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then - ! TEST: E6 - call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) - - return - end if - - if (j > 0) then - m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) - end if - - end do - - ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake - - ! Use the [n+1] version of xd%Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) - y%Vx_wake(0,0) = - u%Vx_rel_disk*p%C_Nearwake*m%a(0) - y%Vx_wake(0,1) = y%Vx_wake(0,0) - - ILo = 0 - do j=1, p%NumRadii-1 - ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation - a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) - - ! [n+1] - y%Vx_wake(j,0) = -u%Vx_rel_disk*p%C_NearWake*a_interp - y%Vx_wake(j,1) = y%Vx_wake(j,0) - end do - - + ! Initialze Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. + call NearWakeCorrection( u%Ct_azavg, u%Vx_rel_disk, p, m, y%Vx_wake, errStat, errMsg ) + if (errStat > AbortErrLev) return + return else - + y%x_plane = xd%x_plane y%p_plane = xd%p_plane y%xhat_plane = xd%xhat_plane y%Vx_wake = xd%Vx_wake @@ -1105,62 +1091,13 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs end do - ! Only need to set the 0 index because everything else is already initialized to zero. - - xd%Vx_rel_disk_filt = u%Vx_rel_disk - + xd%Vx_rel_disk_filt = u%Vx_rel_disk ! Initialze Ct_azavg_filt and Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. + xd%Ct_azavg_filt (:) = u%Ct_azavg(:) - m%r_wake(0) = 0.0_ReKi - - do j=0,p%NumRadii-1 - - xd%Ct_azavg_filt (j) = u%Ct_azavg(j) - - ! compute m%a using the [n+1] values of Ct_azavg_filt - if ( xd%Ct_azavg_filt(j) > 2.0_ReKi ) then - ! THROW ERROR because we are in the prop-brake region - ! TEST: E5 - call SetErrStat(ErrID_FATAL, 'Wake model is not valid in the propeller-brake region, i.e., u%Ct_azavg(j) > 2.0.', errStat, errMsg, RoutineName) - - return - else if ( xd%Ct_azavg_filt(j) >= 24.0_ReKi/25.0_ReKi ) then - m%a(j) = (2.0_ReKi + 3.0_ReKi*sqrt(14.0_ReKi*xd%Ct_azavg_filt(j)-12.0_ReKi))/14.0_ReKi - else - m%a(j) = 0.5_ReKi - 0.5_ReKi*sqrt( 1.0_ReKi-xd%Ct_azavg_filt(j)) - end if - - if ( EqualRealNos(m%a(j),(1.0_ReKi / p%C_NearWake)) .or. (m%a(j) > (1.0_ReKi / p%C_NearWake)) ) then - ! TEST: E6 - call SetErrStat(ErrID_FATAL, 'Local induction is high enough to invalidate the near-wake correction, i.e., m%a(i) >= 1.0_ReKi / p%C_NearWake.', errStat, errMsg, RoutineName) - - return - end if - - if (j > 0) then - m%r_wake(j) = sqrt(m%r_wake(j-1)**2 + p%dr*( ((1.0_ReKi - m%a(j))*p%r(j)) / (1.0_ReKi-p%C_NearWake*m%a(j)) + ((1.0_ReKi - m%a(j-1))*p%r(j-1)) / (1.0_ReKi-p%C_NearWake*m%a(j-1)) ) ) - end if - - end do - - ! NOTE: We need another loop over NumRadii because we need the complete m%a() vector so that we can interpolate into m%a() using the value of r_wake - - ! Use the [n+1] version of xd%Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) - xd%Vx_wake(0,0) = - xd%Vx_rel_disk_filt*p%C_Nearwake*m%a(0) - xd%Vx_wake(0,1) = xd%Vx_wake(0,0) - - ILo = 0 - do j=1, p%NumRadii-1 - - ! given r_wake and m%a at p%dr increments, find value of m%a(r_wake) using interpolation - a_interp = InterpBin( p%r(j),m%r_wake, m%a, ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + call NearWakeCorrection( xd%Ct_azavg_filt, xd%Vx_rel_disk_filt, p, m, xd%Vx_wake, errStat, errMsg ) - ! [n+1] - xd%Vx_wake(j,0) = -xd%Vx_rel_disk_filt*p%C_NearWake*a_interp - xd%Vx_wake(j,1) = xd%Vx_wake(j,0) - end do - end subroutine InitStatesWithInputs !---------------------------------------------------------------------------------------------------------------------------------- diff --git a/modules-local/wakedynamics/src/WakeDynamics_Registry.txt b/modules-local/wakedynamics/src/WakeDynamics_Registry.txt index d11b1f44e6..f9c914da33 100644 --- a/modules-local/wakedynamics/src/WakeDynamics_Registry.txt +++ b/modules-local/wakedynamics/src/WakeDynamics_Registry.txt @@ -156,4 +156,5 @@ typedef ^ OutputType ReKi p_plane {:}{:} - typedef ^ OutputType ReKi Vx_wake {:}{:} - - "Axial wake velocity deficit at wake planes, distributed radially" m/s typedef ^ OutputType ReKi Vr_wake {:}{:} - - "Radial wake velocity deficit at wake planes, distributed radially" m/s typedef ^ OutputType ReKi D_wake {:} - - "Wake diameters at wake planes" m +typedef ^ OutputType ReKi x_plane {:} - - "Downwind distance from rotor to each wake plane" m From 31e90ec0e6d7c43524a5fb8095e6f4ac854a0034 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 18 May 2017 16:49:19 -0600 Subject: [PATCH 010/386] Rework TrilinearInterpRegGrid Reworked TrilinearInterpRegGrid based on FF_Interp --- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 90 +++++++++++++++++---- 1 file changed, 75 insertions(+), 15 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index fb158dd0df..490af12e81 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -42,32 +42,87 @@ MODULE FAST_Farm_Subs CONTAINS - + + !+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+- + !> This function is used to interpolate into the full-field wind array or tower array if it has + !! been defined and is necessary for the given inputs. It receives X, Y, Z and + !! TIME from the calling routine. It then computes a time shift due to a nonzero X based upon + !! the average windspeed. The modified time is used to decide which pair of time slices to interpolate + !! within and between. After finding the two time slices, it decides which four grid points bound the + !! (Y,Z) pair. It does a bilinear interpolation for each time slice. Linear interpolation is then used + !! to interpolate between time slices. This routine assumes that X is downwind, Y is to the left when + !! looking downwind and Z is up. It also assumes that no extrapolation will be needed. + !! + !! If tower points are used, it assumes the velocity at the ground is 0. It interpolates between + !! heights and between time slices, but ignores the Y input. + !! + !! 11/07/1994 - Created by M. Buhl from the original TURBINT. + !! 09/25/1997 - Modified by M. Buhl to use f90 constructs and new variable names. Renamed to FF_Interp. + !! 09/23/2009 - Modified by B. Jonkman to use arguments instead of modules to determine time and position. + !! Height is now relative to the ground + !! 16-Apr-2013 - A. Platt, NREL. Converted to modular framework. Modified for NWTC_Library 2.0 subroutine TrilinearInterpRegGrid(V, pt, dims, val) - real(ReKi), intent(in ) :: V(:,:,:,:) - real(ReKi), intent(in ) :: pt(3) - integer(IntKi), intent(in ) :: dims(3) - real(ReKi), intent( out) :: val(3) + real(ReKi), intent(in ) :: V(:,:,:,:) !< The volume data being sampled + real(ReKi), intent(in ) :: pt(3) !< The point, in grid coordinates where we want to sample the data + integer(IntKi), intent(in ) :: dims(3) !< The grid dimensions + real(ReKi), intent( out) :: val(3) !< The interpolated value of V at location, pt - integer(IntKi) :: x0,x1,y0,y1,z0,z1 + integer(IntKi) :: x0,x1,y0,y1,z0,z1, i real(ReKi) :: xd,yd,zd,c00(3),c01(3),c10(3),c11(3),c0(3),c1(3) + REAL(ReKi) :: N(8) ! array for holding scaling factors for the interpolation algorithm + REAL(ReKi) :: u(8) ! array for holding the corner values for the interpolation algorithm across a cubic volume + real(ReKi) :: val2(3) x0 = floor(pt(1)) x1 = x0 + 1 if (x0 == dims(1)) x1 = x0 ! Handle case where x0 is the last index in the grid, in this case xd = 0.0, so the 2nd term in the interpolation will not contribute - xd = pt(1) - x0 + + xd = 2.0_ReKi * (pt(1) - REAL(x0, ReKi)) - 1.0_ReKi y0 = floor(pt(2)) y1 = y0 + 1 if (y0 == dims(2)) y1 = y0 ! Handle case where y0 is the last index in the grid, in this case yd = 0.0, so the 2nd term in the interpolation will not contribute - yd = pt(2) - y0 + yd = 2.0_ReKi * (pt(2) - REAL(y0, ReKi)) - 1.0_ReKi z0 = floor(pt(3)) z1 = z0 + 1 if (z0 == dims(3)) z1 = z0 ! Handle case where z0 is the last index in the grid, in this case zd = 0.0, so the 2nd term in the interpolation will not contribute - zd = pt(3) - z0 + zd = 2.0_ReKi * (pt(3) - REAL(z0, ReKi)) - 1.0_ReKi + + !------------------------------------------------------------------------------------------------- + ! Interpolate on the grid + !------------------------------------------------------------------------------------------------- + + + + N(1) = ( 1.0_ReKi + zd )*( 1.0_ReKi - yd )*( 1.0_ReKi - xd ) + N(2) = ( 1.0_ReKi + zd )*( 1.0_ReKi + yd )*( 1.0_ReKi - xd ) + N(3) = ( 1.0_ReKi - zd )*( 1.0_ReKi + yd )*( 1.0_ReKi - xd ) + N(4) = ( 1.0_ReKi - zd )*( 1.0_ReKi - yd )*( 1.0_ReKi - xd ) + N(5) = ( 1.0_ReKi + zd )*( 1.0_ReKi - yd )*( 1.0_ReKi + xd ) + N(6) = ( 1.0_ReKi + zd )*( 1.0_ReKi + yd )*( 1.0_ReKi + xd ) + N(7) = ( 1.0_ReKi - zd )*( 1.0_ReKi + yd )*( 1.0_ReKi + xd ) + N(8) = ( 1.0_ReKi - zd )*( 1.0_ReKi - yd )*( 1.0_ReKi + xd ) + N = N / real( size(N), ReKi ) ! normalize + + do i=1,3 + u(1) = V( i, x0, y0, z1 ) + u(2) = V( i, x0, y1, z1 ) + u(3) = V( i, x0, y1, z0 ) + u(4) = V( i, x0, y0, z0 ) + u(5) = V( i, x1, y0, z1 ) + u(6) = V( i, x1, y1, z1 ) + u(7) = V( i, x1, y1, z0 ) + u(8) = V( i, x1, y0, z0 ) + + val(i) = SUM ( N * u ) + end do - + + + xd = pt(1) - x0 + yd = pt(2) - y0 + zd = pt(3) - z0 c00 = V(:,x0,y0,z0)*(1.0_ReKi-xd) + V(:,x1,y0,z0)*xd c01 = V(:,x0,y0,z1)*(1.0_ReKi-xd) + V(:,x1,y0,z1)*xd c10 = V(:,x0,y1,z0)*(1.0_ReKi-xd) + V(:,x1,y1,z0)*xd @@ -76,8 +131,13 @@ subroutine TrilinearInterpRegGrid(V, pt, dims, val) c0 = c00*(1.0_ReKi-yd) + c10*yd c1 = c01*(1.0_ReKi-yd) + c11*yd - val = c0 *(1.0_ReKi-zd) + c1 *zd - + val2 = c0 *(1.0_ReKi-zd) + c1 *zd + do i = 1,3 + if ( .not. EqualRealNos(val(i),val2(i)) ) then + write(*,*) "Different inpolated wind values: "//trim(Num2LStr(val(1)))//", "//trim(Num2LStr(val(2)))//", "//trim(Num2LStr(val(3)))//", "//trim(Num2LStr(val2(1)))//", "//trim(Num2LStr(val2(2)))//", "//trim(Num2LStr(val2(3))) + return + end if + end do end subroutine TrilinearInterpRegGrid @@ -1559,7 +1619,7 @@ subroutine Farm_WriteOutput(n, t, farm, ErrStat, ErrMsg) ! Loop over user-requested, downstream distances (OutDist), m do iOutDist = 1, farm%p%NOutDist - if ( farm%p%OutDist(iOutDist) >= farm%WD(nt)%xd%x_plane(min(farm%WD(nt)%p%NumPlanes-1,n+1)) ) then + if ( farm%p%OutDist(iOutDist) >= farm%WD(nt)%y%x_plane(min(farm%WD(nt)%p%NumPlanes-1,n+1)) ) then ! TODO: Handle this case. Invalid output farm%m%AllOuts(WkAxsXTD(iOutDist,nt)) = 0.0_ReKi @@ -1600,8 +1660,8 @@ subroutine Farm_WriteOutput(n, t, farm, ErrStat, ErrMsg) ! Find wake volume which contains the user-requested downstream location. do np = 0, min(farm%WD(nt)%p%NumPlanes-2 , n) - if ( ( farm%p%OutDist(iOutDist) >= farm%WD(nt)%xd%x_plane(np) ) .and. ( farm%p%OutDist(iOutDist) < farm%WD(nt)%xd%x_plane(np+1) ) ) then - delta = ( farm%p%OutDist(iOutDist) - farm%WD(nt)%xd%x_plane(np) ) / ( farm%WD(nt)%xd%x_plane(np+1) - farm%WD(nt)%xd%x_plane(np) ) + if ( ( farm%p%OutDist(iOutDist) >= farm%WD(nt)%y%x_plane(np) ) .and. ( farm%p%OutDist(iOutDist) < farm%WD(nt)%y%x_plane(np+1) ) ) then + delta = ( farm%p%OutDist(iOutDist) - farm%WD(nt)%y%x_plane(np) ) / ( farm%WD(nt)%y%x_plane(np+1) - farm%WD(nt)%y%x_plane(np) ) deltad = (1.0_ReKi-delta) exit end if From 02de2321c666ca586665b1b6fcd5a3346cc67856 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Fri, 19 May 2017 09:45:35 -0600 Subject: [PATCH 011/386] Fixed bug with radius check on r_e and r_s --- modules-local/awae/src/AWAE.f90 | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index eb26edd443..eb964ce419 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -130,17 +130,19 @@ subroutine ComputeLocals(n, u, p, y, m, errStat, errMsg) dp = u%p_plane(:,np+1,nt) - u%p_plane(:,np,nt) m%r_e(np,nt) = dot_product( u%xhat_plane(:,np ,nt), dp ) m%r_s(np,nt) = dot_product( u%xhat_plane(:,np+1,nt), dp ) - if ( m%r_e(np,nt) < rmax ) then - call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the ending wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) - return - end if - if ( m%r_s(np,nt) < rmax ) then - call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the starting wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) - return - end if if ( sinTerm > ( max( m%r_e(np,nt), m%r_s(np,nt) ) / ( 100.0_ReKi*rmax ) ) ) then m%parallelFlag(np,nt) = .false. + if ( u%D_wake(np,nt) > 0.0_ReKi ) then + if ( m%r_e(np,nt) < rmax ) then + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the ending wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + return + end if + if ( m%r_s(np,nt) < rmax ) then + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the starting wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + return + end if + end if m%r_e(np,nt) = m%r_e(np,nt) / sinTerm m%r_s(np,nt) = m%r_s(np,nt) / sinTerm m%rhat_s(:,np,nt) = (u%xhat_plane(:,np,nt)*cosTerm - u%xhat_plane(:,np+1,nt) ) / sinTerm From 28e5fe0357dbb74d7040a406bcc8755d83021087 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Mon, 22 May 2017 10:06:30 -0600 Subject: [PATCH 012/386] Draft of Summary File code --- glue-codes/fast-farm/src/FASTWrapper.f90 | 2 +- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 156 +++++++++++++++++- .../fast-farm/src/FAST_Farm_Registry.txt | 13 +- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 32 +++- .../wakedynamics/src/WakeDynamics.f90 | 35 +--- 5 files changed, 189 insertions(+), 49 deletions(-) diff --git a/glue-codes/fast-farm/src/FASTWrapper.f90 b/glue-codes/fast-farm/src/FASTWrapper.f90 index 16d96690d9..f37eaa426f 100644 --- a/glue-codes/fast-farm/src/FASTWrapper.f90 +++ b/glue-codes/fast-farm/src/FASTWrapper.f90 @@ -96,7 +96,7 @@ SUBROUTINE FWrap_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, Init ! Display the module information if (InitInp%TurbNum == 1) call DispNVD( FWrap_Ver ) - + InitOut%Ver = FWrap_Ver ! Define initial system states here: diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index f8eb17b930..1f9c13491d 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9825,6 +9825,151 @@ FUNCTION GetVersion(ThisProgVer) RETURN END FUNCTION GetVersion +!---------------------------------------------------------------------------------------------------------------------------------- +!> This routine generates the summary file, which contains a regurgitation of the input data and interpolated flexible body data. +SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) + + ! Passed variables + type(All_FastFarm_Data), INTENT(IN ) :: farm !< FAST.Farm data + type(WD_InputFileType), INTENT(IN ) :: WD_InputFileData !< Wake Dynamics Input File data + INTEGER(IntKi), INTENT(OUT) :: ErrStat !< Error status + CHARACTER(*), INTENT(OUT) :: ErrMsg !< Error message corresponding to ErrStat + + + ! Local variables. + + INTEGER(IntKi) :: I,J ! Index for the nodes. + INTEGER(IntKi) :: K ! Generic index (also for the blade number). + INTEGER(IntKi) :: UnSum ! I/O unit number for the summary output file + + CHARACTER(*), PARAMETER :: Fmt1 = "(34X,3(6X,'Blade',I2,:))" ! Format for outputting blade headings. + CHARACTER(*), PARAMETER :: Fmt2 = "(34X,3(6X,A,:))" ! Format for outputting blade headings. + CHARACTER(*), PARAMETER :: FmtDat = '(A,T35,3(:,F13.3))' ! Format for outputting mass and modal data. + CHARACTER(*), PARAMETER :: FmtDatT = '(A,T35,1(:,F13.8))' ! Format for outputting time steps. + CHARACTER(100) :: RotorType ! Text description of rotor. + CHARACTER(30) :: Fmt + CHARACTER(30) :: OutPFmt ! Format to print list of selected output channels to summary file + CHARACTER(10) :: DOFEnabled ! String to say if a DOF is enabled or disabled + CHARACTER(2) :: outStr + CHARACTER(10) :: CalWakeDiamStr + + + ! Open the summary file and give it a heading. + + CALL GetNewUnit( UnSum, ErrStat, ErrMsg ) + IF ( ErrStat /= ErrID_None ) RETURN + + CALL OpenFOutFile ( UnSum, TRIM( farm%p%OutFileRoot )//'.sum', ErrStat, ErrMsg ) + IF ( ErrStat /= ErrID_None ) RETURN + + + ! Heading: + !.......................... Module Versions ..................................................... + + + WRITE (UnSum,'(A)') 'FAST.Farm Summary File' + WRITE (UnSum,'(/A)') TRIM( farm%p%FileDescLines(1) ) + + WRITE (UnSum,'(2X,A)' ) 'compiled with' + Fmt = '(4x,A)' + WRITE (UnSum,Fmt) TRIM( GetNVD( NWTC_Ver ) ) + WRITE (UnSum,Fmt) TRIM( GetNVD( farm%p%Module_Ver( ModuleFF_SC ) ) ) + WRITE (UnSum,Fmt) TRIM( GetNVD( farm%p%Module_Ver( ModuleFF_FWrap ) ) ) + WRITE (UnSum,Fmt) TRIM( GetNVD( farm%p%Module_Ver( ModuleFF_WD ) ) ) + WRITE (UnSum,Fmt) TRIM( GetNVD( farm%p%Module_Ver( ModuleFF_AWAE ) ) ) + !WRITE (y_FAST%UnSum,Fmt) TRIM( GetNVD( ) ) + + WRITE (UnSum,'(/,A)') 'Description from the FAST.Farm input file: '//trim(farm%p%FTitle) + + WRITE (UnSum,'(/,A)') 'Ambient Wind Input Filepath: '//trim(farm%p%WindFilePath) + + !.................................. + ! Turbine information. + !.................................. + + WRITE (UnSum,'(/,A)' ) 'Wind Turbines: '//trim(Num2LStr(farm%p%NumTurbines)) + WRITE (UnSum,'(2X,A)') 'Turbine Number Output Turbine Number X Y Z FAST Time Step FAST SubCycles FAST Input File' + WRITE (UnSum,'(2X,A)') ' (-) (-) (m) (m) (m) (S) (-) (-)' + + do I = 1,farm%p%NumTurbines + if ( I < 10 ) then + outStr = adjustr(trim(Num2LStr(I))) + else + outStr = '- ' + end if + + WRITE(UnSum,'(6X,I4,16X,A4,9X,3F10.3,5X,F9.4,8X,I4,10X,A)') I, outStr, farm%p%WT_Position(1,I), farm%p%WT_Position(2,I),farm%p%WT_Position(3,I), farm%p%DT, farm%p%n_high_low, trim(farm%p%WT_FASTInFile(I)) + + end do + + WRITE (UnSum,'(/,A)' ) 'Wake Dynamics Finite-Difference Grid: '//trim(Num2LStr(farm%WD(1)%p%NumRadii))//' Radii, '//trim(Num2LStr(farm%WD(1)%p%NumPlanes))//' Planes' + WRITE (UnSum,'(2X,A)') 'Radial Node Number Output Node Number Radius' + WRITE (UnSum,'(2X,A)') ' (-) (-) (m) ' + do I = 0, farm%WD(1)%p%NumRadii-1 + outStr = ' -' + do J = 1, farm%p%NOutRadii + if (farm%p%OutRadii(J) == I ) then + outStr = trim(Num2LStr(J)) + exit + end if + end do + + WRITE(UnSum,'(8X,I4,17X,A2,9X,F10.3)') I, outStr, farm%WD(1)%p%r(I) + + end do + + WRITE (UnSum,'(/,A)' ) 'Wake Dynamics Parameters' + WRITE (UnSum,'(2X,A)') 'Cut-off (corner) frequency of the low-pass time-filter for the wake advection, deflection, and meandering model (Hz): '//trim(Num2LStr(WD_InputFileData%f_c)) + WRITE (UnSum,'(4X,A)') '( low-pass time-filter parameter (-): '//trim(Num2LStr(farm%WD(1)%p%filtParam))//' )' + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset at the rotor (m): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_O)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset at the rotor scaled with yaw error (m/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_OY)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset scaled with downstream distance (-): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_x)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset scaled with downstream distance and yaw error (1/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_xY)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter for near-wake correction (-): '//trim(Num2LStr(farm%WD(1)%p%C_NearWake)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter for the influence of ambient turbulence in the eddy viscosity (-): '//trim(Num2LStr(farm%WD(1)%p%k_vAmb)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter for the influence of the shear layer in the eddy viscosity (-): '//trim(Num2LStr(farm%WD(1)%p%k_vShr)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for ambient turbulence defining the transitional diameter fraction between the minimum and exponential regions (-): '//trim(Num2LStr(farm%WD(1)%p%C_vAmb_DMin)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for ambient turbulence defining the transitional diameter fraction between the exponential and maximum regions (-): '//trim(Num2LStr(farm%WD(1)%p%C_vAmb_DMax)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for ambient turbulence defining the value in the minimum region (-): '//trim(Num2LStr(farm%WD(1)%p%C_vAmb_FMin)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for ambient turbulence defining the exponent in the exponential region (-): '//trim(Num2LStr(farm%WD(1)%p%C_vAmb_Exp)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for the shear layer defining the transitional diameter fraction between the minimum and exponential regions (-): '//trim(Num2LStr(farm%WD(1)%p%C_vShr_DMin)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for the shear layer defining the transitional diameter fraction between the exponential and maximum regions (-): '//trim(Num2LStr(farm%WD(1)%p%C_vShr_DMax)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for the shear layer defining the functional value in the minimum region (-): '//trim(Num2LStr(farm%WD(1)%p%C_vShr_FMin)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the eddy viscosity filter function for the shear layer defining the exponent in the exponential region (-): '//trim(Num2LStr(farm%WD(1)%p%C_vShr_Exp)) + WRITE (UnSum,'(2X,A)') 'Wake diameter calculation model (-): '//trim(Num2LStr(farm%WD(1)%p%Mod_WakeDiam)) + if ( farm%WD(1)%p%Mod_WakeDiam > 1 ) then + CalWakeDiamStr = trim(Num2LStr(farm%WD(1)%p%C_WakeDiam)) + else + CalWakeDiamStr = '-' + end if + + WRITE (UnSum,'(2X,A)') 'Calibrated parameter for wake diameter calculation (-): '//CalWakeDiamStr + + WRITE (UnSum,'(/,A)' ) 'Time Steps' + WRITE (UnSum,'(2X,A)') 'Component Time Step(s) Subcyles' + WRITE (UnSum,'(2X,A)') ' (-) (s) (-)' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'FAST.Farm (glue code) ',farm%p%dt, '1' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Super Controller ',farm%p%dt, '1' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'FAST Wrapper ',farm%p%dt, '1 (See table above for FAST.)' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Wake Dynamics ',farm%p%dt, '1' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Ambient Wind and Array Effects ',farm%p%dt, '1' + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Low -resolution wind input ',farm%p%dt, '1' + WRITE (UnSum,'(2X,A,F10.4,12X,I2)') 'High-resolution wind input ',farm%p%DT_high, farm%p%n_high_low + WRITE (UnSum,'(2X,A,F10.4,12X,I2)') 'Wind visualization output ',farm%AWAE%p%WrDisSkp1*farm%p%dt, farm%AWAE%p%WrDisSkp1-1 + WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'FAST.Farm output files ',farm%p%dt, '1' + + WRITE (UnSum,'(/,A)' ) 'Requested Channels in FAST.Farm Output Files: '//trim(Num2LStr(farm%p%NumOuts+1)) + WRITE (UnSum,'(2X,A)' ) 'Number Name Units' + WRITE (UnSum,'(2X,A)' ) ' 0 Time (s)' + do I=1,farm%p%NumOuts + WRITE (UnSum,'(2X,I4,7X,A14,A14)' ) I, farm%p%OutParam(I)%Name,farm%p%OutParam(I)%Units + end do + + CLOSE(UnSum) + +RETURN +END SUBROUTINE Farm_PrintSum + !---------------------------------------------------------------------------------------------------------------------------------- !> This routine initializes the output for the glue code, including writing the header for the primary output file. SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) @@ -13850,19 +13995,16 @@ SUBROUTINE SetOutParam(OutList, farm, ErrStat, ErrMsg ) InvalidOutput( WVDisX (i) ) = .true. InvalidOutput( WVDisY (i) ) = .true. InvalidOutput( WVDisZ (i) ) = .true. - end if - - + end if end do - do i = farm%p%NWindVel+1, 9 - + + do i = farm%p%NWindVel+1, 9 InvalidOutput( WVAmbX (i) ) = .true. InvalidOutput( WVAmbY (i) ) = .true. InvalidOutput( WVAmbZ (i) ) = .true. InvalidOutput( WVDisX (i) ) = .true. InvalidOutput( WVDisY (i) ) = .true. - InvalidOutput( WVDisZ (i) ) = .true. - + InvalidOutput( WVDisZ (i) ) = .true. end do ! ! ................. End of validity checking ................. diff --git a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt index 1151abb2aa..9c8037d7f0 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt +++ b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt @@ -16,6 +16,12 @@ usefrom FASTWrapper_Registry.txt usefrom WakeDynamics_Registry.txt usefrom AWAE_Registry.txt +param FAST_Farm/Farm - INTEGER NumFFModules - 4 - "The number of modules available in FAST.Farm" - +param ^ - INTEGER ModuleFF_None - 0 - "No module selected" - +param ^ - INTEGER ModuleFF_SC - 1 - "Super Controller" - +param ^ - INTEGER ModuleFF_FWrap - 2 - "FAST Wrapper" - +param ^ - INTEGER ModuleFF_WD - 3 - "Wake Dynamics" - +param ^ - INTEGER ModuleFF_AWAE - 4 - "Ambient Wind and Array Effects" - # ..... Parameters ................................................................................................................ typedef FAST_Farm/Farm ParameterType DbKi DT - - - "Time step for low-resolution wind data input files; will be used as the global FAST.Farm time step" seconds typedef ^ ParameterType DbKi DT_high - - - "High-resolution time step" seconds @@ -31,6 +37,7 @@ typedef ^ ParameterType INTEGER n_ChkptTime - typedef ^ ParameterType DbKi TStart - - - "Time to begin tabular output" s typedef ^ ParameterType IntKi n_TMax - - - "Number of the time step of TMax (the end time of the simulation)" - # parameters for data output to files: +typedef ^ ParameterType LOGICAL SumPrint - - - "Print summary data to file? (.sum)" - typedef ^ ParameterType LOGICAL WrBinOutFile - - - "Write a binary output file? (.outb)" - typedef ^ ParameterType LOGICAL WrTxtOutFile - - - "Write a text (formatted) output file? (.out)" - typedef ^ ParameterType CHARACTER(1) Delim - - - "Delimiter between columns of text output file (.out): space or tab" - @@ -48,8 +55,10 @@ typedef ^ ParameterType ReKi WindVelY {: typedef ^ ParameterType ReKi WindVelZ {:} - - "List of coordinates in the Z direction for wind output [1 to NWindVel]" meters typedef ^ ParameterType OutParmFFType OutParam {:} - - "Names and units (and other characteristics) of all requested output parameters" - typedef ^ ParameterType IntKi NumOuts - - - "Number of user-requested outputs" - -typedef ^ ^ IntKi NOutSteps - - - "Maximum number of output steps" - -typedef ^ ^ CHARACTER(1024) FileDescLines {3} -- "File Description lines" - +typedef ^ ParameterType IntKi NOutSteps - - - "Maximum number of output steps" - +typedef ^ ParameterType CHARACTER(1024) FileDescLines {3} - - "File Description lines" - +typedef ^ ParameterType ProgDesc Module_Ver {NumModules} - - "Version information from all modules" + typedef ^ ParameterType IntKi UnOu - - - "File unit for Fast.Farm output data" - typedef ^ ParameterType ReKi dX_low - - - "The spacing of the low-resolution nodes in X direction" m typedef ^ ParameterType ReKi dY_low - - - "The spacing of the low-resolution nodes in Y direction" m diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index 490af12e81..d2f8b8eb91 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -172,7 +172,7 @@ SUBROUTINE Farm_Initialize( farm, InputFile, ErrStat, ErrMsg ) CHARACTER(*), PARAMETER :: RoutineName = 'Farm_Initialize' CHARACTER(ChanLenFF),ALLOCATABLE :: OutList(:) ! list of user-requested output channels - + INTEGER(IntKi) :: i !.......... ErrStat = ErrID_None ErrMsg = "" @@ -191,7 +191,16 @@ SUBROUTINE Farm_Initialize( farm, InputFile, ErrStat, ErrMsg ) ! Determine the root name of the primary file (will be used for output files) CALL GetRoot( InputFile, farm%p%OutFileRoot ) - + + DO i=1,NumFFModules + farm%p%Module_Ver(i)%Date = 'unknown date' + farm%p%Module_Ver(i)%Ver = 'unknown version' + END DO + farm%p%Module_Ver( ModuleFF_SC )%Name = 'Super Controller' + farm%p%Module_Ver( ModuleFF_FWrap )%Name = 'FAST Wrapper' + farm%p%Module_Ver( ModuleFF_WD )%Name = 'Wake Dynamics' + farm%p%Module_Ver( ModuleFF_AWAE )%Name = 'Ambient Wind and Array Effects' + !............................................................................................................................... ! step 1: read input file !............................................................................................................................... @@ -270,7 +279,7 @@ SUBROUTINE Farm_Initialize( farm, InputFile, ErrStat, ErrMsg ) farm%p%dX_low = AWAE_InitOutput%dX_low farm%p%dY_low = AWAE_InitOutput%dY_low farm%p%dZ_low = AWAE_InitOutput%dZ_low - + farm%p%Module_Ver( ModuleFF_AWAE ) = AWAE_InitOutput%Ver !------------------- ! b. CALL SC_Init @@ -312,6 +321,12 @@ SUBROUTINE Farm_Initialize( farm, InputFile, ErrStat, ErrMsg ) call Farm_InitOutput( farm, ErrStat, ErrMsg ) + ! Print the summary file if requested: + IF (farm%p%SumPrint) THEN + CALL Farm_PrintSum( farm, WD_InitInput%InputFileData, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + END IF + !............................................................................................................................... ! Destroy initializion data !............................................................................................................................... @@ -352,7 +367,6 @@ SUBROUTINE Farm_ReadPrimaryFile( InputFile, p, WD_InitInp, AWAE_InitInp, OutList INTEGER(IntKi) :: OutFileFmt ! An integer that indicates what kind of tabular output should be generated (1=text, 2=binary, 3=both) INTEGER(IntKi) :: NLinTimes ! An integer that indicates how many times to linearize LOGICAL :: Echo ! Determines if an echo file should be written - LOGICAL :: SumPrint ! Determines if a summary file should be written LOGICAL :: TabDelim ! Determines if text output should be delimited by tabs (true) or space (false) CHARACTER(1024) :: PriPath ! Path name of the primary file @@ -896,7 +910,7 @@ SUBROUTINE Farm_ReadPrimaryFile( InputFile, p, WD_InitInp, AWAE_InitInp, OutList end if ! SumPrint - Print summary data to .sum? (flag): - CALL ReadVar( UnIn, InputFile, SumPrint, "SumPrint", "Print summary data to .sum? (flag)", ErrStat2, ErrMsg2, UnEc) + CALL ReadVar( UnIn, InputFile, p%SumPrint, "SumPrint", "Print summary data to .sum? (flag)", ErrStat2, ErrMsg2, UnEc) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) if ( ErrStat >= AbortErrLev ) then call cleanup() @@ -1250,7 +1264,9 @@ SUBROUTINE Farm_InitWD( farm, WD_InitInp, ErrStat, ErrMsg ) end if END DO - + + farm%p%Module_Ver( ModuleFF_WD ) = WD_InitOut%Ver + call cleanup() contains @@ -1336,6 +1352,8 @@ SUBROUTINE Farm_InitFAST( farm, WD_InitInp, AWAE_InitOutput, ErrStat, ErrMsg ) END DO + farm%p%Module_Ver( ModuleFF_FWrap ) = FWrap_InitOut%Ver + call cleanup() contains @@ -1372,6 +1390,8 @@ subroutine FARM_InitialCO(farm, ErrStat, ErrMsg) ErrMsg = "" + + !....................................................................................... ! Initial calls to AWAE and SC modules (steps 1. and 2. can be done in parallel) !....................................................................................... diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index e9d1177790..ff59b1c961 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -291,39 +291,6 @@ subroutine ThomasAlgorithm(nr, a, b, c, d, x, errStat, errMsg) end subroutine ThomasAlgorithm -!---------------------------------------------------------------------------------------------------------------------------------- -!> This subroutine sets the initialization output data structure, which contains data to be returned to the calling program (e.g., -!! FAST or WakeDynamics_Driver) -subroutine WD_SetInitOut(p, InputInp, InitOut, errStat, errMsg) - - type(WD_InitOutputType), intent( out) :: InitOut !< Initialization output data - type(WD_InitInputType), intent(in ) :: InputInp !< Initialization input data - type(WD_ParameterType), intent(in ) :: p !< Parameters - integer(IntKi), intent( out) :: errStat !< Error status of the operation - character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None - - - ! Local variables - integer(intKi) :: ErrStat2 ! temporary Error status - character(ErrMsgLen) :: ErrMsg2 ! temporary Error message - character(*), parameter :: RoutineName = 'WD_SetInitOut' - - - - integer(IntKi) :: i, j, k, f - integer(IntKi) :: NumCoords - - ! Initialize variables for this routine - - errStat = ErrID_None - errMsg = "" - - ! TODO: Set output data - - InitOut%Ver = WD_Ver - -end subroutine WD_SetInitOut - !---------------------------------------------------------------------------------------------------------------------------------- !> This routine is called at the start of the simulation to perform initialization steps. !! The parameters are set here and not changed during the simulation. @@ -527,6 +494,8 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut ! Define initialization output here !............................................................................................ + InitOut%Ver = WD_Ver + allocate ( y%xhat_plane(3,0:p%NumPlanes-1), STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for y%xhat_plane.', errStat, errMsg, RoutineName ) allocate ( y%p_plane (3,0:p%NumPlanes-1), STAT=ErrStat2 ) From ebf4d638a4baa62e30da88eec76c615f9f2c2a16 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Tue, 23 May 2017 11:19:04 -0600 Subject: [PATCH 013/386] Minor Fixes and Clean up to Greg's Latest Commit --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 5 +- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 64 +++++++------------ modules-local/awae/src/AWAE.f90 | 4 +- .../wakedynamics/src/WakeDynamics.f90 | 18 +++--- 4 files changed, 34 insertions(+), 57 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index 1f9c13491d..b007a38321 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9942,11 +9942,10 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) else CalWakeDiamStr = '-' end if - WRITE (UnSum,'(2X,A)') 'Calibrated parameter for wake diameter calculation (-): '//CalWakeDiamStr WRITE (UnSum,'(/,A)' ) 'Time Steps' - WRITE (UnSum,'(2X,A)') 'Component Time Step(s) Subcyles' + WRITE (UnSum,'(2X,A)') 'Component Time Step Subcyles' WRITE (UnSum,'(2X,A)') ' (-) (s) (-)' WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'FAST.Farm (glue code) ',farm%p%dt, '1' WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Super Controller ',farm%p%dt, '1' @@ -9955,7 +9954,7 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Ambient Wind and Array Effects ',farm%p%dt, '1' WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'Low -resolution wind input ',farm%p%dt, '1' WRITE (UnSum,'(2X,A,F10.4,12X,I2)') 'High-resolution wind input ',farm%p%DT_high, farm%p%n_high_low - WRITE (UnSum,'(2X,A,F10.4,12X,I2)') 'Wind visualization output ',farm%AWAE%p%WrDisSkp1*farm%p%dt, farm%AWAE%p%WrDisSkp1-1 + WRITE (UnSum,'(2X,A,F10.4,12X,I2,A)') 'Wind visualization output ',farm%AWAE%p%WrDisSkp1*farm%p%dt, farm%AWAE%p%WrDisSkp1, '^-1' WRITE (UnSum,'(2X,A,F10.4,13X,A)') 'FAST.Farm output files ',farm%p%dt, '1' WRITE (UnSum,'(/,A)' ) 'Requested Channels in FAST.Farm Output Files: '//trim(Num2LStr(farm%p%NumOuts+1)) diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index d2f8b8eb91..cb999d867b 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -43,24 +43,6 @@ MODULE FAST_Farm_Subs CONTAINS - !+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+- - !> This function is used to interpolate into the full-field wind array or tower array if it has - !! been defined and is necessary for the given inputs. It receives X, Y, Z and - !! TIME from the calling routine. It then computes a time shift due to a nonzero X based upon - !! the average windspeed. The modified time is used to decide which pair of time slices to interpolate - !! within and between. After finding the two time slices, it decides which four grid points bound the - !! (Y,Z) pair. It does a bilinear interpolation for each time slice. Linear interpolation is then used - !! to interpolate between time slices. This routine assumes that X is downwind, Y is to the left when - !! looking downwind and Z is up. It also assumes that no extrapolation will be needed. - !! - !! If tower points are used, it assumes the velocity at the ground is 0. It interpolates between - !! heights and between time slices, but ignores the Y input. - !! - !! 11/07/1994 - Created by M. Buhl from the original TURBINT. - !! 09/25/1997 - Modified by M. Buhl to use f90 constructs and new variable names. Renamed to FF_Interp. - !! 09/23/2009 - Modified by B. Jonkman to use arguments instead of modules to determine time and position. - !! Height is now relative to the ground - !! 16-Apr-2013 - A. Platt, NREL. Converted to modular framework. Modified for NWTC_Library 2.0 subroutine TrilinearInterpRegGrid(V, pt, dims, val) real(ReKi), intent(in ) :: V(:,:,:,:) !< The volume data being sampled @@ -75,15 +57,15 @@ subroutine TrilinearInterpRegGrid(V, pt, dims, val) real(ReKi) :: val2(3) x0 = floor(pt(1)) - x1 = x0 + 1 if (x0 == dims(1)) x1 = x0 ! Handle case where x0 is the last index in the grid, in this case xd = 0.0, so the 2nd term in the interpolation will not contribute - xd = 2.0_ReKi * (pt(1) - REAL(x0, ReKi)) - 1.0_ReKi + y0 = floor(pt(2)) y1 = y0 + 1 if (y0 == dims(2)) y1 = y0 ! Handle case where y0 is the last index in the grid, in this case yd = 0.0, so the 2nd term in the interpolation will not contribute yd = 2.0_ReKi * (pt(2) - REAL(y0, ReKi)) - 1.0_ReKi + z0 = floor(pt(3)) z1 = z0 + 1 if (z0 == dims(3)) z1 = z0 ! Handle case where z0 is the last index in the grid, in this case zd = 0.0, so the 2nd term in the interpolation will not contribute @@ -93,8 +75,6 @@ subroutine TrilinearInterpRegGrid(V, pt, dims, val) ! Interpolate on the grid !------------------------------------------------------------------------------------------------- - - N(1) = ( 1.0_ReKi + zd )*( 1.0_ReKi - yd )*( 1.0_ReKi - xd ) N(2) = ( 1.0_ReKi + zd )*( 1.0_ReKi + yd )*( 1.0_ReKi - xd ) N(3) = ( 1.0_ReKi - zd )*( 1.0_ReKi + yd )*( 1.0_ReKi - xd ) @@ -118,26 +98,26 @@ subroutine TrilinearInterpRegGrid(V, pt, dims, val) val(i) = SUM ( N * u ) end do - - - xd = pt(1) - x0 - yd = pt(2) - y0 - zd = pt(3) - z0 - c00 = V(:,x0,y0,z0)*(1.0_ReKi-xd) + V(:,x1,y0,z0)*xd - c01 = V(:,x0,y0,z1)*(1.0_ReKi-xd) + V(:,x1,y0,z1)*xd - c10 = V(:,x0,y1,z0)*(1.0_ReKi-xd) + V(:,x1,y1,z0)*xd - c11 = V(:,x0,y1,z1)*(1.0_ReKi-xd) + V(:,x1,y1,z1)*xd - - c0 = c00*(1.0_ReKi-yd) + c10*yd - c1 = c01*(1.0_ReKi-yd) + c11*yd - - val2 = c0 *(1.0_ReKi-zd) + c1 *zd - do i = 1,3 - if ( .not. EqualRealNos(val(i),val2(i)) ) then - write(*,*) "Different inpolated wind values: "//trim(Num2LStr(val(1)))//", "//trim(Num2LStr(val(2)))//", "//trim(Num2LStr(val(3)))//", "//trim(Num2LStr(val2(1)))//", "//trim(Num2LStr(val2(2)))//", "//trim(Num2LStr(val2(3))) - return - end if - end do + ! + ! + !xd = pt(1) - x0 + !yd = pt(2) - y0 + !zd = pt(3) - z0 + !c00 = V(:,x0,y0,z0)*(1.0_ReKi-xd) + V(:,x1,y0,z0)*xd + !c01 = V(:,x0,y0,z1)*(1.0_ReKi-xd) + V(:,x1,y0,z1)*xd + !c10 = V(:,x0,y1,z0)*(1.0_ReKi-xd) + V(:,x1,y1,z0)*xd + !c11 = V(:,x0,y1,z1)*(1.0_ReKi-xd) + V(:,x1,y1,z1)*xd + ! + !c0 = c00*(1.0_ReKi-yd) + c10*yd + !c1 = c01*(1.0_ReKi-yd) + c11*yd + ! + !val2 = c0 *(1.0_ReKi-zd) + c1 *zd + !do i = 1,3 + ! if ( .not. EqualRealNos(val(i),val2(i)) ) then + ! write(*,*) "Different inpolated wind values: "//trim(Num2LStr(val(1)))//", "//trim(Num2LStr(val(2)))//", "//trim(Num2LStr(val(3)))//", "//trim(Num2LStr(val2(1)))//", "//trim(Num2LStr(val2(2)))//", "//trim(Num2LStr(val2(3))) + ! return + ! end if + !end do end subroutine TrilinearInterpRegGrid diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index eb964ce419..927116797f 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -135,11 +135,11 @@ subroutine ComputeLocals(n, u, p, y, m, errStat, errMsg) m%parallelFlag(np,nt) = .false. if ( u%D_wake(np,nt) > 0.0_ReKi ) then if ( m%r_e(np,nt) < rmax ) then - call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the ending wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the ending wake plane from the line where the starting and ending wake planes intersect for a given wake volume (volume='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) return end if if ( m%r_s(np,nt) < rmax ) then - call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the starting wake plane from the line where the starting and ending wake planes intersect for a given wake volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) + call SetErrStat( ErrID_Fatal, 'Radius to the wake center in the starting wake plane from the line where the starting and ending wake planes intersect for a given wake volume (volume='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') is smaller than rmax: '//trim(num2lstr(rmax))//'.', errStat, errMsg, 'ComputeLocals' ) return end if end if diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index ff59b1c961..fd68665686 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -221,7 +221,6 @@ subroutine NearWakeCorrection( Ct_azavg_filt, Vx_rel_disk_filt, p, m, Vx_wake, e ! Use the [n+1] version of Vx_rel_disk_filt to determine the [n+1] version of Vx_wake(:,0) Vx_wake(0,0) = -Vx_rel_disk_filt*p%C_Nearwake*m%a(0) - Vx_wake(0,1) = Vx_wake(0,0) ILo = 0 do j=1, p%NumRadii-1 @@ -231,7 +230,7 @@ subroutine NearWakeCorrection( Ct_azavg_filt, Vx_rel_disk_filt, p, m, Vx_wake, e ! [n+1] Vx_wake(j,0) = -Vx_rel_disk_filt*p%C_NearWake*a_interp - Vx_wake(j,1) = Vx_wake(j,0) + end do end subroutine NearWakeCorrection @@ -615,9 +614,9 @@ subroutine WD_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg integer(intKi) :: errStat2 ! temporary Error status character(ErrMsgLen) :: errMsg2 ! temporary Error message character(*), parameter :: RoutineName = 'WD_UpdateStates' - real(ReKi) :: lstar, dx, Vx_wake_min, r_wake, a_interp, norm2_xhat_plane, EddyTermA, EddyTermB + real(ReKi) :: lstar, dx, Vx_wake_min, norm2_xhat_plane, EddyTermA, EddyTermB real(ReKi) :: dy_HWkDfl(3) - integer(intKi) :: i,j, ILo, maxPln + integer(intKi) :: i,j, maxPln errStat = ErrID_None errMsg = "" @@ -874,13 +873,11 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) integer, parameter :: indx = 1 - integer(intKi) :: n, i, j, ILo + integer(intKi) :: n, i integer(intKi) :: ErrStat2 character(ErrMsgLen) :: ErrMsg2 character(*), parameter :: RoutineName = 'WD_CalcOutput' real(ReKi) :: correction(3) - real(ReKi) :: x_plane - real(ReKi) :: a_interp errStat = ErrID_None errMsg = "" @@ -891,7 +888,7 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) ! TODO: This entire block needs to be reviewed correction = 0.0_ReKi - do i = 0, min(n+1,p%NumPlanes-1) + do i = 0, 1 y%x_plane(i) = u%Vx_rel_disk*real(i,ReKi)*real(p%DT,ReKi) correction = correction + GetYawCorrection(u%YawErr, u%xhat_disk, y%x_plane(i), p, errStat2, errMsg2) @@ -921,6 +918,7 @@ subroutine WD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg ) ! Initialze Vx_wake; Vr_wake is already initialized to zero, so, we don't need to do that here. call NearWakeCorrection( u%Ct_azavg, u%Vx_rel_disk, p, m, y%Vx_wake, errStat, errMsg ) if (errStat > AbortErrLev) return + y%Vx_wake(:,1) = y%Vx_wake(:,0) return @@ -1024,8 +1022,7 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs INTEGER(IntKi), intent( out) :: errStat !< Error status of the operation CHARACTER(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None character(*), parameter :: RoutineName = 'InitStatesWithInputs' - integer(IntKi) :: i,j, ILo - real(ReKi) :: a_interp + integer(IntKi) :: i integer(intKi) :: ErrStat2 character(ErrMsgLen) :: ErrMsg2 real(ReKi) :: correction(3) @@ -1066,6 +1063,7 @@ subroutine InitStatesWithInputs(numPlanes, numRadii, u, p, xd, m, errStat, errMs xd%Ct_azavg_filt (:) = u%Ct_azavg(:) call NearWakeCorrection( xd%Ct_azavg_filt, xd%Vx_rel_disk_filt, p, m, xd%Vx_wake, errStat, errMsg ) + xd%Vx_wake(:,1) = xd%Vx_wake(:,0) end subroutine InitStatesWithInputs From 6b6b48fac2a93664713b2041b9cbed137ced3195 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Wed, 31 May 2017 14:21:25 -0600 Subject: [PATCH 014/386] Added error handling to ReadVTK_SP_vectors Added interface for WrVTK_SP_vectors3D --- modules-local/nwtc-library/src/NWTC_IO.f90 | 91 ++++++++++++++++++++-- 1 file changed, 84 insertions(+), 7 deletions(-) diff --git a/modules-local/nwtc-library/src/NWTC_IO.f90 b/modules-local/nwtc-library/src/NWTC_IO.f90 index 3b5bda1e6f..0e6b48a4d9 100644 --- a/modules-local/nwtc-library/src/NWTC_IO.f90 +++ b/modules-local/nwtc-library/src/NWTC_IO.f90 @@ -234,7 +234,12 @@ MODULE NWTC_IO MODULE PROCEDURE WrR16AryFileNR END INTERFACE - + INTERFACE WrVTK_SP_vectors3D + MODULE PROCEDURE WrVTK_SP_R4vectors3D + MODULE PROCEDURE WrVTK_SP_R8vectors3D + MODULE PROCEDURE WrVTK_SP_R16vectors3D + END INTERFACE + CONTAINS !> This routine adjusts strings created from real numbers (4, 8, or 16-byte) @@ -7840,7 +7845,7 @@ SUBROUTINE ReadVTK_SP_vectors( FileName, Un, dims, gridVals, ErrStat, ErrMsg ) CHARACTER(*) , INTENT(IN ) :: FileName !< Name of output file INTEGER(IntKi) , INTENT(IN ) :: Un !< unit number of opened file INTEGER(IntKi) , INTENT(IN ) :: dims(3) !< dimension of the 3D grid (nX,nY,nZ) - REAL(ReKi) , INTENT( OUT) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ), must be pre-allocated + REAL(SiKi) , INTENT( OUT) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ), must be pre-allocated INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< error level/status of OpenFOutFile operation CHARACTER(*) , INTENT( OUT) :: ErrMsg !< message when error occurs @@ -7854,9 +7859,12 @@ SUBROUTINE ReadVTK_SP_vectors( FileName, Un, dims, gridVals, ErrStat, ErrMsg ) ErrStat = ErrID_None ErrMsg = '' - READ(Un,*) gridVals(1:3,1:dims(1),1:dims(2),1:dims(3)) - + READ(Un,*, IOSTAT=ErrStat) gridVals(1:3,1:dims(1),1:dims(2),1:dims(3)) + close(Un) + if (ErrStat /= 0) then + CALL SetErrStat( ErrID_Fatal, 'Invalid vtk file: '//trim(FileName)//'.', ErrStat, ErrMsg, 'ReadVTK_SP_vectors' ) + end if END SUBROUTINE ReadVTK_SP_vectors @@ -7884,15 +7892,84 @@ SUBROUTINE WrVTK_SP_header( FileName, descr, Un, ErrStat, ErrMsg ) END SUBROUTINE WrVTK_SP_header + SUBROUTINE WrVTK_SP_R4vectors3D( Un, dataDescr, dims, origin, gridSpacing, gridVals, ErrStat, ErrMsg ) + + INTEGER(IntKi) , INTENT(IN ) :: Un !< unit number of previously opened file (via call to WrVTK_SP_header) + CHARACTER(*) , INTENT(IN ) :: dataDescr !< Short label describing the vector data + INTEGER(IntKi) , INTENT(IN ) :: dims(3) !< dimension of the 3D grid (nX,nY,nZ) + REAL(ReKi) , INTENT(IN ) :: origin(3) !< the lower-left corner of the 3D grid (X0,Y0,Z0) + REAL(ReKi) , INTENT(IN ) :: gridSpacing(3) !< spacing between grid points in each of the 3 directions (dX,dY,dZ) + REAL(SiKi) , INTENT(IN ) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ) + INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< error level/status of OpenFOutFile operation + CHARACTER(*) , INTENT( OUT) :: ErrMsg !< message when error occurs + + INTEGER(IntKi) :: nPts ! Total number of grid points + + if ( .not. (Un > 0) ) then + ErrStat = ErrID_Fatal + ErrMsg = 'WrVTK_SP_points: Invalid file unit, be sure to call WrVTK_SP_header prior to calling WrVTK_SP_points.' + return + end if + + ErrStat = ErrID_None + ErrMsg = '' + nPts = dims(1)*dims(2)*dims(3) + + ! Note: gridVals must be stored such that the left-most dimension is X and the right-most dimension is Z + WRITE(Un,'(A,3(i5,1X))') 'DIMENSIONS ', dims + WRITE(Un,'(A,3(f10.2,1X))') 'ORIGIN ' , origin + WRITE(Un,'(A,3(f10.2,1X))') 'SPACING ' , gridSpacing + WRITE(Un,'(A,i15)') 'POINT_DATA ', nPts + WRITE(Un,'(A)') 'VECTORS '//trim(dataDescr)//' float' + WRITE(Un,'(3(f10.2,1X))') gridVals + close(Un) + RETURN + + END SUBROUTINE WrVTK_SP_R4vectors3D + + SUBROUTINE WrVTK_SP_R8vectors3D( Un, dataDescr, dims, origin, gridSpacing, gridVals, ErrStat, ErrMsg ) + + INTEGER(IntKi) , INTENT(IN ) :: Un !< unit number of previously opened file (via call to WrVTK_SP_header) + CHARACTER(*) , INTENT(IN ) :: dataDescr !< Short label describing the vector data + INTEGER(IntKi) , INTENT(IN ) :: dims(3) !< dimension of the 3D grid (nX,nY,nZ) + REAL(ReKi) , INTENT(IN ) :: origin(3) !< the lower-left corner of the 3D grid (X0,Y0,Z0) + REAL(ReKi) , INTENT(IN ) :: gridSpacing(3) !< spacing between grid points in each of the 3 directions (dX,dY,dZ) + REAL(R8Ki) , INTENT(IN ) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ) + INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< error level/status of OpenFOutFile operation + CHARACTER(*) , INTENT( OUT) :: ErrMsg !< message when error occurs + + INTEGER(IntKi) :: nPts ! Total number of grid points + + if ( .not. (Un > 0) ) then + ErrStat = ErrID_Fatal + ErrMsg = 'WrVTK_SP_points: Invalid file unit, be sure to call WrVTK_SP_header prior to calling WrVTK_SP_points.' + return + end if + + ErrStat = ErrID_None + ErrMsg = '' + nPts = dims(1)*dims(2)*dims(3) + + ! Note: gridVals must be stored such that the left-most dimension is X and the right-most dimension is Z + WRITE(Un,'(A,3(i5,1X))') 'DIMENSIONS ', dims + WRITE(Un,'(A,3(f10.2,1X))') 'ORIGIN ' , origin + WRITE(Un,'(A,3(f10.2,1X))') 'SPACING ' , gridSpacing + WRITE(Un,'(A,i15)') 'POINT_DATA ', nPts + WRITE(Un,'(A)') 'VECTORS '//trim(dataDescr)//' float' + WRITE(Un,'(3(f10.2,1X))') gridVals + close(Un) + RETURN + + END SUBROUTINE WrVTK_SP_R8vectors3D - SUBROUTINE WrVTK_SP_vectors3D( Un, dataDescr, dims, origin, gridSpacing, gridVals, ErrStat, ErrMsg ) + SUBROUTINE WrVTK_SP_R16vectors3D( Un, dataDescr, dims, origin, gridSpacing, gridVals, ErrStat, ErrMsg ) INTEGER(IntKi) , INTENT(IN ) :: Un !< unit number of previously opened file (via call to WrVTK_SP_header) CHARACTER(*) , INTENT(IN ) :: dataDescr !< Short label describing the vector data INTEGER(IntKi) , INTENT(IN ) :: dims(3) !< dimension of the 3D grid (nX,nY,nZ) REAL(ReKi) , INTENT(IN ) :: origin(3) !< the lower-left corner of the 3D grid (X0,Y0,Z0) REAL(ReKi) , INTENT(IN ) :: gridSpacing(3) !< spacing between grid points in each of the 3 directions (dX,dY,dZ) - REAL(ReKi) , INTENT(IN ) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ) + REAL(QuKi) , INTENT(IN ) :: gridVals(:,:,:,:) !< 3D array of data, size (nX,nY,nZ) INTEGER(IntKi) , INTENT( OUT) :: ErrStat !< error level/status of OpenFOutFile operation CHARACTER(*) , INTENT( OUT) :: ErrMsg !< message when error occurs @@ -7918,6 +7995,6 @@ SUBROUTINE WrVTK_SP_vectors3D( Un, dataDescr, dims, origin, gridSpacing, gridVal close(Un) RETURN - END SUBROUTINE WrVTK_SP_vectors3D + END SUBROUTINE WrVTK_SP_R16vectors3D END MODULE NWTC_IO From 5e2ace226c84da816d8a14281831977e1ea1553c Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:21:19 -0600 Subject: [PATCH 015/386] Changed what tests are called (prototype driver at this point) --- modules-local/awae/src/AWAE_Driver.f90 | 9 ++++++--- modules-local/awae/src/AWAE_Driver_Subs.f90 | 14 +++++++++++++- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/modules-local/awae/src/AWAE_Driver.f90 b/modules-local/awae/src/AWAE_Driver.f90 index 241481d6ae..ba02644f78 100644 --- a/modules-local/awae/src/AWAE_Driver.f90 +++ b/modules-local/awae/src/AWAE_Driver.f90 @@ -37,7 +37,10 @@ program AWAE_Driver ! Initialize the NWTC Subroutine Library call NWTC_Init( EchoLibVer=.FALSE. ) - + !call AWAE_TEST_ExtractSlice(errStat, errMsg) + call AWAE_TEST_LowResGridCalcs(errStat, errMsg) +! call AWAE_Dvr_Tests(1, errStat, errMsg) + call CheckError( errStat, errMsg ) ! Initialize the Driver and the WD module !call AWAE_TEST_Init_BadData(errStat, ErrMsg) !call CheckError( ErrStat, ErrMsg ) @@ -45,8 +48,8 @@ program AWAE_Driver ! call AWAE_TEST_Init_GoodData(errStat, ErrMsg) ! call CheckError( ErrStat, ErrMsg ) !call AWAE_Dvr_Init( AWAE_InitInp, AWAE_InitOut, AWAE_u,AWAE_p, AWAE_xd, AWAE_y, errStat, errMsg) - call AWAE_TEST_CalcOutput(errStat, errMsg) - call CheckError( ErrStat, ErrMsg ) + ! call AWAE_TEST_CalcOutput(errStat, errMsg) + ! call CheckError( ErrStat, ErrMsg ) ! Run the time marching loop ! call AWAE_Dvr_Time_Marching() diff --git a/modules-local/awae/src/AWAE_Driver_Subs.f90 b/modules-local/awae/src/AWAE_Driver_Subs.f90 index c80fb81e38..24bcc165b8 100644 --- a/modules-local/awae/src/AWAE_Driver_Subs.f90 +++ b/modules-local/awae/src/AWAE_Driver_Subs.f90 @@ -401,6 +401,18 @@ module AWAE_Driver_Subs ! end subroutine Cleanup ! !end subroutine ReadWDInputFile + + + +subroutine AWAE_Dvr_Tests(pMod, errStat, errMsg) + integer(IntKi), intent(out) :: pMod !< Flag indicating parallel code mode [0=serial code, 1=parallel code] + integer(IntKi), intent(out) :: errStat !< Error status + character(*), intent(out) :: errMsg !< Error message + +end subroutine AWAE_Dvr_Tests + + + subroutine AWAE_Dvr_Init( AWAE_InitInp, AWAE_InitOut, AWAE_u,AWAE_p, AWAE_xd, AWAE_y, errStat, errMsg) @@ -416,7 +428,7 @@ subroutine AWAE_Dvr_Init( AWAE_InitInp, AWAE_InitOut, AWAE_u,AWAE_p, AWAE_xd, ! Local variables - TYPE(ProgDesc), PARAMETER :: version = ProgDesc( 'WakeDynamics', 'v0.01', '4-Nov-2016') ! The name, version, and date of AirfoilInfo. + TYPE(ProgDesc), PARAMETER :: version = ProgDesc( 'AWAE_Dvr', 'v0.02', '25-May-2017') ! The name, version, and date of AirfoilInfo. character(*), parameter :: RoutineName = 'AWAE_Dvr_Init' character(1024) :: OutFileRoot !< The rootname of the echo file, possibly opened in this routine integer(IntKi) :: errStat2 ! local status of error message From b0364d355df04586edcfd78ea27d41ad0963bdfa Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:22:07 -0600 Subject: [PATCH 016/386] changed all volume wind data and extracted 2D slices to SiKi since InflowWind expects SiKi data. --- glue-codes/fast-farm/src/FASTWrapper_Registry.txt | 2 +- modules-local/awae/src/AWAE_Registry.txt | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/glue-codes/fast-farm/src/FASTWrapper_Registry.txt b/glue-codes/fast-farm/src/FASTWrapper_Registry.txt index 61a09f8477..406b3f3c91 100644 --- a/glue-codes/fast-farm/src/FASTWrapper_Registry.txt +++ b/glue-codes/fast-farm/src/FASTWrapper_Registry.txt @@ -78,7 +78,7 @@ typedef ^ ParameterType ReKi p_ref_Turbine # Define inputs that are contained on the mesh here: typedef ^ InputType SiKi FromSC_Global {:} - - "Global (turbine-independent) commands from the super controller" "(various units)" typedef ^ InputType SiKi FromSC_Turbine {:} - - "Turbine-dependent commands from the super controller from the super controller" "(various units)" -typedef ^ InputType ReKi Vdist_High {:}{:}{:}{:}{:} - - "UVW components of disturbed wind [nx^high, ny^high, nz^high, n^high/low] (ambient + deficits) across the high-resolution domain around the turbine for each high-resolution time step within a low-resolution time step" "(m/s)" +typedef ^ InputType SiKi Vdist_High {:}{:}{:}{:}{:} - - "UVW components of disturbed wind [nx^high, ny^high, nz^high, n^high/low] (ambient + deficits) across the high-resolution domain around the turbine for each high-resolution time step within a low-resolution time step" "(m/s)" # ..... Outputs ................................................................................................................... # Define outputs that are contained on the mesh here: diff --git a/modules-local/awae/src/AWAE_Registry.txt b/modules-local/awae/src/AWAE_Registry.txt index 0d1cb32352..b071be9b56 100644 --- a/modules-local/awae/src/AWAE_Registry.txt +++ b/modules-local/awae/src/AWAE_Registry.txt @@ -19,7 +19,7 @@ param ^ - INTEGER YZSlice - 2 - "E param ^ - INTEGER XZSlice - 3 - "Extract an XZ slice of data from the 3D grid" - # ..... Wind 3D Data ....................................................................................................... -typedef AWAE/AWAE AWAE_HighWindGrid ReKi data {:}{:}{:}{:}{:} - - "UVW components of wind data across the high-res regularly-spaced grid" m/s +typedef AWAE/AWAE AWAE_HighWindGrid SiKi data {:}{:}{:}{:}{:} - - "UVW components of wind data across the high-res regularly-spaced grid" m/s # ..... InputFile Data ....................................................................................................... typedef AWAE/AWAE AWAE_InputFileType ReKi dr - - - "Radial increment of radial finite-difference grid [>0.0]" m typedef ^ AWAE_InputFileType DbKi dt - - - "Low-resolution (FAST.Farm driver/glue code) time step" s @@ -84,9 +84,9 @@ typedef ^ OtherStateType ReKi DummyOtherState - - - "Remove this va # ..... 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 Vamb_low {:}{:}{:}{:} - - "UVW components of ambient wind across the low-resolution domain throughout the farm" m/s -typedef ^ MiscVarType ReKi Vdist_low {:}{:}{:}{:} - - "UVW components of disturbed wind (ambient + deficits) across the low-resolution domain throughout the farm" m/s -typedef ^ MiscVarType ReKi Vamb_high {:}{:}{:}{:} - - "UVW components of ambient wind across each high-resolution domain around a turbine (one for each turbine) for each high-resolution time step within a low-resolution time step" m/s +typedef ^ MiscVarType SiKi Vamb_low {:}{:}{:}{:} - - "UVW components of ambient wind across the low-resolution domain throughout the farm" m/s +typedef ^ MiscVarType SiKi Vdist_low {:}{:}{:}{:} - - "UVW components of disturbed wind (ambient + deficits) across the low-resolution domain throughout the farm" m/s +typedef ^ MiscVarType SiKi Vamb_high {:}{:}{:}{:} - - "UVW components of ambient wind across each high-resolution domain around a turbine (one for each turbine) for each high-resolution time step within a low-resolution time step" m/s typedef ^ MiscVarType IntKi N_wind {:}{:} - - "Number of grid points contained in a given wake plane volume" - typedef ^ MiscVarType ReKi xhat_plane {:}{:} - - "Orientations of wake planes, normal to wake planes, associated with a given point in the wind spatial domain Orientations of wake planes, normal to wake planes, associated with a given point in the wind spatial domain" - #typedef ^ MiscVarType ReKi r_plane {:}{:} - - "" m @@ -103,9 +103,9 @@ typedef ^ MiscVarType ReKi Vr_wake {:} - - "" m/s typedef ^ MiscVarType IntKi nx_wind {:}{:}{:} - - "" - typedef ^ MiscVarType IntKi ny_wind {:}{:}{:} - - "" - typedef ^ MiscVarType IntKi nz_wind {:}{:}{:} - - "" - -typedef ^ MiscVarType ReKi outVizXYPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - -typedef ^ MiscVarType ReKi outVizYZPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - -typedef ^ MiscVarType ReKi outVizXZPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - +typedef ^ MiscVarType SiKi outVizXYPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - +typedef ^ MiscVarType SiKi outVizYZPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - +typedef ^ MiscVarType SiKi outVizXZPlane {:}{:}{:}{:} -- "An array holding the output data for a 2D visualization slice" - # ..... Parameters ................................................................................................................ From b468b7cee5ab435ec9ba86ab0c7ae1ec7d8f0228 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:22:58 -0600 Subject: [PATCH 017/386] Added prototype OpenMP calls and serial versions for FARM_CalcOutput and FARM_UpdateStates --- glue-codes/fast-farm/src/FAST_Farm.f90 | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm.f90 b/glue-codes/fast-farm/src/FAST_Farm.f90 index 2978e0cef1..c7575eace8 100644 --- a/glue-codes/fast-farm/src/FAST_Farm.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm.f90 @@ -125,11 +125,13 @@ PROGRAM FAST_Farm ! ! this takes data from n_t_global and gets values at n_t_global + 1 t = n_t_global*farm%p%DT - CALL FARM_UpdateStates(t, n_t_global, farm, ErrStat, ErrMsg) + !CALL FARM_UpdateStates(t, n_t_global, farm, ErrStat, ErrMsg) + CALL FARM_UpdateStatesSerial(t, n_t_global, farm, ErrStat, ErrMsg) CALL CheckError( ErrStat, ErrMsg ) t = (n_t_global+1)*farm%p%DT - CALL FARM_CalcOutput(t, farm, ErrStat, ErrMsg) + !CALL FARM_CalcOutput(t, farm, ErrStat, ErrMsg) + CALL FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) CALL CheckError( ErrStat, ErrMsg ) CALL SimStatus( PrevSimTime, PrevClockTime, t, farm%p%TMax ) From b239f7e32b5eede255c6e83bef31d3616897f390 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:23:24 -0600 Subject: [PATCH 018/386] Summary File Changes Added T in front of the turbine number for the Summary File tables Added N in front of the radial node number for the Summary File tables farm%WD(1)%p%C_HWkDfl_OY is now reported correctly in degrees farm%WD(1)%p%C_HWkDfl_xY is now reported correctly in degrees Added comment about why we cannot always use WrFileNR for our FAST.Farm output channels (ChanLenFF instead of ChanLen channel lengths!) --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 31 +++++++++++++---------- 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index b007a38321..912d620287 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9850,7 +9850,7 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) CHARACTER(30) :: Fmt CHARACTER(30) :: OutPFmt ! Format to print list of selected output channels to summary file CHARACTER(10) :: DOFEnabled ! String to say if a DOF is enabled or disabled - CHARACTER(2) :: outStr + CHARACTER(3) :: outStr CHARACTER(10) :: CalWakeDiamStr @@ -9893,12 +9893,12 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) do I = 1,farm%p%NumTurbines if ( I < 10 ) then - outStr = adjustr(trim(Num2LStr(I))) + outStr = 'T'//(trim(Num2LStr(I))) else - outStr = '- ' + outStr = ' - ' end if - WRITE(UnSum,'(6X,I4,16X,A4,9X,3F10.3,5X,F9.4,8X,I4,10X,A)') I, outStr, farm%p%WT_Position(1,I), farm%p%WT_Position(2,I),farm%p%WT_Position(3,I), farm%p%DT, farm%p%n_high_low, trim(farm%p%WT_FASTInFile(I)) + WRITE(UnSum,'(6X,I4,16X,A4,9X,3F10.3,5X,F10.5,8X,I4,10X,A)') I, outStr, farm%p%WT_Position(1,I), farm%p%WT_Position(2,I),farm%p%WT_Position(3,I), farm%p%DT/farm%FWrap%p%n_FAST_low, farm%FWrap%p%n_FAST_low, trim(farm%p%WT_FASTInFile(I)) end do @@ -9906,15 +9906,15 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) WRITE (UnSum,'(2X,A)') 'Radial Node Number Output Node Number Radius' WRITE (UnSum,'(2X,A)') ' (-) (-) (m) ' do I = 0, farm%WD(1)%p%NumRadii-1 - outStr = ' -' + outStr = ' - ' do J = 1, farm%p%NOutRadii if (farm%p%OutRadii(J) == I ) then - outStr = trim(Num2LStr(J)) + outStr = 'N'//trim(Num2LStr(J)) exit end if end do - WRITE(UnSum,'(8X,I4,17X,A2,9X,F10.3)') I, outStr, farm%WD(1)%p%r(I) + WRITE(UnSum,'(8X,I4,16X,A3,9X,F10.3)') I, outStr, farm%WD(1)%p%r(I) end do @@ -9922,9 +9922,9 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) WRITE (UnSum,'(2X,A)') 'Cut-off (corner) frequency of the low-pass time-filter for the wake advection, deflection, and meandering model (Hz): '//trim(Num2LStr(WD_InputFileData%f_c)) WRITE (UnSum,'(4X,A)') '( low-pass time-filter parameter (-): '//trim(Num2LStr(farm%WD(1)%p%filtParam))//' )' WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset at the rotor (m): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_O)) - WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset at the rotor scaled with yaw error (m/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_OY)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset at the rotor scaled with yaw error (m/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_OY/R2D)) WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset scaled with downstream distance (-): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_x)) - WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset scaled with downstream distance and yaw error (1/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_xY)) + WRITE (UnSum,'(2X,A)') 'Calibrated parameter in the correction for wake deflection defining the horizontal offset scaled with downstream distance and yaw error (1/deg): '//trim(Num2LStr(farm%WD(1)%p%C_HWkDfl_xY/R2D)) WRITE (UnSum,'(2X,A)') 'Calibrated parameter for near-wake correction (-): '//trim(Num2LStr(farm%WD(1)%p%C_NearWake)) WRITE (UnSum,'(2X,A)') 'Calibrated parameter for the influence of ambient turbulence in the eddy viscosity (-): '//trim(Num2LStr(farm%WD(1)%p%k_vAmb)) WRITE (UnSum,'(2X,A)') 'Calibrated parameter for the influence of the shear layer in the eddy viscosity (-): '//trim(Num2LStr(farm%WD(1)%p%k_vShr)) @@ -10040,7 +10040,7 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) CALL WrFileNR ( farm%p%UnOu, farm%p%OutParam(0)%Name ) DO I=1,farm%p%NumOuts - WRITE (farm%p%UnOu,'(A14)',ADVANCE='NO') farm%p%Delim//farm%p%OutParam(I)%Name + WRITE (farm%p%UnOu,'(A14)',ADVANCE='NO') farm%p%Delim//farm%p%OutParam(I)%Name ! Cannot use WrFileNR because it assumes a ChanLen length string and ours is ChanLenFF (14) ! CALL WrFileNR ( farm%p%UnOu, farm%p%Delim//farm%p%OutParam(I)%Name ) ENDDO ! I !============================================================ @@ -10246,15 +10246,20 @@ SUBROUTINE WriteFarmOutputToFile( t_global, farm, ErrStat, ErrMsg ) CALL WrFileNR( farm%p%UnOu, TmpStr ) ! Generate fast.farm output file + + DO I = 1,farm%p%NumOuts ! Loop through all selected output channels OutputAry(I) = farm%p%OutParam(I)%SignM * farm%m%AllOuts( farm%p%OutParam(I)%Indx ) - WRITE( TmpStr2, '('//Frmt//')' ) OutputAry(I) - CALL WrFileNR( farm%p%UnOu, TmpStr2 ) + ! WRITE( TmpStr2, '('//trim(Frmt)//')' ) OutputAry(I) + ! WRITE (farm%p%UnOu,'(A14)',ADVANCE='NO') TmpStr2 + + ! CALL WrFileNR( farm%p%UnOu, TmpStr2 ) ENDDO ! I - All selected output channels - + ! write the individual module output (convert to SiKi if necessary, so that we don't need to print so many digits in the exponent) + CALL WrNumAryFileNR ( farm%p%UnOu, REAL(OutputAry,SiKi), Frmt, ErrStat, ErrMsg ) !============================================================ ! DEBUG OUTPUTS HERE ! From 4b8de17d50f9498cee1624646378f2db6017a03d Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:23:42 -0600 Subject: [PATCH 019/386] Added prototype OpenMP and serial versions for FARM_CalcOutput and FARM_UpdateStates changed all volume wind data and extracted 2D slices to SiKi since InflowWind expects SiKi data. Moved the low-res wind file read to AWAE_UpdateStates, so added appropriate calls to that routine --- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 267 +++++++++++++++++--- 1 file changed, 238 insertions(+), 29 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index cb999d867b..2a9694ba1a 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -32,6 +32,7 @@ MODULE FAST_Farm_Subs USE FAST_Farm_IO USE FAST_Subs USE FASTWrapper + USE OMP_LIB IMPLICIT NONE @@ -45,7 +46,7 @@ MODULE FAST_Farm_Subs subroutine TrilinearInterpRegGrid(V, pt, dims, val) - real(ReKi), intent(in ) :: V(:,:,:,:) !< The volume data being sampled + real(SiKi), intent(in ) :: V(:,:,:,:) !< The volume data being sampled real(ReKi), intent(in ) :: pt(3) !< The point, in grid coordinates where we want to sample the data integer(IntKi), intent(in ) :: dims(3) !< The grid dimensions real(ReKi), intent( out) :: val(3) !< The interpolated value of V at location, pt @@ -86,14 +87,14 @@ subroutine TrilinearInterpRegGrid(V, pt, dims, val) N = N / real( size(N), ReKi ) ! normalize do i=1,3 - u(1) = V( i, x0, y0, z1 ) - u(2) = V( i, x0, y1, z1 ) - u(3) = V( i, x0, y1, z0 ) - u(4) = V( i, x0, y0, z0 ) - u(5) = V( i, x1, y0, z1 ) - u(6) = V( i, x1, y1, z1 ) - u(7) = V( i, x1, y1, z0 ) - u(8) = V( i, x1, y0, z0 ) + u(1) = real(V( i, x0, y0, z1 ), ReKi) + u(2) = real(V( i, x0, y1, z1 ), ReKi) + u(3) = real(V( i, x0, y1, z0 ), ReKi) + u(4) = real(V( i, x0, y0, z0 ), ReKi) + u(5) = real(V( i, x1, y0, z1 ), ReKi) + u(6) = real(V( i, x1, y1, z1 ), ReKi) + u(7) = real(V( i, x1, y1, z0 ), ReKi) + u(8) = real(V( i, x1, y0, z0 ), ReKi) val(i) = SUM ( N * u ) end do @@ -1385,11 +1386,13 @@ subroutine FARM_InitialCO(farm, ErrStat, ErrMsg) farm%AWAE%u%D_wake = 0.0_ReKi ! Wake diameters at wake planes for each turbine !-------------------- - ! 1b. CALL AWAE_CO + ! 1b. CALL AWAE_CO + call AWAE_UpdateStates( 0.0_DbKi, -1, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & + farm%AWAE%OtherSt, farm%AWAE%m, errStat, errMsg ) call AWAE_CalcOutput( 0.0_DbKi, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & farm%AWAE%OtherSt, farm%AWAE%y, farm%AWAE%m, ErrStat2, ErrMsg2 ) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - + if (ErrStat >= AbortErrLev) return !-------------------- ! 1c. transfer y_AWAE to u_F and u_WD @@ -1482,6 +1485,7 @@ subroutine FARM_InitialCO(farm, ErrStat, ErrMsg) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) end subroutine FARM_InitialCO + !---------------------------------------------------------------------------------------------------------------------------------- !> This routine updates states each time increment. !! The update states algorithm: \n @@ -1489,6 +1493,7 @@ end subroutine FARM_InitialCO !! 1. call WD_US !! 2. call SC_US !! 3. call F_Increment +!! 4. call AWAE_UpdateStates !! - \f$ n = n + 1 \f$ !! - \f$ t = t + \Delta t \f$ subroutine FARM_UpdateStates(t, n, farm, ErrStat, ErrMsg) @@ -1499,30 +1504,39 @@ subroutine FARM_UpdateStates(t, n, farm, ErrStat, ErrMsg) CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message INTEGER(IntKi) :: nt - INTEGER(IntKi) :: ErrStat2 ! Temporary Error status - CHARACTER(ErrMsgLen) :: ErrMsg2 ! Temporary Error message + INTEGER(IntKi) :: ErrStatWD, ErrStatF, ErrStatAWAE ! Temporary Error status + CHARACTER(ErrMsgLen) :: ErrMsgWD, ErrMsgF, ErrMsgAWAE ! Temporary Error message CHARACTER(*), PARAMETER :: RoutineName = 'FARM_UpdateStates' - - + INTEGER(IntKi) :: procs + REAL(DbKi) :: t1,t2,t3,t4,t5,t6,tm1,tm2 ErrStat = ErrID_None ErrMsg = "" + write(*,*) 'Beginning FARM_US' + procs = omp_get_num_procs() + call omp_set_num_threads(procs) + tm1 = omp_get_wtime() + !$OMP PARALLEL + !$OMP SECTIONS PRIVATE(nt) !....................................................................................... - ! update module states (steps 1. and 2. and 3. can be done in parallel) + ! update module states (steps 1. and 2. and 3. and 4. can be done in parallel) !....................................................................................... !-------------------- ! 1. CALL WD_US - + !$OMP SECTION + t1 = omp_get_wtime() DO nt = 1,farm%p%NumTurbines call WD_UpdateStates( t, n, farm%WD(nt)%u, farm%WD(nt)%p, farm%WD(nt)%x, farm%WD(nt)%xd, farm%WD(nt)%z, & - farm%WD(nt)%OtherSt, farm%WD(nt)%m, ErrStat2, ErrMsg2 ) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'T'//trim(num2lstr(nt))//':'//RoutineName) + farm%WD(nt)%OtherSt, farm%WD(nt)%m, ErrStatWD, ErrMsgWD ) + call SetErrStat(ErrStatWD, ErrMsgWD, ErrStatWD, ErrMsgWD, 'T'//trim(num2lstr(nt))//':FARM_UpdateStates') END DO - if (ErrStat >= AbortErrLev) return + t2 = omp_get_wtime() + write(*,*) ' Serial WD_UpdateStates took '//trim(num2lstr(t2-t1))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) + ! if (ErrStat >= AbortErrLev) return !-------------------- @@ -1531,19 +1545,115 @@ subroutine FARM_UpdateStates(t, n, farm, ErrStat, ErrMsg) !-------------------- ! 3. CALL F_Increment - + !$OMP SECTION + t3 = omp_get_wtime() DO nt = 1,farm%p%NumTurbines call FWrap_Increment( t, n, farm%FWrap(nt)%u, farm%FWrap(nt)%p, farm%FWrap(nt)%x, farm%FWrap(nt)%xd, farm%FWrap(nt)%z, & - farm%FWrap(nt)%OtherSt, farm%FWrap(nt)%y, farm%FWrap(nt)%m, ErrStat2, ErrMsg2 ) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'T'//trim(num2lstr(nt))//':'//RoutineName) - + farm%FWrap(nt)%OtherSt, farm%FWrap(nt)%y, farm%FWrap(nt)%m, ErrStatF, ErrMsgF ) + call SetErrStat(ErrStatF, ErrMsgF, ErrStatF, ErrMsgF, 'T'//trim(num2lstr(nt))//':FARM_UpdateStates') + t4 = omp_get_wtime() + write(*,*) ' Serial F_Increment took '//trim(num2lstr(t4-t3))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) END DO + + ! if (ErrStat >= AbortErrLev) return + + + !-------------------- + ! 4. CALL AWAE_UpdateStates + !$OMP SECTION + t5 = omp_get_wtime() + call AWAE_UpdateStates( t, n, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & + farm%AWAE%OtherSt, farm%AWAE%m, errStatAWAE, errMsgAWAE ) + t6 = omp_get_wtime() + write(*,*) ' Serial AWAE_UpdateStates took '//trim(num2lstr(t6-t5))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) + !$OMP END SECTIONS + ! if (ErrStat >= AbortErrLev) return + + !$OMP BARRIER + !$OMP END PARALLEL + + tm2 = omp_get_wtime() + write(*,*) 'Total Farm_US took '//trim(num2lstr(tm2-tm1))//' seconds.' + if (ErrStat >= AbortErrLev) return - end subroutine FARM_UpdateStates +subroutine FARM_UpdateStatesSerial(t, n, farm, ErrStat, ErrMsg) + REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds + INTEGER(IntKi), INTENT(IN ) :: n !< Current step of the simulation: t = n*Interval + type(All_FastFarm_Data), INTENT(INOUT) :: farm !< FAST.Farm data + INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status + CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message + + INTEGER(IntKi) :: nt + INTEGER(IntKi) :: ErrStatWD, ErrStatF, ErrStatAWAE ! Temporary Error status + CHARACTER(ErrMsgLen) :: ErrMsgWD, ErrMsgF, ErrMsgAWAE ! Temporary Error message + CHARACTER(*), PARAMETER :: RoutineName = 'FARM_UpdateStates' + REAL(DbKi) :: tm1,tm2 + + ErrStat = ErrID_None + ErrMsg = "" + + tm1 = omp_get_wtime() + + + !....................................................................................... + ! update module states (steps 1. and 2. and 3. and 4. can be done in parallel) + !....................................................................................... + + !-------------------- + ! 1. CALL WD_US + + + DO nt = 1,farm%p%NumTurbines + + call WD_UpdateStates( t, n, farm%WD(nt)%u, farm%WD(nt)%p, farm%WD(nt)%x, farm%WD(nt)%xd, farm%WD(nt)%z, & + farm%WD(nt)%OtherSt, farm%WD(nt)%m, ErrStatWD, ErrMsgWD ) + call SetErrStat(ErrStatWD, ErrMsgWD, ErrStatWD, ErrMsgWD, 'T'//trim(num2lstr(nt))//':FARM_UpdateStates') + + END DO + + if (ErrStatWD >= AbortErrLev) return + + + !-------------------- + ! 2. CALL SC_US + + + !-------------------- + ! 3. CALL F_Increment + + DO nt = 1,farm%p%NumTurbines + + call FWrap_Increment( t, n, farm%FWrap(nt)%u, farm%FWrap(nt)%p, farm%FWrap(nt)%x, farm%FWrap(nt)%xd, farm%FWrap(nt)%z, & + farm%FWrap(nt)%OtherSt, farm%FWrap(nt)%y, farm%FWrap(nt)%m, ErrStatF, ErrMsgF ) + call SetErrStat(ErrStatF, ErrMsgF, ErrStatF, ErrMsgF, 'T'//trim(num2lstr(nt))//':FARM_UpdateStates') + + + END DO + + if (ErrStatF >= AbortErrLev) return + + + !-------------------- + ! 4. CALL AWAE_UpdateStates + + + call AWAE_UpdateStates( t, n, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & + farm%AWAE%OtherSt, farm%AWAE%m, errStatAWAE, errMsgAWAE ) + + + if (errStatAWAE >= AbortErrLev) return + + + tm2 = omp_get_wtime() + write(*,*) 'Total Farm_US-serial took '//trim(num2lstr(tm2-tm1))//' seconds.' + + +end subroutine FARM_UpdateStatesSerial + subroutine Farm_WriteOutput(n, t, farm, ErrStat, ErrMsg) INTEGER(IntKi), INTENT(IN ) :: n !< Time step increment number REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds @@ -1766,14 +1876,113 @@ subroutine FARM_CalcOutput(t, farm, ErrStat, ErrMsg) INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message + INTEGER(IntKi) :: nt + INTEGER(IntKi) :: ErrStat2, ErrStatWD, ErrStatF, ErrStatAWAE ! Temporary Error status + CHARACTER(ErrMsgLen) :: ErrMsg2, ErrMsgWD, ErrMsgF, ErrMsgAWAE ! Temporary Error message + CHARACTER(*), PARAMETER :: RoutineName = 'FARM_CalcOutput' + INTEGER(IntKi) :: n ! time step increment number + INTEGER(IntKi) :: procs + REAL(DbKi) :: t1,t2,t3,t4,t5,t6,tm1,tm2,t1b,t2b + + ErrStat = ErrID_None + ErrMsg = "" + write(*,*) 'Beginning FARM_CO' + procs = omp_get_num_procs() + call omp_set_num_threads(procs) + tm1 = omp_get_wtime() + + !$OMP PARALLEL DEFAULT(SHARED) + !$OMP SECTIONS PRIVATE(nt) + + !....................................................................................... + ! calculate module outputs and perform some input-output solves (steps 1. and 2. and 3. can be done in parallel, + ! but be careful that step 3 doesn't modify the inputs to steps 1 or 2) + !....................................................................................... + + !-------------------- + ! 1. call WD_CO and transfer y_WD to u_AWAE + !$OMP SECTION + t1 = omp_get_wtime() + + DO nt = 1,farm%p%NumTurbines + + call WD_CalcOutput( t, farm%WD(nt)%u, farm%WD(nt)%p, farm%WD(nt)%x, farm%WD(nt)%xd, farm%WD(nt)%z, & + farm%WD(nt)%OtherSt, farm%WD(nt)%y, farm%WD(nt)%m, ErrStatWD, ErrMsgWD ) + call SetErrStat(ErrStatWD, ErrMsgWD, ErrStatWD, ErrMsgWD, 'T'//trim(num2lstr(nt))//':FARM_CalcOutput') + + END DO + ! if (ErrStat >= AbortErrLev) return + + call Transfer_WD_to_AWAE(farm) + t1b = omp_get_wtime() + write(*,*) ' Serial WD_CalcOutput and Transfer took '//trim(num2lstr(t1b-t1))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) + !-------------------- + ! 2. call SC_CO and transfer y_SC to u_F + + + !-------------------- + ! 3. Transfer y_F to u_SC and u_WD + !$OMP SECTION + t2 = omp_get_wtime() + call Transfer_FAST_to_WD(farm) + t2b = omp_get_wtime() + write(*,*) ' Serial Transfer_FAST_to_WD took '//trim(num2lstr(t2b-t2))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) + !$OMP END SECTIONS + + !$OMP BARRIER + !$OMP END PARALLEL + tm2 = omp_get_wtime() + write(*,*) ' Parallel part of Farm_CO took '//trim(num2lstr(tm2-tm1))//' seconds.' + !....................................................................................... + ! calculate AWAE outputs and perform rest of input-output solves + !....................................................................................... + + !-------------------- + ! 1. call AWAE_CO + + t3 = omp_get_wtime() + call AWAE_CalcOutput( t, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & + farm%AWAE%OtherSt, farm%AWAE%y, farm%AWAE%m, ErrStat2, ErrMsg2 ) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + t4 = omp_get_wtime() + !-------------------- + ! 2. Transfer y_AWAE to u_F and u_WD + call Transfer_AWAE_to_FAST(farm) + t5 = omp_get_wtime() + call Transfer_AWAE_to_WD(farm) + t6 = omp_get_wtime() + + write(*,*) ' Total AWAE_CalcOutput and related transfers took '//trim(num2lstr(t6-t3))//' seconds.' + + + !....................................................................................... + ! Write Output to File + !....................................................................................... + ! NOTE: Visualization data is output via the AWAE module + n = nint(t/farm%p%DT) + call Farm_WriteOutput(n, t, farm, ErrStat2, ErrMsg2) + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + + write(*,*) 'Total Farm_CO took '//trim(num2lstr(t6-tm1))//' seconds.' + +end subroutine FARM_CalcOutput +subroutine FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) + REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds + type(All_FastFarm_Data), INTENT(INOUT) :: farm !< FAST.Farm data + INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status + CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message + INTEGER(IntKi) :: nt INTEGER(IntKi) :: ErrStat2 ! Temporary Error status CHARACTER(ErrMsgLen) :: ErrMsg2 ! Temporary Error message CHARACTER(*), PARAMETER :: RoutineName = 'FARM_CalcOutput' INTEGER(IntKi) :: n ! time step increment number + REAL(DbKi) :: tm1 ErrStat = ErrID_None ErrMsg = "" + tm1 = omp_get_wtime() + !....................................................................................... ! calculate module outputs and perform some input-output solves (steps 1. and 2. and 3. can be done in parallel, ! but be careful that step 3 doesn't modify the inputs to steps 1 or 2) @@ -1786,8 +1995,8 @@ subroutine FARM_CalcOutput(t, farm, ErrStat, ErrMsg) call WD_CalcOutput( t, farm%WD(nt)%u, farm%WD(nt)%p, farm%WD(nt)%x, farm%WD(nt)%xd, farm%WD(nt)%z, & farm%WD(nt)%OtherSt, farm%WD(nt)%y, farm%WD(nt)%m, ErrStat2, ErrMsg2 ) - call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'T'//trim(num2lstr(nt))//':'//RoutineName) - + call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, 'T'//trim(num2lstr(nt))//':'//RoutineName) + END DO if (ErrStat >= AbortErrLev) return @@ -1826,9 +2035,9 @@ subroutine FARM_CalcOutput(t, farm, ErrStat, ErrMsg) call Farm_WriteOutput(n, t, farm, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + write(*,*) 'Total Farm_CO-serial took '//trim(num2lstr(omp_get_wtime()-tm1))//' seconds.' - -end subroutine FARM_CalcOutput +end subroutine FARM_CalcOutputSerial !---------------------------------------------------------------------------------------------------------------------------------- !> This routine ends the modules used in this simulation. It does not exit the program. !! - In parallel: From b51219b3c35a4713939decc9fe9e64a9918b068d Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:23:58 -0600 Subject: [PATCH 020/386] Added prototype OpenMP versions of ExtractSlice and LowResGridCalcOutput changed all volume wind data and extracted 2D slices to SiKi since InflowWind expects SiKi data. Moved the low-res wind file read to AWAE_UpdateStates, so added appropriate calls to that routine Added some more testing subroutines --- modules-local/awae/src/AWAE.f90 | 490 ++++++++++++++++++++++++++++++-- 1 file changed, 459 insertions(+), 31 deletions(-) diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index 927116797f..e357516232 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -27,7 +27,8 @@ module AWAE use NWTC_Library use AWAE_Types use AWAE_IO - + use OMP_LIB + implicit none private @@ -47,10 +48,70 @@ module AWAE public :: AWAE_TEST_Init_BadData public :: AWAE_TEST_Init_GoodData public :: AWAE_TEST_CalcOutput + public :: AWAE_TEST_ExtractSlice + public :: AWAE_TEST_LowResGridCalcs contains +subroutine ExtractSliceOMP( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) + + + + ! TODO: Rewrite this algorithm using shape functions + integer(IntKi), intent(in ) :: sliceType !< Type of slice: XYSlice, YZSlice, XZSlice + real(ReKi), intent(in ) :: s !< data value in meters of the interpolatan + real(ReKi), intent(in ) :: s0 !< origin value in meters of the interpolatan + integer(IntKi), intent(in ) :: szs + integer(IntKi), intent(in ) :: sz1 !< 1st dimension of slice + integer(IntKi), intent(in ) :: sz2 !< 2nd dimension of slice + real(ReKi), intent(in ) :: ds + real(SiKi), intent(in ) :: V(:,0:,0:,0:) + real(SiKi), intent(inout) :: slice(:,0:,0:) + + integer(IntKi) :: s_grid0,s_grid1,i,j,m, procs + real(SiKi) :: s_grid, sd + + + ! s is in meters but all the s_grid variables are in the grid units so that we can index into the grid arrays properly + ! NOTE: The grid coordinates run from 0 to sz-1 + + s_grid = real((s-s0)/ds,SiKi) + + ! Lower bounds of grid cell in interpolation direction + s_grid0 = floor(s_grid) + + ! Upper bounds of grid cell in interpolation direction + s_grid1 = s_grid0 + 1 + + ! fractional distance of requested slice from lower cell bounds in the range [0-1] + sd = (s_grid-real(s_grid0,SiKi)) + + if (s_grid0 == (szs-1)) s_grid1 = s_grid0 ! Handle case where s0 is the last index in the grid, in this case sd = 0.0, so the 2nd term in the interpolation will not contribute + + ! TODO: Add code to check bounds of requested slice location at INIT and fatal error if out of bounds + ! doing the bounds checks at INIT keeps this algorithm as fast as possible + procs = omp_get_num_procs() + call omp_set_num_threads(procs) + + !$OMP PARALLEL DO PRIVATE(i,j) SHARED(slice,sz1,sz2,sliceType,V,sd,s_grid0,s_grid1) DEFAULT(NONE) + do m = 0,(sz2)*(sz1)-1 + j = m/(sz1) + i = mod(m,sz1) + select case (sliceType) + case (XYSlice) + slice(:,i,j) = V(:,i,j,s_grid0)*(1.0_SiKi-sd) + V(:,i,j,s_grid1)*sd + case (YZSlice) + slice(:,i,j) = V(:,s_grid0,i,j)*(1.0_SiKi-sd) + V(:,s_grid1,i,j)*sd + case (XZSlice) + slice(:,i,j) = V(:,i,s_grid0,j)*(1.0_SiKi-sd) + V(:,i,s_grid1,j)*sd + end select + end do + !$OMP END PARALLEL DO + +end subroutine ExtractSliceOMP + subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) + ! TODO: Rewrite this algorithm using shape functions integer(IntKi), intent(in ) :: sliceType !< Type of slice: XYSlice, YZSlice, XZSlice real(ReKi), intent(in ) :: s !< data value in meters of the interpolatan @@ -59,17 +120,17 @@ subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) integer(IntKi), intent(in ) :: sz1 !< 1st dimension of slice integer(IntKi), intent(in ) :: sz2 !< 2nd dimension of slice real(ReKi), intent(in ) :: ds - real(ReKi), intent(in ) :: V(:,0:,0:,0:) - real(ReKi), intent(inout) :: slice(:,0:,0:) + real(SiKi), intent(in ) :: V(:,0:,0:,0:) + real(SiKi), intent(inout) :: slice(:,0:,0:) integer(IntKi) :: s_grid0,s_grid1,i,j - real(ReKi) :: s_grid, sd + real(SiKi) :: s_grid, sd ! s is in meters but all the s_grid variables are in the grid units so that we can index into the grid arrays properly ! NOTE: The grid coordinates run from 0 to sz-1 - s_grid = ((s-s0)/ds) + s_grid = real((s-s0)/ds,SiKi) ! Lower bounds of grid cell in interpolation direction s_grid0 = floor(s_grid) @@ -78,7 +139,7 @@ subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) s_grid1 = s_grid0 + 1 ! fractional distance of requested slice from lower cell bounds in the range [0-1] - sd = (s_grid-real(s_grid0,ReKi)) + sd = (s_grid-real(s_grid0,SiKi)) if (s_grid0 == (szs-1)) s_grid1 = s_grid0 ! Handle case where s0 is the last index in the grid, in this case sd = 0.0, so the 2nd term in the interpolation will not contribute @@ -88,11 +149,11 @@ subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) do i = 0,sz1-1 select case (sliceType) case (XYSlice) - slice(:,i,j) = V(:,i,j,s_grid0)*(1.0_ReKi-sd) + V(:,i,j,s_grid1)*sd + slice(:,i,j) = V(:,i,j,s_grid0)*(1.0_SiKi-sd) + V(:,i,j,s_grid1)*sd case (YZSlice) - slice(:,i,j) = V(:,s_grid0,i,j)*(1.0_ReKi-sd) + V(:,s_grid1,i,j)*sd + slice(:,i,j) = V(:,s_grid0,i,j)*(1.0_SiKi-sd) + V(:,s_grid1,i,j)*sd case (XZSlice) - slice(:,i,j) = V(:,i,s_grid0,j)*(1.0_ReKi-sd) + V(:,i,s_grid1,j)*sd + slice(:,i,j) = V(:,i,s_grid0,j)*(1.0_SiKi-sd) + V(:,i,s_grid1,j)*sd end select end do end do @@ -197,11 +258,11 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) errMsg = "" maxPln = min(n,p%NumPlanes-2) - ! read from file the ambient flow for the current time step - call ReadLowResWindFile(n, p, m%Vamb_Low, errStat, errMsg) - if ( errStat >= AbortErrLev ) then - return - end if + ! ! read from file the ambient flow for the current time step + ! call ReadLowResWindFile(n, p, m%Vamb_Low, errStat, errMsg) + ! if ( errStat >= AbortErrLev ) then + ! return + ! end if nXYZ_low = 0 @@ -312,7 +373,7 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) end do ! [I - XX']V = V - (V dot X)X Vr_wake_tmp = Vr_wake_tmp - dot_product(Vr_wake_tmp,xhatBar_plane)*xhatBar_plane - m%Vdist_low(:,nx_low,ny_low,nz_low) = m%Vdist_low(:,nx_low,ny_low,nz_low) + Vr_wake_tmp - xhatBar_plane*sqrt(Vx_wake_tmp) + m%Vdist_low(:,nx_low,ny_low,nz_low) = m%Vdist_low(:,nx_low,ny_low,nz_low) + real(Vr_wake_tmp - xhatBar_plane*sqrt(Vx_wake_tmp),SiKi) end if ! (n_wake > 0) end do ! do nx_low=0, p%nX_low-1 @@ -325,7 +386,7 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) Vsum_low = 0.0_ReKi do nw=1,m%N_wind(0,nt) - Vsum_low = Vsum_low + m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)) + Vsum_low = Vsum_low + real(m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)),ReKi) end do Vsum_low = Vsum_low / m%N_wind(0,nt) ! if N_wind gets large ( ~= 100,000 ) then this may not give enough precision in Vave_amb_low Vave_amb_low_norm = TwoNorm(Vsum_low) @@ -337,7 +398,7 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) y%Vx_wind_disk(nt) = dot_product( u%xhat_plane(:,0,nt), Vsum_low ) y%TI_amb(nt) = 0.0_ReKi do nw=1,m%N_wind(0,nt) - y%TI_amb(nt) = y%TI_amb(nt) + TwoNorm( m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)) - Vsum_low )**2 + y%TI_amb(nt) = y%TI_amb(nt) + TwoNorm( real(m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)),ReKi) - Vsum_low )**2 end do y%TI_amb(nt) = sqrt(y%TI_amb(nt)/(3.0*m%N_wind(0,nt)))/Vave_amb_low_norm else @@ -381,7 +442,227 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) end subroutine LowResGridCalcOutput +!---------------------------------------------------------------------------------------------------------------------------------- +!> This subroutine +!! +subroutine LowResGridCalcOutputOMP(n, u, p, y, Vdist_low, Vamb_low, m, errStat, errMsg) + integer(IntKi), intent(in ) :: n !< Current simulation time increment (zero-based) + type(AWAE_InputType), intent(in ) :: u !< Inputs at Time t + type(AWAE_ParameterType), intent(in ) :: p !< Parameters + type(AWAE_OutputType), intent(inout) :: y !< Outputs computed at t (Input only so that mesh con- + !! nectivity information does not have to be recalculated) + real(SiKi), intent(inout) :: Vdist_low(:,0:,0:,0:) + real(SiKi), intent(inout) :: Vamb_low(:,0:,0:,0:) + type(AWAE_MiscVarType), intent(inout) :: m !< Misc/optimization variables + integer(IntKi), intent( out) :: errStat !< Error status of the operation + character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None + + integer(IntKi) :: i,nx, ny, nz, nt, np, nw, nx_low, ny_low, nz_low !< loop counters + integer(IntKi) :: nXYZ_low, n_wake !< accumulating counters + real(ReKi) :: xhatBar_plane(3) !< + real(ReKi) :: x_end_plane + real(ReKi) :: x_start_plane + real(ReKi) :: r_vec_plane(3) + real(ReKi) :: tmp_xhatBar_plane + real(ReKi) :: r_tmp_plane + real(ReKi) :: Vx_wake_tmp + real(ReKi) :: Vr_wake_tmp(3) + real(ReKi) :: Vr_term(3) + real(ReKi) :: Vx_term + real(ReKi) :: Vsum_low(3) + real(ReKi) :: p_tmp_plane(3) + real(ReKi) :: tmp_vec(3) + real(ReKi) :: Vave_amb_low_norm + real(ReKi) :: delta, deltad + integer(IntKi) :: ILo, j + integer(IntKi) :: maxPln, procs + integer(IntKi) :: N_wind_tmp + + character(*), parameter :: RoutineName = 'LowResGridCalcOutput' + errStat = ErrID_None + errMsg = "" + maxPln = min(n,p%NumPlanes-2) + nXYZ_low = 0 + m%N_wind(:,:) = 0 + + ! Loop over the entire grid of low resolution ambient wind data to compute: + ! 1) the disturbed flow at each point and 2) the averaged disturbed velocity of each wake plane + procs = omp_get_num_procs() + call omp_set_num_threads(procs) + + !$OMP PARALLEL DO PRIVATE(j, nx_low,ny_low,nz_low, nXYZ_low, n_wake, xhatBar_plane, x_end_plane, nt,np,ILo,x_start_plane,delta,deltad, p_tmp_plane,tmp_vec,r_vec_plane,r_tmp_plane,tmp_xhatBar_plane,Vx_wake_tmp,Vr_wake_tmp,nw,Vr_term,Vx_term) SHARED(Vdist_low,Vamb_low,m,u,p,maxPln,errStat, errMsg) DEFAULT(NONE) + do i = 0, p%nX_low*p%nY_low*p%nZ_low - 1 + + nx_low = mod(i,p%nX_low) + ny_low = mod(i/(p%nX_low),p%nY_low) + nz_low = i / (p%nX_low*p%nY_low) + + ! set the disturbed flow equal to the ambient flow for this time step + Vdist_low(:,nx_low,ny_low,nz_low) = Vamb_low(:,nx_low,ny_low,nz_low) + + nXYZ_low = i + 1 + n_wake = 0 + xhatBar_plane = 0.0_ReKi + + do nt = 1,p%NumTurbines + + x_end_plane = dot_product(u%xhat_plane(:,0,nt), (p%Grid_Low(:,nXYZ_low) - u%p_plane(:,0,nt)) ) + + do np = 0, maxPln + + ! Reset interpolation counter + ILo = 0 + + ! Construct the endcaps of the current wake plane volume + x_start_plane = x_end_plane + x_end_plane = dot_product(u%xhat_plane(:,np+1,nt), (p%Grid_Low(:,nXYZ_low) - u%p_plane(:,np+1,nt)) ) + + ! test if the point is within the endcaps of the wake volume + if ( ( x_start_plane >= 0.0_ReKi ) .and. ( x_end_plane < 0.0_ReKi ) ) then + + delta = x_start_plane / ( x_start_plane - x_end_plane ) + deltad = (1.0_ReKi - delta) + if ( m%parallelFlag(np,nt) ) then + p_tmp_plane = delta*u%p_plane(:,np+1,nt) + deltad*u%p_plane(:,np,nt) + else + tmp_vec = delta*m%rhat_e(:,np,nt) + deltad*m%rhat_s(:,np,nt) + p_tmp_plane = delta*m%pvec_ce(:,np,nt) + deltad*m%pvec_cs(:,np,nt) + ( delta*m%r_e(np,nt) + deltad*m%r_s(np,nt) )* tmp_vec / TwoNorm(tmp_vec) + end if + + + + r_vec_plane = p%Grid_Low(:,nXYZ_low) - p_tmp_plane + r_tmp_plane = TwoNorm( r_vec_plane ) + + ! test if the point is within radial finite-difference grid + if ( r_tmp_plane <= p%r(p%numRadii-1) ) then + + n_wake = n_wake + 1 + ! m%r_plane(n_wake) = r_tmp_plane ! Why do we need this?? GJH + + if ( EqualRealNos(r_tmp_plane, 0.0_ReKi) ) then + m%rhat_plane(:,n_wake) = 0.0_ReKi + else + m%rhat_plane(:,n_wake) = ( r_vec_plane ) / r_tmp_plane + end if + + + ! given r_tmp_plane and Vx_wake at p%dr increments, find value of m%Vx_wake(@r_tmp_plane) using interpolation + m%Vx_wake(n_wake) = delta*InterpBin( r_tmp_plane, p%r, u%Vx_wake(:,np+1,nt), ILo, p%NumRadii ) + deltad*InterpBin( r_tmp_plane, p%r, u%Vx_wake(:,np,nt), ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + m%Vr_wake(n_wake) = delta*InterpBin( r_tmp_plane, p%r, u%Vr_wake(:,np+1,nt), ILo, p%NumRadii ) + deltad*InterpBin( r_tmp_plane, p%r, u%Vr_wake(:,np,nt), ILo, p%NumRadii ) !( XVal, XAry, YAry, ILo, AryLen ) + + + m%xhat_plane(:,n_wake) = delta*u%xhat_plane(:,np+1,nt) + deltad*u%xhat_plane(:,np,nt) + m%xhat_plane(:,n_wake) = m%xhat_plane(:,n_wake) / TwoNorm(m%xhat_plane(:,n_wake)) + xhatBar_plane = xhatBar_plane + abs(m%Vx_wake(n_wake))*m%xhat_plane(:,n_wake) + + end if ! if the point is within radial finite-difference grid + + ! test if the point is within the radius of the wake volume cylinder + if ( r_tmp_plane <= (delta*u%D_wake(np+1,nt) + deltad*u%D_wake(np,nt) )) then + m%N_wind(np,nt) = m%N_wind(np,nt) + 1 + + ! TODO: Verify that m%N_wind(np,nt) <= MAX_1ST_DIM_SIZE of nx_wind + if ( m%N_wind(np,nt) > p%n_wind_max ) then + call SetErrStat( ErrID_Fatal, 'The wake plane volume (plane='//trim(num2lstr(np))//',turbine='//trim(num2lstr(nt))//') contains more points than the maximum predicted points: 30*pi*DT(2*r*[Nr-1])**2/(dx*dy*dz)', errStat, errMsg, 'LowResGridCalcOutput' ) + ! return + end if + + m%nx_wind(m%N_wind(np,nt),np,nt) = nx_low + m%ny_wind(m%N_wind(np,nt),np,nt) = ny_low + m%nz_wind(m%N_wind(np,nt),np,nt) = nz_low + + end if + exit + end if ! if the point is within the endcaps of the wake volume + end do ! do np = 0, p%NumPlanes-2 + end do ! do nt = 1,p%NumTurbines + if (n_wake > 0) then + tmp_xhatBar_plane = TwoNorm(xhatBar_plane) + if ( EqualRealNos(tmp_xhatBar_plane, 0.0_ReKi) ) then + xhatBar_plane = 0.0_ReKi + else + xhatBar_plane = xhatBar_plane / tmp_xhatBar_plane + end if + + Vx_wake_tmp = 0.0_ReKi + Vr_wake_tmp = 0.0_ReKi + do nw = 1,n_wake + Vr_term = m%Vx_wake(nw)*m%xhat_plane(:,nw) + m%Vr_wake(nw)*m%rhat_plane(:,nw) + Vx_term = dot_product( xhatBar_plane, Vr_term ) + Vx_wake_tmp = Vx_wake_tmp + Vx_term*Vx_term + Vr_wake_tmp = Vr_wake_tmp + Vr_term + end do + ! [I - XX']V = V - (V dot X)X + Vr_wake_tmp = Vr_wake_tmp - dot_product(Vr_wake_tmp,xhatBar_plane)*xhatBar_plane + m%Vdist_low(:,nx_low,ny_low,nz_low) = m%Vdist_low(:,nx_low,ny_low,nz_low) + real(Vr_wake_tmp - xhatBar_plane*sqrt(Vx_wake_tmp),SiKi) + end if ! (n_wake > 0) + + end do ! do i : loop over all grid points + !$OMP END PARALLEL DO + + do nt = 1,p%NumTurbines + if ( m%N_wind(0,nt) > 0 ) then + ! TODO: This is modified in Rev 7 and the current code is for Rev 6. 13/Feb/2017 + Vsum_low = 0.0_ReKi + + do nw=1,m%N_wind(0,nt) + Vsum_low = Vsum_low + real(m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)),ReKi) + end do + Vsum_low = Vsum_low / m%N_wind(0,nt) ! if N_wind gets large ( ~= 100,000 ) then this may not give enough precision in Vave_amb_low + Vave_amb_low_norm = TwoNorm(Vsum_low) + if ( EqualRealNos(Vave_amb_low_norm,0.0_ReKi) ) then + call SetErrStat( ErrID_Fatal, 'The magnitude of the spatial-averaged ambient wind speed in the low-resolution domain associated with the wake volume at the rotor disk for turbine '//trim(num2lstr(nt))//' is zero.', errStat, errMsg, RoutineName ) + return + end if + + y%Vx_wind_disk(nt) = dot_product( u%xhat_plane(:,0,nt), Vsum_low ) + y%TI_amb(nt) = 0.0_ReKi + do nw=1,m%N_wind(0,nt) + y%TI_amb(nt) = y%TI_amb(nt) + TwoNorm( real(m%Vamb_Low(:, m%nx_wind(nw,0,nt), m%ny_wind(nw,0,nt), m%nz_wind(nw,0,nt)),ReKi) - Vsum_low )**2 + end do + y%TI_amb(nt) = sqrt(y%TI_amb(nt)/(3.0*m%N_wind(0,nt)))/Vave_amb_low_norm + else + y%Vx_wind_disk(nt) = 0.0_ReKi + y%TI_amb(nt) = 0.0_ReKi + end if + + + do np = 0, maxPln !p%NumPlanes-2 + if ( (u%D_wake(np,nt) > 0.0_ReKi) .and. (m%N_wind(np,nt) < p%n_wind_min) ) then + call SetErrStat( ErrID_Fatal, 'The number of points in the wake volume #'//trim(num2lstr(np))//' for turbine '//trim(num2lstr(nt))//' is '//trim(num2lstr(m%N_wind(np,nt)))//', which is less than the minimum threshold, '//trim(num2lstr(p%n_wind_min))//'.', errStat, errMsg, RoutineName ) + return + else if ( m%N_wind(np,nt) > 0 ) then + Vsum_low = 0.0_ReKi + do nw=1,m%N_wind(np,nt) + Vsum_low = Vsum_low + m%Vdist_low( :, m%nx_wind(nw,np,nt),m%ny_wind(nw,np,nt),m%nz_wind(nw,np,nt) ) + end do + y%V_plane(:,np,nt) = Vsum_low + else + y%V_plane(:,np,nt) = 0.0_ReKi + end if + + end do + + if ( m%N_wind(maxPln ,nt) > 0 ) then + y%V_plane(:,maxPln+1,nt) = y%V_plane(:,maxPln,nt) / m%N_wind(maxPln,nt) + else + y%V_plane(:,maxPln+1,nt) = 0.0_ReKi + end if + do np = maxPln, 1, -1 + N_wind_tmp = m%N_wind(np,nt) + m%N_wind(np-1,nt) + if ( N_wind_tmp > 0 ) then + y%V_plane(:,np ,nt) = ( y%V_plane(:,np ,nt) + y%V_plane(:,np-1,nt) ) / N_wind_tmp + end if + end do + if ( m%N_wind(0 ,nt) > 0 ) then + y%V_plane(:,0 ,nt) = y%V_plane(:,0 ,nt) / m%N_wind(0 ,nt) + end if + + end do + +end subroutine LowResGridCalcOutputOMP !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine !! @@ -533,7 +814,7 @@ subroutine HighResGridCalcOutput(n, u, p, y, m, errStat, errMsg) ! [I - XX']V = V - (V dot X)X Vr_wake_tmp = Vr_wake_tmp - dot_product(Vr_wake_tmp,xhatBar_plane)*xhatBar_plane do n_hl=0, n_high_low-1 - y%Vdist_high(nt)%data(:,nx_high,ny_high,nz_high,n_hl) = y%Vdist_high(nt)%data(:,nx_high,ny_high,nz_high,n_hl) + Vr_wake_tmp - xhatBar_plane*sqrt(Vx_wake_tmp) + y%Vdist_high(nt)%data(:,nx_high,ny_high,nz_high,n_hl) = y%Vdist_high(nt)%data(:,nx_high,ny_high,nz_high,n_hl) + real(Vr_wake_tmp - xhatBar_plane*sqrt(Vx_wake_tmp),SiKi) end do end if ! (n_wake > 0) @@ -749,7 +1030,7 @@ subroutine AWAE_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO do i = 1, p%NumTurbines allocate ( y%Vdist_High(i)%data(3,0:p%nX_high-1,0:p%nY_high-1,0:p%nZ_high-1,0:p%n_high_low-1), STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for y%Vdist_High%data.', errStat, errMsg, RoutineName ) - y%Vdist_High(i)%data = 0.0_Reki + y%Vdist_High(i)%data = 0.0_Siki end do allocate ( y%Vx_wind_disk (1:p%NumTurbines), STAT=ErrStat2 ) @@ -842,9 +1123,9 @@ subroutine AWAE_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO if (errStat /= ErrID_None) return ! TODO: This step isn't really needed - m%Vamb_low = 0.0_ReKi - m%Vdist_low = 0.0_ReKi - m%Vamb_High = 0.0_ReKi + m%Vamb_low = 0.0_SiKi + m%Vdist_low = 0.0_SiKi + m%Vamb_High = 0.0_SiKi m%N_wind = 0 m%xhat_plane = 0.0_ReKi m%rhat_plane = 0.0_ReKi @@ -951,10 +1232,24 @@ subroutine AWAE_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errM integer(intKi) :: errStat2 ! temporary Error status character(ErrMsgLen) :: errMsg2 ! temporary Error message character(*), parameter :: RoutineName = 'AWAE_UpdateStates' + real(DbKi) :: t1, tread errStat = ErrID_None errMsg = "" - + + ! Read the ambient wind data that is need for t+dt + + !t1 = omp_get_wtime() + ! read from file the ambient flow for the n+1 time step + call ReadLowResWindFile(n+1, p, m%Vamb_Low, errStat, errMsg) + if ( errStat >= AbortErrLev ) then + return + end if + ! tread = ( omp_get_wtime() - t1 ) + ! write(*,*) 'Time spent reading data: ',tread + + + end subroutine AWAE_UpdateStates @@ -1002,11 +1297,13 @@ subroutine AWAE_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, errStat, errMsg return end if call LowResGridCalcOutput(n, u, p, y, m, errStat2, errMsg2) + !call LowResGridCalcOutputOMP(n, u, p, y, m%Vdist_low, m%Vamb_low, m, errStat2, errMsg2) + call SetErrStat ( errStat2, errMsg2, errStat, errMsg, RoutineName ) if (errStat2 >= AbortErrLev) then return end if - + ! starting index for the high-res files n_high = n*p%n_high_low call HighResGridCalcOutput(n_high, u, p, y, m, errStat2, errMsg2) @@ -1176,13 +1473,25 @@ subroutine AWAE_TEST_SetGoodInitInpData(interval, InitInp) real(DbKi) , intent(out) :: interval type(AWAE_InitInputType), intent(out) :: InitInp !< Input data for initialization routine - ! Based on NREL 5MW - interval = 1.0_DbKi - InitInp%InputFileData%WindFilePath = 'C:\Dev\NWTC Github\FAST.Farm\data' - InitInp%InputFileData%NumTurbines = 1 - InitInp%InputFileData%NumPlanes = 500 - InitInp%InputFileData%NumRadii = 40 - InitInp%InputFileData%dr = 5.0_ReKi + ! Based on NREL 5MW + interval = 2.0_DbKi + InitInp%InputFileData%WindFilePath = 'C:\Dev\OpenFAST-farm\OpenFAST-test\fast-farm\steady' + InitInp%InputFileData%WindFilePath = 'Y:\Wind\Public\Projects\Projects F\FAST.Farm\AmbWind\04' + InitInp%InputFileData%NumTurbines = 1 + InitInp%InputFileData%NumPlanes = 140 + InitInp%InputFileData%NumRadii = 40 + InitInp%InputFileData%dr = 5.0_ReKi + InitInp%n_high_low = 6 + InitInp%InputFileData%dt = 2.0 + InitInp%NumDT = 1 + InitInp%InputFileData%NOutDisWindXY = 0 + InitInp%InputFileData%NOutDisWindYZ = 0 + InitInp%InputFileData%NOutDisWindXZ = 0 + InitInp%InputFileData%WrDisWind = .false. + InitInp%InputFileData%WrDisDT = 0.0 + InitInp%InputFileData%OutDisWindY = 0 + InitInp%InputFileData%OutDisWindZ = 0 + InitInp%InputFileData%OutDisWindX = 0 end subroutine AWAE_TEST_SetGoodInitInpData @@ -1220,6 +1529,125 @@ subroutine AWAE_TEST_Init_GoodData(errStat, errMsg) end subroutine AWAE_TEST_Init_GoodData +subroutine AWAE_TEST_LowResGridCalcs(errStat, errMsg) + + integer(IntKi), intent(out) :: errStat !< Error status + character(*), intent(out) :: errMsg !< Error message + + real(DbKi) :: t1, t2, t3 + type(AWAE_InitInputType) :: InitInp !< Input data for initialization routine + type(AWAE_InputType) :: u !< An initial guess for the input; input mesh must be defined + type(AWAE_ParameterType) :: p !< Parameters + type(AWAE_ContinuousStateType) :: x !< Initial continuous states + type(AWAE_DiscreteStateType) :: xd !< Initial discrete states + type(AWAE_ConstraintStateType) :: z !< Initial guess of the constraint states + type(AWAE_OtherStateType) :: OtherState !< Initial other states + type(AWAE_OutputType) :: y !< Initial system outputs (outputs are not calculated; + !! only the output mesh is initialized) + type(AWAE_MiscVarType) :: m !< Initial misc/optimization variables + real(DbKi) :: interval !< Coupling interval in seconds: the rate that + real(DbKi) :: t + type(AWAE_InitOutputType) :: initOut !< Input data for initialization routine + integer(IntKi) :: n,ix,iy,iz + real(SiKi),allocatable :: Vamb_lowOMP(:,:,:,:) + real(SiKi),allocatable :: Vdist_lowOMP(:,:,:,:) + ! Set up the initialization inputs + call AWAE_TEST_SetGoodInitInpData(interval, InitInp) + + call AWAE_Init( InitInp, u, p, x, xd, z, OtherState, y, m, interval, InitOut, errStat, errMsg ) + + + allocate ( Vamb_lowOMP ( 3, 0:p%nX_low-1 , 0:p%nY_low-1 , 0:p%nZ_low-1 ) , STAT=errStat ) + if (errStat /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%Vamb_low.', errStat, errMsg, 'AWAE_TEST_LowResGridCalcs' ) + allocate ( Vdist_lowOMP ( 3, 0:p%nX_low-1 , 0:p%nY_low-1 , 0:p%nZ_low-1 ) , STAT=errStat ) + if (errStat /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%Vdist_low.', errStat, errMsg, 'AWAE_TEST_LowResGridCalcs' ) + if (errStat > ErrID_None) return + + n = 0 ! starting time + t = n*p%dt + ! Update states is really reading the wind data for n+1 time step + call AWAE_UpdateStates( t, n, u, p, x, xd, z, OtherState, m, errStat, errMsg ) + + n=n+1 ! increment time + + t1 = omp_get_wtime() + call LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) + if (errStat >= AbortErrLev) then + return + end if + t2 = omp_get_wtime() + call LowResGridCalcOutputOMP(n, u, p, y, Vdist_lowOMP, m%Vamb_low, m, errStat, errMsg) + if (errStat >= AbortErrLev) then + return + end if + t3 = omp_get_wtime() + write(*,*) 'Serial Low Res Grid took '//trim(num2lstr(t2-t1))//' seconds.' + write(*,*) 'Parallel Low Res Grid took '//trim(num2lstr(t3-t2))//' seconds.' + + do iz = 0,p%nZ_low-1 + do iy = 0,p%nY_low-1 + do ix = 0,p%nX_low-1 + if ( .not. (EqualRealNos(Vdist_lowOMP(1,ix,iy,iz),m%Vdist_low(1,ix,iy,iz)) .and. EqualRealNos(Vdist_lowOMP(2,ix,iy,iz),m%Vdist_low(2,ix,iy,iz)) .and. EqualRealNos(Vdist_lowOMP(3,ix,iy,iz),m%Vdist_low(3,ix,iy,iz)) ) ) then + WRITE(*,*) 'Values do not match between serial and parallel results' + end if + end do + end do + end do + +end subroutine AWAE_TEST_LowResGridCalcs + +subroutine AWAE_TEST_ExtractSlice(errStat, errMsg) + + integer(IntKi), intent(out) :: errStat !< Error status + character(*), intent(out) :: errMsg !< Error message + + integer(IntKi) :: nx, ny, nz, ix, iy, iz + real(SiKi), allocatable :: V(:,:,:,:),sliceXY(:,:,:),sliceXY_OMP(:,:,:),sliceYZ(:,:,:),sliceXZ(:,:,:) + real(ReKi) :: dx,dy,dz,x0,y0,z0,x,y,z + real(DbKi) :: t1, t2, t3 + + ! Create a volume of random number data + nx = 500 + ny = 500 + nz = 100 + dx = 10.0 + dy = 10.0 + dz = 10.0 + x0 = 500.0 + y0 = 300.0 + z0 = 10.0 + !allocate( p%r(0:p%NumRadii-1),stat=errStat2) + allocate(V(3,0:nx-1,0:ny-1,0:nz-1)) + allocate(sliceXY(3,0:nx-1,0:ny-1)) + allocate(sliceXY_OMP(3,0:nx-1,0:ny-1)) + do iz = 0,nz-1 + do iy = 0,ny-1 + do ix = 0,nx-1 + CALL RANDOM_NUMBER(V(1,ix,iy,iz) ) + CALL RANDOM_NUMBER(V(2,ix,iy,iz) ) + CALL RANDOM_NUMBER(V(3,ix,iy,iz) ) + end do + end do + end do + CALL RANDOM_NUMBER(z) + z = z*nz*dz + z0 + t1 = omp_get_wtime() + call ExtractSlice( XYSlice, z, z0, nz, nx, ny, dz, V, sliceXY) + t2 = omp_get_wtime() + call ExtractSliceOMP( XYSlice, z, z0, nz, nx, ny, dz, V, sliceXY_OMP) + t3 = omp_get_wtime() + write(*,*) 'Serial Extract slice took '//trim(num2lstr(t2-t1))//' seconds.' + write(*,*) 'Parallel Extract slice took '//trim(num2lstr(t3-t2))//' seconds.' + do iy = 0,ny-1 + do ix = 0,nx-1 + if ( .not. (EqualRealNos(sliceXY(1,ix,iy),sliceXY_OMP(1,ix,iy)) .and. EqualRealNos(sliceXY(2,ix,iy),sliceXY_OMP(2,ix,iy)) .and. EqualRealNos(sliceXY(3,ix,iy),sliceXY_OMP(3,ix,iy)) ) ) then + WRITE(*,*) 'Values do not match between serial and parallel results' + end if + end do + end do +end subroutine AWAE_TEST_ExtractSlice + + subroutine AWAE_TEST_CalcOutput(errStat, errMsg) integer(IntKi), intent(out) :: errStat !< Error status From ad0bc33c2c5cab662e538e0a5adf0218f911092f Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:24:26 -0600 Subject: [PATCH 021/386] Added HiResWindCheck() subroutines - grid must have two points in each direction - All turbines and all time steps must have the same grid dimensions due to array allocation assumptions - spacing must be consistent for a given turbine across all time steps - verify origin of any given turbine is not changing with time step. changed all volume wind data and extracted 2D slices to SiKi since InflowWind expects SiKi data. Reworked AWAE_IO_InitGridInfo for more error handling/ data checking, per plan - check added that low res grids must have two points in each direction - call HiResWindCheck() for high res grid checks --- modules-local/awae/src/AWAE_IO.f90 | 150 +++++++++++++++++++++++++---- 1 file changed, 132 insertions(+), 18 deletions(-) diff --git a/modules-local/awae/src/AWAE_IO.f90 b/modules-local/awae/src/AWAE_IO.f90 index 2de4f20186..c2313e22a1 100644 --- a/modules-local/awae/src/AWAE_IO.f90 +++ b/modules-local/awae/src/AWAE_IO.f90 @@ -37,6 +37,50 @@ MODULE AWAE_IO contains +subroutine HiResWindCheck(n, nt, nX, nY, nZ, dX, dY, dZ, X0, Y0, Z0, dims, gridSpacing, origin, callingRoutine, errMsg, errStat) + integer(IntKi), intent(in ) :: n !< high-resolution time step number (0-based) + integer(IntKi), intent(in ) :: nt !< turbine number + integer(IntKi), intent(in ) :: nX !< number of grid points in the X-direction for turbine 1 at high-res time step 0 + integer(IntKi), intent(in ) :: nY !< number of grid points in the Y-direction for turbine 1 at high-res time step 0 + integer(IntKi), intent(in ) :: nZ !< number of grid points in the Z-direction for turbine 1 at high-res time step 0 + real(ReKi), intent(in ) :: dX !< space between grid points in the X-direction for turbine 1 at high-res time step 0 + real(ReKi), intent(in ) :: dY !< space between grid points in the Y-direction for turbine 1 at high-res time step 0 + real(ReKi), intent(in ) :: dZ !< space between grid points in the Z-direction for turbine 1 at high-res time step 0 + real(ReKi), intent(in ) :: X0 !< starting X-location of the grid for turbine 1 at high-res time step 0 (m) + real(ReKi), intent(in ) :: Y0 !< starting Y-location of the grid for turbine 1 at high-res time step 0 (m) + real(ReKi), intent(in ) :: Z0 !< starting Z-location of the grid for turbine 1 at high-res time step 0 (m) + integer(IntKi), intent(in ) :: dims(3) !< dimensions of the grid for turbine nt at high-res time step n (m) + real(ReKi), intent(in ) :: gridSpacing(3) !< spacing between grid points for turbine nt at high-res time step n (m) + real(ReKi), intent(in ) :: origin(3) !< starting coordinates of the grid for turbine nt at high-res time step n (m) + character(*), intent(in ) :: callingRoutine !< string containing the name of the calling routine. + integer(IntKi), intent( out) :: errStat !< Error status of the operation + character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None + + ! grid must have two points in each direction + if ( (dims(1) < 2) .or. (dims(2) < 2) .or. (dims(3) < 2) ) then + call SetErrStat ( ErrID_Fatal, 'The high resolution grid dimensions must contain a minimum of 2 nodes in each spatial direction. Turbine #'//trim(num2lstr(nt))//', time step '//trim(num2lstr(n)), errStat, errMsg, callingRoutine ) + return + end if + + ! All turbines and all time steps must have the same grid dimensions due to array allocation assumptions + if ( ( dims(1) .ne. nX ) .or. ( dims(2) .ne. nY ) .or. ( dims(3) .ne. nZ ) ) then + call SetErrStat ( ErrID_Fatal, 'The high resolution grid dimensions for turbine #'//trim(num2lstr(nt))//' and high-res time step '//trim(num2lstr(n))//' do not match turbine #1 and time step 0.', errStat, errMsg, callingRoutine ) + return + end if + + ! spacing must be consistent for a given turbine across all time steps + if ( ( gridSpacing(1) .ne. dX ) .or. ( gridSpacing(2) .ne. dY ) .or. ( gridSpacing(3) .ne. dZ ) ) then + call SetErrStat ( ErrID_Fatal, 'The high resolution grid spacing for turbine #'//trim(num2lstr(nt))//' and high-res time step '//trim(num2lstr(n))//' do not match time step 0.', errStat, errMsg, callingRoutine ) + return + end if + + ! verify origin of any given turbine is not changing with time step. + if ( ( origin(1) .ne. X0 ) .or. ( origin(2) .ne. Y0 ) .or. ( origin(3) .ne. Z0 ) ) then + call SetErrStat ( ErrID_Fatal, 'The high resolution grid origin for turbine #'//trim(num2lstr(nt))//' and high-res time step '//trim(num2lstr(n))//' do not match time step 0.', errStat, errMsg, callingRoutine ) + return + end if + +end subroutine HiResWindCheck subroutine WriteDisWindFiles( n, WrDisSkp1, p, y, m, errStat, errMsg ) integer(IntKi), intent(in ) :: n !< Low-resolution time step increment @@ -88,7 +132,7 @@ end subroutine WriteDisWindFiles subroutine ReadLowResWindFile(n, p, Vamb_Low, errStat, errMsg) integer(IntKi), intent(in ) :: n !< Current simulation timestep increment (zero-based) type(AWAE_ParameterType), intent(in ) :: p !< Parameters - real(ReKi), intent(inout) :: Vamb_Low(:,0:,0:,0:) !< Array which will contain the low resolution grid of ambient wind velocities + real(SiKi), intent(inout) :: Vamb_Low(:,0:,0:,0:) !< Array which will contain the low resolution grid of ambient wind velocities integer(IntKi), intent( out) :: errStat !< Error status of the operation character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None @@ -123,7 +167,7 @@ subroutine ReadHighResWindFile(nt, n, p, Vamb_high, errStat, errMsg) integer(IntKi), intent(in ) :: nt integer(IntKi), intent(in ) :: n !< high-res time increment type(AWAE_ParameterType), intent(in ) :: p !< Parameters - real(ReKi), intent(inout) :: Vamb_high(:,0:,0:,0:) !< Array which will contain the low resolution grid of ambient wind velocities + real(SiKi), intent(inout) :: Vamb_high(:,0:,0:,0:) !< Array which will contain the low resolution grid of ambient wind velocities integer(IntKi), intent( out) :: errStat !< Error status of the operation character(*), intent( out) :: errMsg !< Error message if errStat /= ErrID_None @@ -163,7 +207,7 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) character(ErrMsgLen) :: errMsg2 ! temporary error message character(*), parameter :: RoutineName = 'AWAE_IO_InitGridInfo' real(ReKi) :: X0_low, Y0_low, Z0_low, dX_low, dY_low, dZ_low, dt_low, dt_high - integer(IntKi) :: nXYZ_low, nt, nx_low, ny_low, nz_low, nXYZ_high, nx_high, ny_high, nz_high + integer(IntKi) :: nXYZ_low, nx_low, ny_low, nz_low, nXYZ_high, nx_high, ny_high, nz_high integer(IntKi) :: dims(3) ! dimension of the 3D grid (nX,nY,nZ) real(ReKi) :: origin(3) ! the lower-left corner of the 3D grid (X0,Y0,Z0) real(ReKi) :: gridSpacing(3) ! spacing between grid points in each of the 3 directions (dX,dY,dZ) @@ -171,9 +215,12 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) character(1024) :: descr ! Line describing the contents of the file character(1024) :: vecLabel ! descriptor of the vector data integer(IntKi) :: Un ! file unit + integer(IntKi) :: n, nt, nh, n_high_low, nhigh + + errStat = ErrID_None errMsg = "" - + @@ -181,7 +228,10 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) Un = -1 ! Set to force closing of file on return call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, ErrStat, ErrMsg ) if (ErrStat >= AbortErrLev) return - + if ( (dims(1) < 2) .or. (dims(2) < 2) .or. (dims(3) < 2) ) then + call SetErrStat ( ErrID_Fatal, 'The low resolution grid dimensions most contain a minimum of 2 nodes in each spatial direction.', errStat, errMsg, RoutineName ) + return + end if p%X0_Low = origin(1) p%Y0_low = origin(2) p%Z0_low = origin(3) @@ -230,40 +280,50 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) end do ! Parse a high res wind input file to gather the grid information - + allocate( InitOut%X0_high(p%NumTurbines), InitOut%Y0_high(p%NumTurbines), InitOut%Z0_high(p%NumTurbines), stat=errStat2) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for InitOut origin arrays.', errStat, errMsg, RoutineName ) + allocate( InitOut%dX_high(p%NumTurbines), InitOut%dY_high(p%NumTurbines), InitOut%dZ_high(p%NumTurbines), stat=errStat2) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for InitOut spatial increment arrays.', errStat, errMsg, RoutineName ) + allocate( p%X0_high(p%NumTurbines), p%Y0_high(p%NumTurbines), p%Z0_high(p%NumTurbines), stat=errStat2) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for p origin arrays.', errStat, errMsg, RoutineName ) + allocate( p%dX_high(p%NumTurbines), p%dY_high(p%NumTurbines), p%dZ_high(p%NumTurbines), stat=errStat2) + if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for p spatial increment arrays.', errStat, errMsg, RoutineName ) + if (ErrStat >= AbortErrLev) return FileName = trim(p%WindFilePath)//trim(PathSep)//"HighT1"//trim(PathSep)//"Amb.t0.vtk" !TODO: Should the turbine numbers be padding with leading zero(es)? - ! TODO: Error checking to see that all p%NumTurbines turbines use the same nX, nY, nZ for the high res grids Un = -1 ! Set to force closing of file on return - call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, ErrStat, ErrMsg ) - if (ErrStat >= AbortErrLev) return + call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, errStat, errMsg ) + if (errStat >= AbortErrLev) return p%nX_high = dims(1) p%nY_high = dims(2) p%nZ_high = dims(3) + p%X0_high(1) = origin(1) + p%Y0_high(1) = origin(2) + p%Z0_high(1) = origin(3) + p%dX_high(1) = gridSpacing(1) + p%dY_high(1) = gridSpacing(2) + p%dZ_high(1) = gridSpacing(3) NumGrid_high = p%nX_high*p%nY_high*p%nZ_high + ! Just using this to make sure dims are >=2 points in each direction + call HiResWindCheck(0, 1, p%nX_high, p%nY_high, p%nZ_high, p%dX_high(1), p%dY_high(1), p%dZ_high(1), p%X0_high(1), p%Y0_high(1), p%Z0_high(1), dims, gridSpacing, origin, RoutineName, errMsg, errStat) + if (errStat >= AbortErrLev ) return + allocate( p%Grid_high(3,NumGrid_high,p%NumTurbines ),stat=errStat2) if (errStat2 /= 0) then call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for Grid_high.', errStat, errMsg, RoutineName ) return end if - allocate( InitOut%X0_high(p%NumTurbines), InitOut%Y0_high(p%NumTurbines), InitOut%Z0_high(p%NumTurbines), stat=errStat2) - if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for InitOut origin arrays.', errStat, errMsg, RoutineName ) - allocate( InitOut%dX_high(p%NumTurbines), InitOut%dY_high(p%NumTurbines), InitOut%dZ_high(p%NumTurbines), stat=errStat2) - if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for InitOut spatial increment arrays.', errStat, errMsg, RoutineName ) - allocate( p%X0_high(p%NumTurbines), p%Y0_high(p%NumTurbines), p%Z0_high(p%NumTurbines), stat=errStat2) - if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for p origin arrays.', errStat, errMsg, RoutineName ) - allocate( p%dX_high(p%NumTurbines), p%dY_high(p%NumTurbines), p%dZ_high(p%NumTurbines), stat=errStat2) - if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for p spatial increment arrays.', errStat, errMsg, RoutineName ) - if (ErrStat >= AbortErrLev) return + do nt = 1, p%NumTurbines FileName = trim(p%WindFilePath)//trim(PathSep)//"HighT"//trim(num2lstr(nt))//trim(PathSep)//"Amb.t0.vtk" Un = -1 ! Set to force closing of file on return call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, ErrStat, ErrMsg ) if (ErrStat >= AbortErrLev) return + InitOut%X0_high(nt) = origin(1) InitOut%Y0_high(nt) = origin(2) InitOut%Z0_high(nt) = origin(3) @@ -278,6 +338,12 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) p%dY_high(nt) = gridSpacing(2) p%dZ_high(nt) = gridSpacing(3) + ! Using this to make sure dims are >=2 points in each direction, and number of grid points in each direction matches turbine 1 + call HiResWindCheck(0, nt, p%nX_high, p%nY_high, p%nZ_high, p%dX_high(nt), p%dY_high(nt), p%dZ_high(nt), p%X0_high(nt), p%Y0_high(nt), p%Z0_high(nt), dims, gridSpacing, origin, RoutineName, errMsg, errStat) + if (errStat >= AbortErrLev ) return + + + nXYZ_high = 0 do nz_high=0, p%nZ_high-1 do ny_high=0, p%nY_high-1 @@ -290,6 +356,7 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) end do end do + end do InitOut%nx_high = p%nx_high @@ -297,6 +364,53 @@ subroutine AWAE_IO_InitGridInfo(InitInp, p, InitOut, errStat, errMsg) InitOut%nz_high = p%nz_high + ! Error checking to see that all winds files have consistent headers + + !do nt=1,p%NumTurbines + ! do n=0,p%NumDT-1 ! We have already checked the first low res time step but we need to check all the high-res files associated with n=0 + ! FileName = trim(p%WindFilePath)//trim(PathSep)//"Low"//trim(PathSep)//"Amb.t"//trim(num2lstr(n))//".vtk" + ! Un = -1 ! Set to force closing of file on return + ! call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, ErrStat, ErrMsg ) + ! if (ErrStat >= AbortErrLev) return + ! + ! ! verify dims, origin, gridSpacing + ! if ( ( dims(1) .ne. p%nX_low ) .or. ( dims(2) .ne. p%nY_low ) .or. ( dims(3) .ne. p%nZ_low ) ) then + ! call SetErrStat ( ErrID_Fatal, 'The low resolution grid dimensions for time step '//trim(num2lstr(n))//' do not match time step 0.', errStat, errMsg, RoutineName ) + ! return + ! end if + ! if ( ( origin(1) .ne. InitOut%X0_Low ) .or. ( origin(2) .ne. InitOut%Y0_Low ) .or. ( origin(3) .ne. InitOut%Z0_Low ) ) then + ! call SetErrStat ( ErrID_Fatal, 'The low resolution grid origins for time step '//trim(num2lstr(n))//' do not match time step 0.', errStat, errMsg, RoutineName ) + ! return + ! end if + ! if ( ( gridSpacing(1) .ne. p%dX_low ) .or. ( gridSpacing(2) .ne. p%dY_low ) .or. ( gridSpacing(3) .ne. p%dZ_low ) ) then + ! call SetErrStat ( ErrID_Fatal, 'The low resolution grid spacing for time step '//trim(num2lstr(n))//' do not match time step 0.', errStat, errMsg, RoutineName ) + ! return + ! end if + ! + ! ! High-res turbine wind files + ! if ( (n) == (p%NumDT-1) ) then + ! n_high_low = 1 + ! else + ! n_high_low = p%n_high_low + ! end if + ! do nh=1,n_high_low + ! nhigh = nh+n*p%n_high_low-1 + ! FileName = trim(p%WindFilePath)//trim(PathSep)//"HighT"//trim(num2lstr(nt))//trim(PathSep)//"Amb.t"//trim(num2lstr(nhigh))//".vtk" !TODO: Should the turbine numbers be padding with leading zero(es)? + ! Un = -1 ! Set to force closing of file on return + ! call ReadVTK_SP_info( FileName, descr, dims, origin, gridSpacing, vecLabel, Un, ErrStat, ErrMsg ) + ! if (ErrStat >= AbortErrLev) return + ! + ! call HiResWindCheck(nhigh, nt, p%nX_high, p%nY_high, p%nZ_high, p%dX_high(nt), p%dY_high(nt), p%dZ_high(nt), p%X0_high(nt), p%Y0_high(nt), p%Z0_high(nt), dims, gridSpacing, origin, RoutineName, errMsg, errStat) + ! if (errStat >= AbortErrLev ) return + ! + ! end do + ! end do + ! + !end do + + + + !TODO: Perform any error checking on InitOut and all wind input files here : Review Plan. ! End simulated read of low and high res ambient wind files From cda0614870d7b58d4a719bdd93614840f409018b Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 10:24:45 -0600 Subject: [PATCH 022/386] Added explicit _ReKi to xydisk, etc. initialization Changed number of planes allocated for m%vt_tot, m%vt_amb, and m%vt_shr to NumPlanes-1 instead of NumPlanes-2 fixed unit conversions for C_HWkDfl_OY and %C_HWkDfl_xY in WD_TEST_Init_BadData --- .../wakedynamics/src/WakeDynamics.f90 | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/modules-local/wakedynamics/src/WakeDynamics.f90 b/modules-local/wakedynamics/src/WakeDynamics.f90 index fd68665686..d12c0f0884 100644 --- a/modules-local/wakedynamics/src/WakeDynamics.f90 +++ b/modules-local/wakedynamics/src/WakeDynamics.f90 @@ -67,10 +67,10 @@ function GetYawCorrection(yawErr, xhat_disk, dx, p, errStat, errMsg) errStat = ErrID_None errMsg = '' - xydisk = (/0.0, xhat_disk(1), 0.0/) - yxdisk = (/xhat_disk(2), 0.0, 0.0/) - yydisk = (/0.0, xhat_disk(2), 0.0/) - xxdisk = (/xhat_disk(1), 0.0, 0.0/) + xydisk = (/0.0_ReKi, xhat_disk(1), 0.0_ReKi/) + yxdisk = (/xhat_disk(2), 0.0_ReKi, 0.0_ReKi/) + yydisk = (/0.0_ReKi, xhat_disk(2), 0.0_ReKi/) + xxdisk = (/xhat_disk(1), 0.0_ReKi, 0.0_ReKi/) xydisknorm = TwoNorm(xxdisk + yydisk) if (EqualRealNos(xydisknorm,0.0_ReKi)) then @@ -470,11 +470,11 @@ subroutine WD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitOut if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%dvdr.', errStat, errMsg, RoutineName ) allocate ( m%dvtdr(0:p%NumRadii-1 ) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%dvtdr.', errStat, errMsg, RoutineName ) - allocate ( m%vt_tot(0:p%NumRadii-1,0:p%NumPlanes-2 ) , STAT=ErrStat2 ) + allocate ( m%vt_tot(0:p%NumRadii-1,0:p%NumPlanes-1 ) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%vt_tot.', errStat, errMsg, RoutineName ) - allocate ( m%vt_amb(0:p%NumRadii-1,0:p%NumPlanes-2 ) , STAT=ErrStat2 ) + allocate ( m%vt_amb(0:p%NumRadii-1,0:p%NumPlanes-1 ) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%vt_amb.', errStat, errMsg, RoutineName ) - allocate ( m%vt_shr(0:p%NumRadii-1,0:p%NumPlanes-2 ) , STAT=ErrStat2 ) + allocate ( m%vt_shr(0:p%NumRadii-1,0:p%NumPlanes-1 ) , STAT=ErrStat2 ) if (errStat2 /= 0) call SetErrStat ( ErrID_Fatal, 'Could not allocate memory for m%vt_shr.', errStat, errMsg, RoutineName ) allocate ( m%a(0:p%NumRadii-1 ) , STAT=ErrStat2 ) @@ -1188,9 +1188,9 @@ subroutine WD_TEST_SetGoodInitInpData(interval, InitInp) InitInp%InputFileData%dr = 0.1_ReKi InitInp%InputFileData%f_c = 0.03333333333333 InitInp%InputFileData%C_HWkDfl_O = -2.9 - InitInp%InputFileData%C_HWkDfl_OY = -.24*D2R + InitInp%InputFileData%C_HWkDfl_OY = -.24/D2R InitInp%InputFileData%C_HWkDfl_x = -0.0054 - InitInp%InputFileData%C_HWkDfl_xY = 0.00039*D2R + InitInp%InputFileData%C_HWkDfl_xY = 0.00039/D2R InitInp%InputFileData%C_NearWake = 2 InitInp%InputFileData%C_vAmb_DMin = 0 InitInp%InputFileData%C_vAmb_DMax = 2 From 009b7dba71eadada7a7c23a3320ccdd84cc0e771 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Thu, 1 Jun 2017 11:46:24 -0600 Subject: [PATCH 023/386] Augmented Output channel arrays for 9 turbine support --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 988 +++++++++++++++++++--- 1 file changed, 884 insertions(+), 104 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index 912d620287..27c5873232 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9682,107 +9682,6 @@ module FAST_Farm_IO WkDiamT7D1,WkDiamT7D2,WkDiamT7D3,WkDiamT7D4,WkDiamT7D5,WkDiamT7D6,WkDiamT7D7,WkDiamT7D8,WkDiamT7D9, & WkDiamT8D1,WkDiamT8D2,WkDiamT8D3,WkDiamT8D4,WkDiamT8D5,WkDiamT8D6,WkDiamT8D7,WkDiamT8D8,WkDiamT8D9, & WkDiamT9D1,WkDiamT9D2,WkDiamT9D3,WkDiamT9D4,WkDiamT9D5,WkDiamT9D6,WkDiamT9D7,WkDiamT9D8,WkDiamT9D9/), (/9,9/) ) - - - INTEGER, PARAMETER :: WkDfVxTND(20,9,1) = RESHAPE( & - (/WkDfVxT1N01D1,WkDfVxT1N02D1,WkDfVxT1N03D1,WkDfVxT1N04D1,WkDfVxT1N05D1,WkDfVxT1N06D1,WkDfVxT1N07D1,WkDfVxT1N08D1,WkDfVxT1N09D1,WkDfVxT1N10D1, & - WkDfVxT1N11D1,WkDfVxT1N12D1,WkDfVxT1N13D1,WkDfVxT1N14D1,WkDfVxT1N15D1,WkDfVxT1N16D1,WkDfVxT1N17D1,WkDfVxT1N18D1,WkDfVxT1N19D1,WkDfVxT1N20D1, & - WkDfVxT1N01D2,WkDfVxT1N02D2,WkDfVxT1N03D2,WkDfVxT1N04D2,WkDfVxT1N05D2,WkDfVxT1N06D2,WkDfVxT1N07D2,WkDfVxT1N08D2,WkDfVxT1N09D2,WkDfVxT1N10D2, & - WkDfVxT1N11D2,WkDfVxT1N12D2,WkDfVxT1N13D2,WkDfVxT1N14D2,WkDfVxT1N15D2,WkDfVxT1N16D2,WkDfVxT1N17D2,WkDfVxT1N18D2,WkDfVxT1N19D2,WkDfVxT1N20D2, & - WkDfVxT1N01D3,WkDfVxT1N02D3,WkDfVxT1N03D3,WkDfVxT1N04D3,WkDfVxT1N05D3,WkDfVxT1N06D3,WkDfVxT1N07D3,WkDfVxT1N08D3,WkDfVxT1N09D3,WkDfVxT1N10D3, & - WkDfVxT1N11D3,WkDfVxT1N12D3,WkDfVxT1N13D3,WkDfVxT1N14D3,WkDfVxT1N15D3,WkDfVxT1N16D3,WkDfVxT1N17D3,WkDfVxT1N18D3,WkDfVxT1N19D3,WkDfVxT1N20D3, & - WkDfVxT1N01D4,WkDfVxT1N02D4,WkDfVxT1N03D4,WkDfVxT1N04D4,WkDfVxT1N05D4,WkDfVxT1N06D4,WkDfVxT1N07D4,WkDfVxT1N08D4,WkDfVxT1N09D4,WkDfVxT1N10D4, & - WkDfVxT1N11D4,WkDfVxT1N12D4,WkDfVxT1N13D4,WkDfVxT1N14D4,WkDfVxT1N15D4,WkDfVxT1N16D4,WkDfVxT1N17D4,WkDfVxT1N18D4,WkDfVxT1N19D4,WkDfVxT1N20D4, & - WkDfVxT1N01D5,WkDfVxT1N02D5,WkDfVxT1N03D5,WkDfVxT1N04D5,WkDfVxT1N05D5,WkDfVxT1N06D5,WkDfVxT1N07D5,WkDfVxT1N08D5,WkDfVxT1N09D5,WkDfVxT1N10D5, & - WkDfVxT1N11D5,WkDfVxT1N12D5,WkDfVxT1N13D5,WkDfVxT1N14D5,WkDfVxT1N15D5,WkDfVxT1N16D5,WkDfVxT1N17D5,WkDfVxT1N18D5,WkDfVxT1N19D5,WkDfVxT1N20D5, & - WkDfVxT1N01D6,WkDfVxT1N02D6,WkDfVxT1N03D6,WkDfVxT1N04D6,WkDfVxT1N05D6,WkDfVxT1N06D6,WkDfVxT1N07D6,WkDfVxT1N08D6,WkDfVxT1N09D6,WkDfVxT1N10D6, & - WkDfVxT1N11D6,WkDfVxT1N12D6,WkDfVxT1N13D6,WkDfVxT1N14D6,WkDfVxT1N15D6,WkDfVxT1N16D6,WkDfVxT1N17D6,WkDfVxT1N18D6,WkDfVxT1N19D6,WkDfVxT1N20D6, & - WkDfVxT1N01D7,WkDfVxT1N02D7,WkDfVxT1N03D7,WkDfVxT1N04D7,WkDfVxT1N05D7,WkDfVxT1N06D7,WkDfVxT1N07D7,WkDfVxT1N08D7,WkDfVxT1N09D7,WkDfVxT1N10D7, & - WkDfVxT1N11D7,WkDfVxT1N12D7,WkDfVxT1N13D7,WkDfVxT1N14D7,WkDfVxT1N15D7,WkDfVxT1N16D7,WkDfVxT1N17D7,WkDfVxT1N18D7,WkDfVxT1N19D7,WkDfVxT1N20D7, & - WkDfVxT1N01D8,WkDfVxT1N02D8,WkDfVxT1N03D8,WkDfVxT1N04D8,WkDfVxT1N05D8,WkDfVxT1N06D8,WkDfVxT1N07D8,WkDfVxT1N08D8,WkDfVxT1N09D8,WkDfVxT1N10D8, & - WkDfVxT1N11D8,WkDfVxT1N12D8,WkDfVxT1N13D8,WkDfVxT1N14D8,WkDfVxT1N15D8,WkDfVxT1N16D8,WkDfVxT1N17D8,WkDfVxT1N18D8,WkDfVxT1N19D8,WkDfVxT1N20D8, & - WkDfVxT1N01D9,WkDfVxT1N02D9,WkDfVxT1N03D9,WkDfVxT1N04D9,WkDfVxT1N05D9,WkDfVxT1N06D9,WkDfVxT1N07D9,WkDfVxT1N08D9,WkDfVxT1N09D9,WkDfVxT1N10D9, & - WkDfVxT1N11D9,WkDfVxT1N12D9,WkDfVxT1N13D9,WkDfVxT1N14D9,WkDfVxT1N15D9,WkDfVxT1N16D9,WkDfVxT1N17D9,WkDfVxT1N18D9,WkDfVxT1N19D9,WkDfVxT1N20D9/), (/20,9,1/) ) - - INTEGER, PARAMETER :: WkDfVrTND(20,9,1) = RESHAPE( & - (/WkDfVrT1N01D1,WkDfVrT1N02D1,WkDfVrT1N03D1,WkDfVrT1N04D1,WkDfVrT1N05D1,WkDfVrT1N06D1,WkDfVrT1N07D1,WkDfVrT1N08D1,WkDfVrT1N09D1,WkDfVrT1N10D1, & - WkDfVrT1N11D1,WkDfVrT1N12D1,WkDfVrT1N13D1,WkDfVrT1N14D1,WkDfVrT1N15D1,WkDfVrT1N16D1,WkDfVrT1N17D1,WkDfVrT1N18D1,WkDfVrT1N19D1,WkDfVrT1N20D1, & - WkDfVrT1N01D2,WkDfVrT1N02D2,WkDfVrT1N03D2,WkDfVrT1N04D2,WkDfVrT1N05D2,WkDfVrT1N06D2,WkDfVrT1N07D2,WkDfVrT1N08D2,WkDfVrT1N09D2,WkDfVrT1N10D2, & - WkDfVrT1N11D2,WkDfVrT1N12D2,WkDfVrT1N13D2,WkDfVrT1N14D2,WkDfVrT1N15D2,WkDfVrT1N16D2,WkDfVrT1N17D2,WkDfVrT1N18D2,WkDfVrT1N19D2,WkDfVrT1N20D2, & - WkDfVrT1N01D3,WkDfVrT1N02D3,WkDfVrT1N03D3,WkDfVrT1N04D3,WkDfVrT1N05D3,WkDfVrT1N06D3,WkDfVrT1N07D3,WkDfVrT1N08D3,WkDfVrT1N09D3,WkDfVrT1N10D3, & - WkDfVrT1N11D3,WkDfVrT1N12D3,WkDfVrT1N13D3,WkDfVrT1N14D3,WkDfVrT1N15D3,WkDfVrT1N16D3,WkDfVrT1N17D3,WkDfVrT1N18D3,WkDfVrT1N19D3,WkDfVrT1N20D3, & - WkDfVrT1N01D4,WkDfVrT1N02D4,WkDfVrT1N03D4,WkDfVrT1N04D4,WkDfVrT1N05D4,WkDfVrT1N06D4,WkDfVrT1N07D4,WkDfVrT1N08D4,WkDfVrT1N09D4,WkDfVrT1N10D4, & - WkDfVrT1N11D4,WkDfVrT1N12D4,WkDfVrT1N13D4,WkDfVrT1N14D4,WkDfVrT1N15D4,WkDfVrT1N16D4,WkDfVrT1N17D4,WkDfVrT1N18D4,WkDfVrT1N19D4,WkDfVrT1N20D4, & - WkDfVrT1N01D5,WkDfVrT1N02D5,WkDfVrT1N03D5,WkDfVrT1N04D5,WkDfVrT1N05D5,WkDfVrT1N06D5,WkDfVrT1N07D5,WkDfVrT1N08D5,WkDfVrT1N09D5,WkDfVrT1N10D5, & - WkDfVrT1N11D5,WkDfVrT1N12D5,WkDfVrT1N13D5,WkDfVrT1N14D5,WkDfVrT1N15D5,WkDfVrT1N16D5,WkDfVrT1N17D5,WkDfVrT1N18D5,WkDfVrT1N19D5,WkDfVrT1N20D5, & - WkDfVrT1N01D6,WkDfVrT1N02D6,WkDfVrT1N03D6,WkDfVrT1N04D6,WkDfVrT1N05D6,WkDfVrT1N06D6,WkDfVrT1N07D6,WkDfVrT1N08D6,WkDfVrT1N09D6,WkDfVrT1N10D6, & - WkDfVrT1N11D6,WkDfVrT1N12D6,WkDfVrT1N13D6,WkDfVrT1N14D6,WkDfVrT1N15D6,WkDfVrT1N16D6,WkDfVrT1N17D6,WkDfVrT1N18D6,WkDfVrT1N19D6,WkDfVrT1N20D6, & - WkDfVrT1N01D7,WkDfVrT1N02D7,WkDfVrT1N03D7,WkDfVrT1N04D7,WkDfVrT1N05D7,WkDfVrT1N06D7,WkDfVrT1N07D7,WkDfVrT1N08D7,WkDfVrT1N09D7,WkDfVrT1N10D7, & - WkDfVrT1N11D7,WkDfVrT1N12D7,WkDfVrT1N13D7,WkDfVrT1N14D7,WkDfVrT1N15D7,WkDfVrT1N16D7,WkDfVrT1N17D7,WkDfVrT1N18D7,WkDfVrT1N19D7,WkDfVrT1N20D7, & - WkDfVrT1N01D8,WkDfVrT1N02D8,WkDfVrT1N03D8,WkDfVrT1N04D8,WkDfVrT1N05D8,WkDfVrT1N06D8,WkDfVrT1N07D8,WkDfVrT1N08D8,WkDfVrT1N09D8,WkDfVrT1N10D8, & - WkDfVrT1N11D8,WkDfVrT1N12D8,WkDfVrT1N13D8,WkDfVrT1N14D8,WkDfVrT1N15D8,WkDfVrT1N16D8,WkDfVrT1N17D8,WkDfVrT1N18D8,WkDfVrT1N19D8,WkDfVrT1N20D8, & - WkDfVrT1N01D9,WkDfVrT1N02D9,WkDfVrT1N03D9,WkDfVrT1N04D9,WkDfVrT1N05D9,WkDfVrT1N06D9,WkDfVrT1N07D9,WkDfVrT1N08D9,WkDfVrT1N09D9,WkDfVrT1N10D9, & - WkDfVrT1N11D9,WkDfVrT1N12D9,WkDfVrT1N13D9,WkDfVrT1N14D9,WkDfVrT1N15D9,WkDfVrT1N16D9,WkDfVrT1N17D9,WkDfVrT1N18D9,WkDfVrT1N19D9,WkDfVrT1N20D9/), (/20,9,1/) ) - - INTEGER, PARAMETER :: EddVisTND(20,9,1) = RESHAPE( & - (/EddVisT1N01D1,EddVisT1N02D1,EddVisT1N03D1,EddVisT1N04D1,EddVisT1N05D1,EddVisT1N06D1,EddVisT1N07D1,EddVisT1N08D1,EddVisT1N09D1,EddVisT1N10D1, & - EddVisT1N11D1,EddVisT1N12D1,EddVisT1N13D1,EddVisT1N14D1,EddVisT1N15D1,EddVisT1N16D1,EddVisT1N17D1,EddVisT1N18D1,EddVisT1N19D1,EddVisT1N20D1, & - EddVisT1N01D2,EddVisT1N02D2,EddVisT1N03D2,EddVisT1N04D2,EddVisT1N05D2,EddVisT1N06D2,EddVisT1N07D2,EddVisT1N08D2,EddVisT1N09D2,EddVisT1N10D2, & - EddVisT1N11D2,EddVisT1N12D2,EddVisT1N13D2,EddVisT1N14D2,EddVisT1N15D2,EddVisT1N16D2,EddVisT1N17D2,EddVisT1N18D2,EddVisT1N19D2,EddVisT1N20D2, & - EddVisT1N01D3,EddVisT1N02D3,EddVisT1N03D3,EddVisT1N04D3,EddVisT1N05D3,EddVisT1N06D3,EddVisT1N07D3,EddVisT1N08D3,EddVisT1N09D3,EddVisT1N10D3, & - EddVisT1N11D3,EddVisT1N12D3,EddVisT1N13D3,EddVisT1N14D3,EddVisT1N15D3,EddVisT1N16D3,EddVisT1N17D3,EddVisT1N18D3,EddVisT1N19D3,EddVisT1N20D3, & - EddVisT1N01D4,EddVisT1N02D4,EddVisT1N03D4,EddVisT1N04D4,EddVisT1N05D4,EddVisT1N06D4,EddVisT1N07D4,EddVisT1N08D4,EddVisT1N09D4,EddVisT1N10D4, & - EddVisT1N11D4,EddVisT1N12D4,EddVisT1N13D4,EddVisT1N14D4,EddVisT1N15D4,EddVisT1N16D4,EddVisT1N17D4,EddVisT1N18D4,EddVisT1N19D4,EddVisT1N20D4, & - EddVisT1N01D5,EddVisT1N02D5,EddVisT1N03D5,EddVisT1N04D5,EddVisT1N05D5,EddVisT1N06D5,EddVisT1N07D5,EddVisT1N08D5,EddVisT1N09D5,EddVisT1N10D5, & - EddVisT1N11D5,EddVisT1N12D5,EddVisT1N13D5,EddVisT1N14D5,EddVisT1N15D5,EddVisT1N16D5,EddVisT1N17D5,EddVisT1N18D5,EddVisT1N19D5,EddVisT1N20D5, & - EddVisT1N01D6,EddVisT1N02D6,EddVisT1N03D6,EddVisT1N04D6,EddVisT1N05D6,EddVisT1N06D6,EddVisT1N07D6,EddVisT1N08D6,EddVisT1N09D6,EddVisT1N10D6, & - EddVisT1N11D6,EddVisT1N12D6,EddVisT1N13D6,EddVisT1N14D6,EddVisT1N15D6,EddVisT1N16D6,EddVisT1N17D6,EddVisT1N18D6,EddVisT1N19D6,EddVisT1N20D6, & - EddVisT1N01D7,EddVisT1N02D7,EddVisT1N03D7,EddVisT1N04D7,EddVisT1N05D7,EddVisT1N06D7,EddVisT1N07D7,EddVisT1N08D7,EddVisT1N09D7,EddVisT1N10D7, & - EddVisT1N11D7,EddVisT1N12D7,EddVisT1N13D7,EddVisT1N14D7,EddVisT1N15D7,EddVisT1N16D7,EddVisT1N17D7,EddVisT1N18D7,EddVisT1N19D7,EddVisT1N20D7, & - EddVisT1N01D8,EddVisT1N02D8,EddVisT1N03D8,EddVisT1N04D8,EddVisT1N05D8,EddVisT1N06D8,EddVisT1N07D8,EddVisT1N08D8,EddVisT1N09D8,EddVisT1N10D8, & - EddVisT1N11D8,EddVisT1N12D8,EddVisT1N13D8,EddVisT1N14D8,EddVisT1N15D8,EddVisT1N16D8,EddVisT1N17D8,EddVisT1N18D8,EddVisT1N19D8,EddVisT1N20D8, & - EddVisT1N01D9,EddVisT1N02D9,EddVisT1N03D9,EddVisT1N04D9,EddVisT1N05D9,EddVisT1N06D9,EddVisT1N07D9,EddVisT1N08D9,EddVisT1N09D9,EddVisT1N10D9, & - EddVisT1N11D9,EddVisT1N12D9,EddVisT1N13D9,EddVisT1N14D9,EddVisT1N15D9,EddVisT1N16D9,EddVisT1N17D9,EddVisT1N18D9,EddVisT1N19D9,EddVisT1N20D9/), (/20,9,1/) ) - - INTEGER, PARAMETER :: EddAmbTND(20,9,1) = RESHAPE( & - (/EddAmbT1N01D1,EddAmbT1N02D1,EddAmbT1N03D1,EddAmbT1N04D1,EddAmbT1N05D1,EddAmbT1N06D1,EddAmbT1N07D1,EddAmbT1N08D1,EddAmbT1N09D1,EddAmbT1N10D1, & - EddAmbT1N11D1,EddAmbT1N12D1,EddAmbT1N13D1,EddAmbT1N14D1,EddAmbT1N15D1,EddAmbT1N16D1,EddAmbT1N17D1,EddAmbT1N18D1,EddAmbT1N19D1,EddAmbT1N20D1, & - EddAmbT1N01D2,EddAmbT1N02D2,EddAmbT1N03D2,EddAmbT1N04D2,EddAmbT1N05D2,EddAmbT1N06D2,EddAmbT1N07D2,EddAmbT1N08D2,EddAmbT1N09D2,EddAmbT1N10D2, & - EddAmbT1N11D2,EddAmbT1N12D2,EddAmbT1N13D2,EddAmbT1N14D2,EddAmbT1N15D2,EddAmbT1N16D2,EddAmbT1N17D2,EddAmbT1N18D2,EddAmbT1N19D2,EddAmbT1N20D2, & - EddAmbT1N01D3,EddAmbT1N02D3,EddAmbT1N03D3,EddAmbT1N04D3,EddAmbT1N05D3,EddAmbT1N06D3,EddAmbT1N07D3,EddAmbT1N08D3,EddAmbT1N09D3,EddAmbT1N10D3, & - EddAmbT1N11D3,EddAmbT1N12D3,EddAmbT1N13D3,EddAmbT1N14D3,EddAmbT1N15D3,EddAmbT1N16D3,EddAmbT1N17D3,EddAmbT1N18D3,EddAmbT1N19D3,EddAmbT1N20D3, & - EddAmbT1N01D4,EddAmbT1N02D4,EddAmbT1N03D4,EddAmbT1N04D4,EddAmbT1N05D4,EddAmbT1N06D4,EddAmbT1N07D4,EddAmbT1N08D4,EddAmbT1N09D4,EddAmbT1N10D4, & - EddAmbT1N11D4,EddAmbT1N12D4,EddAmbT1N13D4,EddAmbT1N14D4,EddAmbT1N15D4,EddAmbT1N16D4,EddAmbT1N17D4,EddAmbT1N18D4,EddAmbT1N19D4,EddAmbT1N20D4, & - EddAmbT1N01D5,EddAmbT1N02D5,EddAmbT1N03D5,EddAmbT1N04D5,EddAmbT1N05D5,EddAmbT1N06D5,EddAmbT1N07D5,EddAmbT1N08D5,EddAmbT1N09D5,EddAmbT1N10D5, & - EddAmbT1N11D5,EddAmbT1N12D5,EddAmbT1N13D5,EddAmbT1N14D5,EddAmbT1N15D5,EddAmbT1N16D5,EddAmbT1N17D5,EddAmbT1N18D5,EddAmbT1N19D5,EddAmbT1N20D5, & - EddAmbT1N01D6,EddAmbT1N02D6,EddAmbT1N03D6,EddAmbT1N04D6,EddAmbT1N05D6,EddAmbT1N06D6,EddAmbT1N07D6,EddAmbT1N08D6,EddAmbT1N09D6,EddAmbT1N10D6, & - EddAmbT1N11D6,EddAmbT1N12D6,EddAmbT1N13D6,EddAmbT1N14D6,EddAmbT1N15D6,EddAmbT1N16D6,EddAmbT1N17D6,EddAmbT1N18D6,EddAmbT1N19D6,EddAmbT1N20D6, & - EddAmbT1N01D7,EddAmbT1N02D7,EddAmbT1N03D7,EddAmbT1N04D7,EddAmbT1N05D7,EddAmbT1N06D7,EddAmbT1N07D7,EddAmbT1N08D7,EddAmbT1N09D7,EddAmbT1N10D7, & - EddAmbT1N11D7,EddAmbT1N12D7,EddAmbT1N13D7,EddAmbT1N14D7,EddAmbT1N15D7,EddAmbT1N16D7,EddAmbT1N17D7,EddAmbT1N18D7,EddAmbT1N19D7,EddAmbT1N20D7, & - EddAmbT1N01D8,EddAmbT1N02D8,EddAmbT1N03D8,EddAmbT1N04D8,EddAmbT1N05D8,EddAmbT1N06D8,EddAmbT1N07D8,EddAmbT1N08D8,EddAmbT1N09D8,EddAmbT1N10D8, & - EddAmbT1N11D8,EddAmbT1N12D8,EddAmbT1N13D8,EddAmbT1N14D8,EddAmbT1N15D8,EddAmbT1N16D8,EddAmbT1N17D8,EddAmbT1N18D8,EddAmbT1N19D8,EddAmbT1N20D8, & - EddAmbT1N01D9,EddAmbT1N02D9,EddAmbT1N03D9,EddAmbT1N04D9,EddAmbT1N05D9,EddAmbT1N06D9,EddAmbT1N07D9,EddAmbT1N08D9,EddAmbT1N09D9,EddAmbT1N10D9, & - EddAmbT1N11D9,EddAmbT1N12D9,EddAmbT1N13D9,EddAmbT1N14D9,EddAmbT1N15D9,EddAmbT1N16D9,EddAmbT1N17D9,EddAmbT1N18D9,EddAmbT1N19D9,EddAmbT1N20D9/), (/20,9,1/) ) - - INTEGER, PARAMETER :: EddShrTND(20,9,1) = RESHAPE( & - (/EddShrT1N01D1,EddShrT1N02D1,EddShrT1N03D1,EddShrT1N04D1,EddShrT1N05D1,EddShrT1N06D1,EddShrT1N07D1,EddShrT1N08D1,EddShrT1N09D1,EddShrT1N10D1, & - EddShrT1N11D1,EddShrT1N12D1,EddShrT1N13D1,EddShrT1N14D1,EddShrT1N15D1,EddShrT1N16D1,EddShrT1N17D1,EddShrT1N18D1,EddShrT1N19D1,EddShrT1N20D1, & - EddShrT1N01D2,EddShrT1N02D2,EddShrT1N03D2,EddShrT1N04D2,EddShrT1N05D2,EddShrT1N06D2,EddShrT1N07D2,EddShrT1N08D2,EddShrT1N09D2,EddShrT1N10D2, & - EddShrT1N11D2,EddShrT1N12D2,EddShrT1N13D2,EddShrT1N14D2,EddShrT1N15D2,EddShrT1N16D2,EddShrT1N17D2,EddShrT1N18D2,EddShrT1N19D2,EddShrT1N20D2, & - EddShrT1N01D3,EddShrT1N02D3,EddShrT1N03D3,EddShrT1N04D3,EddShrT1N05D3,EddShrT1N06D3,EddShrT1N07D3,EddShrT1N08D3,EddShrT1N09D3,EddShrT1N10D3, & - EddShrT1N11D3,EddShrT1N12D3,EddShrT1N13D3,EddShrT1N14D3,EddShrT1N15D3,EddShrT1N16D3,EddShrT1N17D3,EddShrT1N18D3,EddShrT1N19D3,EddShrT1N20D3, & - EddShrT1N01D4,EddShrT1N02D4,EddShrT1N03D4,EddShrT1N04D4,EddShrT1N05D4,EddShrT1N06D4,EddShrT1N07D4,EddShrT1N08D4,EddShrT1N09D4,EddShrT1N10D4, & - EddShrT1N11D4,EddShrT1N12D4,EddShrT1N13D4,EddShrT1N14D4,EddShrT1N15D4,EddShrT1N16D4,EddShrT1N17D4,EddShrT1N18D4,EddShrT1N19D4,EddShrT1N20D4, & - EddShrT1N01D5,EddShrT1N02D5,EddShrT1N03D5,EddShrT1N04D5,EddShrT1N05D5,EddShrT1N06D5,EddShrT1N07D5,EddShrT1N08D5,EddShrT1N09D5,EddShrT1N10D5, & - EddShrT1N11D5,EddShrT1N12D5,EddShrT1N13D5,EddShrT1N14D5,EddShrT1N15D5,EddShrT1N16D5,EddShrT1N17D5,EddShrT1N18D5,EddShrT1N19D5,EddShrT1N20D5, & - EddShrT1N01D6,EddShrT1N02D6,EddShrT1N03D6,EddShrT1N04D6,EddShrT1N05D6,EddShrT1N06D6,EddShrT1N07D6,EddShrT1N08D6,EddShrT1N09D6,EddShrT1N10D6, & - EddShrT1N11D6,EddShrT1N12D6,EddShrT1N13D6,EddShrT1N14D6,EddShrT1N15D6,EddShrT1N16D6,EddShrT1N17D6,EddShrT1N18D6,EddShrT1N19D6,EddShrT1N20D6, & - EddShrT1N01D7,EddShrT1N02D7,EddShrT1N03D7,EddShrT1N04D7,EddShrT1N05D7,EddShrT1N06D7,EddShrT1N07D7,EddShrT1N08D7,EddShrT1N09D7,EddShrT1N10D7, & - EddShrT1N11D7,EddShrT1N12D7,EddShrT1N13D7,EddShrT1N14D7,EddShrT1N15D7,EddShrT1N16D7,EddShrT1N17D7,EddShrT1N18D7,EddShrT1N19D7,EddShrT1N20D7, & - EddShrT1N01D8,EddShrT1N02D8,EddShrT1N03D8,EddShrT1N04D8,EddShrT1N05D8,EddShrT1N06D8,EddShrT1N07D8,EddShrT1N08D8,EddShrT1N09D8,EddShrT1N10D8, & - EddShrT1N11D8,EddShrT1N12D8,EddShrT1N13D8,EddShrT1N14D8,EddShrT1N15D8,EddShrT1N16D8,EddShrT1N17D8,EddShrT1N18D8,EddShrT1N19D8,EddShrT1N20D8, & - EddShrT1N01D9,EddShrT1N02D9,EddShrT1N03D9,EddShrT1N04D9,EddShrT1N05D9,EddShrT1N06D9,EddShrT1N07D9,EddShrT1N08D9,EddShrT1N09D9,EddShrT1N10D9, & - EddShrT1N11D9,EddShrT1N12D9,EddShrT1N13D9,EddShrT1N14D9,EddShrT1N15D9,EddShrT1N16D9,EddShrT1N17D9,EddShrT1N18D9,EddShrT1N19D9,EddShrT1N20D9/), (/20,9,1/) ) INTEGER, PARAMETER :: WVAmbX(9) = (/W1VAmbX, W2VAmbX, W3VAmbX, W4VAmbX, W5VAmbX, W6VAmbX, W7VAmbX, W8VAmbX, W9VAmbX/) INTEGER, PARAMETER :: WVAmbY(9) = (/W1VAmbY, W2VAmbY, W3VAmbY, W4VAmbY, W5VAmbY, W6VAmbY, W7VAmbY, W8VAmbY, W9VAmbY/) @@ -9791,6 +9690,20 @@ module FAST_Farm_IO INTEGER, PARAMETER :: WVDisX(9) = (/W1VDisX, W2VDisX, W3VDisX, W4VDisX, W5VDisX, W6VDisX, W7VDisX, W8VDisX, W9VDisX/) INTEGER, PARAMETER :: WVDisY(9) = (/W1VDisY, W2VDisY, W3VDisY, W4VDisY, W5VDisY, W6VDisY, W7VDisY, W8VDisY, W9VDisY/) INTEGER, PARAMETER :: WVDisZ(9) = (/W1VDisZ, W2VDisZ, W3VDisZ, W4VDisZ, W5VDisZ, W6VDisZ, W7VDisZ, W8VDisZ, W9VDisZ/) + + INTEGER(IntKi) :: WkDfVxTND(20,9,9) + INTEGER(IntKi) :: WkDfVrTND(20,9,9) + INTEGER(IntKi) :: EddVisTND(20,9,9) + INTEGER(IntKi) :: EddAmbTND(20,9,9) + INTEGER(IntKi) :: EddShrTND(20,9,9) + public:: WkDfVxTND, WkDfVrTND, EddVisTND, EddAmbTND, EddShrTND + + + + + + + contains @@ -9987,12 +9900,879 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) INTEGER(IntKi) :: indxLast ! The index of the last value to be written to an array INTEGER(IntKi) :: indxNext ! The index of the next value to be written to an array INTEGER(IntKi) :: NumOuts ! number of channels to be written to the output file(s) + INTEGER(IntKi) :: temp(20,9) +WkDfVxTND(:,:,1) = RESHAPE( & + (/WkDfVxT1N01D1,WkDfVxT1N02D1,WkDfVxT1N03D1,WkDfVxT1N04D1,WkDfVxT1N05D1,WkDfVxT1N06D1,WkDfVxT1N07D1,WkDfVxT1N08D1,WkDfVxT1N09D1,WkDfVxT1N10D1, & + WkDfVxT1N11D1,WkDfVxT1N12D1,WkDfVxT1N13D1,WkDfVxT1N14D1,WkDfVxT1N15D1,WkDfVxT1N16D1,WkDfVxT1N17D1,WkDfVxT1N18D1,WkDfVxT1N19D1,WkDfVxT1N20D1, & + WkDfVxT1N01D2,WkDfVxT1N02D2,WkDfVxT1N03D2,WkDfVxT1N04D2,WkDfVxT1N05D2,WkDfVxT1N06D2,WkDfVxT1N07D2,WkDfVxT1N08D2,WkDfVxT1N09D2,WkDfVxT1N10D2, & + WkDfVxT1N11D2,WkDfVxT1N12D2,WkDfVxT1N13D2,WkDfVxT1N14D2,WkDfVxT1N15D2,WkDfVxT1N16D2,WkDfVxT1N17D2,WkDfVxT1N18D2,WkDfVxT1N19D2,WkDfVxT1N20D2, & + WkDfVxT1N01D3,WkDfVxT1N02D3,WkDfVxT1N03D3,WkDfVxT1N04D3,WkDfVxT1N05D3,WkDfVxT1N06D3,WkDfVxT1N07D3,WkDfVxT1N08D3,WkDfVxT1N09D3,WkDfVxT1N10D3, & + WkDfVxT1N11D3,WkDfVxT1N12D3,WkDfVxT1N13D3,WkDfVxT1N14D3,WkDfVxT1N15D3,WkDfVxT1N16D3,WkDfVxT1N17D3,WkDfVxT1N18D3,WkDfVxT1N19D3,WkDfVxT1N20D3, & + WkDfVxT1N01D4,WkDfVxT1N02D4,WkDfVxT1N03D4,WkDfVxT1N04D4,WkDfVxT1N05D4,WkDfVxT1N06D4,WkDfVxT1N07D4,WkDfVxT1N08D4,WkDfVxT1N09D4,WkDfVxT1N10D4, & + WkDfVxT1N11D4,WkDfVxT1N12D4,WkDfVxT1N13D4,WkDfVxT1N14D4,WkDfVxT1N15D4,WkDfVxT1N16D4,WkDfVxT1N17D4,WkDfVxT1N18D4,WkDfVxT1N19D4,WkDfVxT1N20D4, & + WkDfVxT1N01D5,WkDfVxT1N02D5,WkDfVxT1N03D5,WkDfVxT1N04D5,WkDfVxT1N05D5,WkDfVxT1N06D5,WkDfVxT1N07D5,WkDfVxT1N08D5,WkDfVxT1N09D5,WkDfVxT1N10D5, & + WkDfVxT1N11D5,WkDfVxT1N12D5,WkDfVxT1N13D5,WkDfVxT1N14D5,WkDfVxT1N15D5,WkDfVxT1N16D5,WkDfVxT1N17D5,WkDfVxT1N18D5,WkDfVxT1N19D5,WkDfVxT1N20D5, & + WkDfVxT1N01D6,WkDfVxT1N02D6,WkDfVxT1N03D6,WkDfVxT1N04D6,WkDfVxT1N05D6,WkDfVxT1N06D6,WkDfVxT1N07D6,WkDfVxT1N08D6,WkDfVxT1N09D6,WkDfVxT1N10D6, & + WkDfVxT1N11D6,WkDfVxT1N12D6,WkDfVxT1N13D6,WkDfVxT1N14D6,WkDfVxT1N15D6,WkDfVxT1N16D6,WkDfVxT1N17D6,WkDfVxT1N18D6,WkDfVxT1N19D6,WkDfVxT1N20D6, & + WkDfVxT1N01D7,WkDfVxT1N02D7,WkDfVxT1N03D7,WkDfVxT1N04D7,WkDfVxT1N05D7,WkDfVxT1N06D7,WkDfVxT1N07D7,WkDfVxT1N08D7,WkDfVxT1N09D7,WkDfVxT1N10D7, & + WkDfVxT1N11D7,WkDfVxT1N12D7,WkDfVxT1N13D7,WkDfVxT1N14D7,WkDfVxT1N15D7,WkDfVxT1N16D7,WkDfVxT1N17D7,WkDfVxT1N18D7,WkDfVxT1N19D7,WkDfVxT1N20D7, & + WkDfVxT1N01D8,WkDfVxT1N02D8,WkDfVxT1N03D8,WkDfVxT1N04D8,WkDfVxT1N05D8,WkDfVxT1N06D8,WkDfVxT1N07D8,WkDfVxT1N08D8,WkDfVxT1N09D8,WkDfVxT1N10D8, & + WkDfVxT1N11D8,WkDfVxT1N12D8,WkDfVxT1N13D8,WkDfVxT1N14D8,WkDfVxT1N15D8,WkDfVxT1N16D8,WkDfVxT1N17D8,WkDfVxT1N18D8,WkDfVxT1N19D8,WkDfVxT1N20D8, & + WkDfVxT1N01D9,WkDfVxT1N02D9,WkDfVxT1N03D9,WkDfVxT1N04D9,WkDfVxT1N05D9,WkDfVxT1N06D9,WkDfVxT1N07D9,WkDfVxT1N08D9,WkDfVxT1N09D9,WkDfVxT1N10D9, & + WkDfVxT1N11D9,WkDfVxT1N12D9,WkDfVxT1N13D9,WkDfVxT1N14D9,WkDfVxT1N15D9,WkDfVxT1N16D9,WkDfVxT1N17D9,WkDfVxT1N18D9,WkDfVxT1N19D9,WkDfVxT1N20D9/), (/20,9/) ) + +WkDfVxTND(:,:,2) = RESHAPE( & + (/WkDfVxT2N01D1,WkDfVxT2N02D1,WkDfVxT2N03D1,WkDfVxT2N04D1,WkDfVxT2N05D1,WkDfVxT2N06D1,WkDfVxT2N07D1,WkDfVxT2N08D1,WkDfVxT2N09D1,WkDfVxT2N10D1, & + WkDfVxT2N11D1,WkDfVxT2N12D1,WkDfVxT2N13D1,WkDfVxT2N14D1,WkDfVxT2N15D1,WkDfVxT2N16D1,WkDfVxT2N17D1,WkDfVxT2N18D1,WkDfVxT2N19D1,WkDfVxT2N20D1, & + WkDfVxT2N01D2,WkDfVxT2N02D2,WkDfVxT2N03D2,WkDfVxT2N04D2,WkDfVxT2N05D2,WkDfVxT2N06D2,WkDfVxT2N07D2,WkDfVxT2N08D2,WkDfVxT2N09D2,WkDfVxT2N10D2, & + WkDfVxT2N11D2,WkDfVxT2N12D2,WkDfVxT2N13D2,WkDfVxT2N14D2,WkDfVxT2N15D2,WkDfVxT2N16D2,WkDfVxT2N17D2,WkDfVxT2N18D2,WkDfVxT2N19D2,WkDfVxT2N20D2, & + WkDfVxT2N01D3,WkDfVxT2N02D3,WkDfVxT2N03D3,WkDfVxT2N04D3,WkDfVxT2N05D3,WkDfVxT2N06D3,WkDfVxT2N07D3,WkDfVxT2N08D3,WkDfVxT2N09D3,WkDfVxT2N10D3, & + WkDfVxT2N11D3,WkDfVxT2N12D3,WkDfVxT2N13D3,WkDfVxT2N14D3,WkDfVxT2N15D3,WkDfVxT2N16D3,WkDfVxT2N17D3,WkDfVxT2N18D3,WkDfVxT2N19D3,WkDfVxT2N20D3, & + WkDfVxT2N01D4,WkDfVxT2N02D4,WkDfVxT2N03D4,WkDfVxT2N04D4,WkDfVxT2N05D4,WkDfVxT2N06D4,WkDfVxT2N07D4,WkDfVxT2N08D4,WkDfVxT2N09D4,WkDfVxT2N10D4, & + WkDfVxT2N11D4,WkDfVxT2N12D4,WkDfVxT2N13D4,WkDfVxT2N14D4,WkDfVxT2N15D4,WkDfVxT2N16D4,WkDfVxT2N17D4,WkDfVxT2N18D4,WkDfVxT2N19D4,WkDfVxT2N20D4, & + WkDfVxT2N01D5,WkDfVxT2N02D5,WkDfVxT2N03D5,WkDfVxT2N04D5,WkDfVxT2N05D5,WkDfVxT2N06D5,WkDfVxT2N07D5,WkDfVxT2N08D5,WkDfVxT2N09D5,WkDfVxT2N10D5, & + WkDfVxT2N11D5,WkDfVxT2N12D5,WkDfVxT2N13D5,WkDfVxT2N14D5,WkDfVxT2N15D5,WkDfVxT2N16D5,WkDfVxT2N17D5,WkDfVxT2N18D5,WkDfVxT2N19D5,WkDfVxT2N20D5, & + WkDfVxT2N01D6,WkDfVxT2N02D6,WkDfVxT2N03D6,WkDfVxT2N04D6,WkDfVxT2N05D6,WkDfVxT2N06D6,WkDfVxT2N07D6,WkDfVxT2N08D6,WkDfVxT2N09D6,WkDfVxT2N10D6, & + WkDfVxT2N11D6,WkDfVxT2N12D6,WkDfVxT2N13D6,WkDfVxT2N14D6,WkDfVxT2N15D6,WkDfVxT2N16D6,WkDfVxT2N17D6,WkDfVxT2N18D6,WkDfVxT2N19D6,WkDfVxT2N20D6, & + WkDfVxT2N01D7,WkDfVxT2N02D7,WkDfVxT2N03D7,WkDfVxT2N04D7,WkDfVxT2N05D7,WkDfVxT2N06D7,WkDfVxT2N07D7,WkDfVxT2N08D7,WkDfVxT2N09D7,WkDfVxT2N10D7, & + WkDfVxT2N11D7,WkDfVxT2N12D7,WkDfVxT2N13D7,WkDfVxT2N14D7,WkDfVxT2N15D7,WkDfVxT2N16D7,WkDfVxT2N17D7,WkDfVxT2N18D7,WkDfVxT2N19D7,WkDfVxT2N20D7, & + WkDfVxT2N01D8,WkDfVxT2N02D8,WkDfVxT2N03D8,WkDfVxT2N04D8,WkDfVxT2N05D8,WkDfVxT2N06D8,WkDfVxT2N07D8,WkDfVxT2N08D8,WkDfVxT2N09D8,WkDfVxT2N10D8, & + WkDfVxT2N11D8,WkDfVxT2N12D8,WkDfVxT2N13D8,WkDfVxT2N14D8,WkDfVxT2N15D8,WkDfVxT2N16D8,WkDfVxT2N17D8,WkDfVxT2N18D8,WkDfVxT2N19D8,WkDfVxT2N20D8, & + WkDfVxT2N01D9,WkDfVxT2N02D9,WkDfVxT2N03D9,WkDfVxT2N04D9,WkDfVxT2N05D9,WkDfVxT2N06D9,WkDfVxT2N07D9,WkDfVxT2N08D9,WkDfVxT2N09D9,WkDfVxT2N10D9, & + WkDfVxT2N11D9,WkDfVxT2N12D9,WkDfVxT2N13D9,WkDfVxT2N14D9,WkDfVxT2N15D9,WkDfVxT2N16D9,WkDfVxT2N17D9,WkDfVxT2N18D9,WkDfVxT2N19D9,WkDfVxT2N20D9/), (/20,9/) ) +WkDfVxTND(:,:,3) = RESHAPE( & + (/WkDfVxT3N01D1,WkDfVxT3N02D1,WkDfVxT3N03D1,WkDfVxT3N04D1,WkDfVxT3N05D1,WkDfVxT3N06D1,WkDfVxT3N07D1,WkDfVxT3N08D1,WkDfVxT3N09D1,WkDfVxT3N10D1, & + WkDfVxT3N11D1,WkDfVxT3N12D1,WkDfVxT3N13D1,WkDfVxT3N14D1,WkDfVxT3N15D1,WkDfVxT3N16D1,WkDfVxT3N17D1,WkDfVxT3N18D1,WkDfVxT3N19D1,WkDfVxT3N20D1, & + WkDfVxT3N01D2,WkDfVxT3N02D2,WkDfVxT3N03D2,WkDfVxT3N04D2,WkDfVxT3N05D2,WkDfVxT3N06D2,WkDfVxT3N07D2,WkDfVxT3N08D2,WkDfVxT3N09D2,WkDfVxT3N10D2, & + WkDfVxT3N11D2,WkDfVxT3N12D2,WkDfVxT3N13D2,WkDfVxT3N14D2,WkDfVxT3N15D2,WkDfVxT3N16D2,WkDfVxT3N17D2,WkDfVxT3N18D2,WkDfVxT3N19D2,WkDfVxT3N20D2, & + WkDfVxT3N01D3,WkDfVxT3N02D3,WkDfVxT3N03D3,WkDfVxT3N04D3,WkDfVxT3N05D3,WkDfVxT3N06D3,WkDfVxT3N07D3,WkDfVxT3N08D3,WkDfVxT3N09D3,WkDfVxT3N10D3, & + WkDfVxT3N11D3,WkDfVxT3N12D3,WkDfVxT3N13D3,WkDfVxT3N14D3,WkDfVxT3N15D3,WkDfVxT3N16D3,WkDfVxT3N17D3,WkDfVxT3N18D3,WkDfVxT3N19D3,WkDfVxT3N20D3, & + WkDfVxT3N01D4,WkDfVxT3N02D4,WkDfVxT3N03D4,WkDfVxT3N04D4,WkDfVxT3N05D4,WkDfVxT3N06D4,WkDfVxT3N07D4,WkDfVxT3N08D4,WkDfVxT3N09D4,WkDfVxT3N10D4, & + WkDfVxT3N11D4,WkDfVxT3N12D4,WkDfVxT3N13D4,WkDfVxT3N14D4,WkDfVxT3N15D4,WkDfVxT3N16D4,WkDfVxT3N17D4,WkDfVxT3N18D4,WkDfVxT3N19D4,WkDfVxT3N20D4, & + WkDfVxT3N01D5,WkDfVxT3N02D5,WkDfVxT3N03D5,WkDfVxT3N04D5,WkDfVxT3N05D5,WkDfVxT3N06D5,WkDfVxT3N07D5,WkDfVxT3N08D5,WkDfVxT3N09D5,WkDfVxT3N10D5, & + WkDfVxT3N11D5,WkDfVxT3N12D5,WkDfVxT3N13D5,WkDfVxT3N14D5,WkDfVxT3N15D5,WkDfVxT3N16D5,WkDfVxT3N17D5,WkDfVxT3N18D5,WkDfVxT3N19D5,WkDfVxT3N20D5, & + WkDfVxT3N01D6,WkDfVxT3N02D6,WkDfVxT3N03D6,WkDfVxT3N04D6,WkDfVxT3N05D6,WkDfVxT3N06D6,WkDfVxT3N07D6,WkDfVxT3N08D6,WkDfVxT3N09D6,WkDfVxT3N10D6, & + WkDfVxT3N11D6,WkDfVxT3N12D6,WkDfVxT3N13D6,WkDfVxT3N14D6,WkDfVxT3N15D6,WkDfVxT3N16D6,WkDfVxT3N17D6,WkDfVxT3N18D6,WkDfVxT3N19D6,WkDfVxT3N20D6, & + WkDfVxT3N01D7,WkDfVxT3N02D7,WkDfVxT3N03D7,WkDfVxT3N04D7,WkDfVxT3N05D7,WkDfVxT3N06D7,WkDfVxT3N07D7,WkDfVxT3N08D7,WkDfVxT3N09D7,WkDfVxT3N10D7, & + WkDfVxT3N11D7,WkDfVxT3N12D7,WkDfVxT3N13D7,WkDfVxT3N14D7,WkDfVxT3N15D7,WkDfVxT3N16D7,WkDfVxT3N17D7,WkDfVxT3N18D7,WkDfVxT3N19D7,WkDfVxT3N20D7, & + WkDfVxT3N01D8,WkDfVxT3N02D8,WkDfVxT3N03D8,WkDfVxT3N04D8,WkDfVxT3N05D8,WkDfVxT3N06D8,WkDfVxT3N07D8,WkDfVxT3N08D8,WkDfVxT3N09D8,WkDfVxT3N10D8, & + WkDfVxT3N11D8,WkDfVxT3N12D8,WkDfVxT3N13D8,WkDfVxT3N14D8,WkDfVxT3N15D8,WkDfVxT3N16D8,WkDfVxT3N17D8,WkDfVxT3N18D8,WkDfVxT3N19D8,WkDfVxT3N20D8, & + WkDfVxT3N01D9,WkDfVxT3N02D9,WkDfVxT3N03D9,WkDfVxT3N04D9,WkDfVxT3N05D9,WkDfVxT3N06D9,WkDfVxT3N07D9,WkDfVxT3N08D9,WkDfVxT3N09D9,WkDfVxT3N10D9, & + WkDfVxT3N11D9,WkDfVxT3N12D9,WkDfVxT3N13D9,WkDfVxT3N14D9,WkDfVxT3N15D9,WkDfVxT3N16D9,WkDfVxT3N17D9,WkDfVxT3N18D9,WkDfVxT3N19D9,WkDfVxT3N20D9/), (/20,9/) ) +WkDfVxTND(:,:,4) = RESHAPE( & + (/WkDfVxT4N01D1,WkDfVxT4N02D1,WkDfVxT4N03D1,WkDfVxT4N04D1,WkDfVxT4N05D1,WkDfVxT4N06D1,WkDfVxT4N07D1,WkDfVxT4N08D1,WkDfVxT4N09D1,WkDfVxT4N10D1, & + WkDfVxT4N11D1,WkDfVxT4N12D1,WkDfVxT4N13D1,WkDfVxT4N14D1,WkDfVxT4N15D1,WkDfVxT4N16D1,WkDfVxT4N17D1,WkDfVxT4N18D1,WkDfVxT4N19D1,WkDfVxT4N20D1, & + WkDfVxT4N01D2,WkDfVxT4N02D2,WkDfVxT4N03D2,WkDfVxT4N04D2,WkDfVxT4N05D2,WkDfVxT4N06D2,WkDfVxT4N07D2,WkDfVxT4N08D2,WkDfVxT4N09D2,WkDfVxT4N10D2, & + WkDfVxT4N11D2,WkDfVxT4N12D2,WkDfVxT4N13D2,WkDfVxT4N14D2,WkDfVxT4N15D2,WkDfVxT4N16D2,WkDfVxT4N17D2,WkDfVxT4N18D2,WkDfVxT4N19D2,WkDfVxT4N20D2, & + WkDfVxT4N01D3,WkDfVxT4N02D3,WkDfVxT4N03D3,WkDfVxT4N04D3,WkDfVxT4N05D3,WkDfVxT4N06D3,WkDfVxT4N07D3,WkDfVxT4N08D3,WkDfVxT4N09D3,WkDfVxT4N10D3, & + WkDfVxT4N11D3,WkDfVxT4N12D3,WkDfVxT4N13D3,WkDfVxT4N14D3,WkDfVxT4N15D3,WkDfVxT4N16D3,WkDfVxT4N17D3,WkDfVxT4N18D3,WkDfVxT4N19D3,WkDfVxT4N20D3, & + WkDfVxT4N01D4,WkDfVxT4N02D4,WkDfVxT4N03D4,WkDfVxT4N04D4,WkDfVxT4N05D4,WkDfVxT4N06D4,WkDfVxT4N07D4,WkDfVxT4N08D4,WkDfVxT4N09D4,WkDfVxT4N10D4, & + WkDfVxT4N11D4,WkDfVxT4N12D4,WkDfVxT4N13D4,WkDfVxT4N14D4,WkDfVxT4N15D4,WkDfVxT4N16D4,WkDfVxT4N17D4,WkDfVxT4N18D4,WkDfVxT4N19D4,WkDfVxT4N20D4, & + WkDfVxT4N01D5,WkDfVxT4N02D5,WkDfVxT4N03D5,WkDfVxT4N04D5,WkDfVxT4N05D5,WkDfVxT4N06D5,WkDfVxT4N07D5,WkDfVxT4N08D5,WkDfVxT4N09D5,WkDfVxT4N10D5, & + WkDfVxT4N11D5,WkDfVxT4N12D5,WkDfVxT4N13D5,WkDfVxT4N14D5,WkDfVxT4N15D5,WkDfVxT4N16D5,WkDfVxT4N17D5,WkDfVxT4N18D5,WkDfVxT4N19D5,WkDfVxT4N20D5, & + WkDfVxT4N01D6,WkDfVxT4N02D6,WkDfVxT4N03D6,WkDfVxT4N04D6,WkDfVxT4N05D6,WkDfVxT4N06D6,WkDfVxT4N07D6,WkDfVxT4N08D6,WkDfVxT4N09D6,WkDfVxT4N10D6, & + WkDfVxT4N11D6,WkDfVxT4N12D6,WkDfVxT4N13D6,WkDfVxT4N14D6,WkDfVxT4N15D6,WkDfVxT4N16D6,WkDfVxT4N17D6,WkDfVxT4N18D6,WkDfVxT4N19D6,WkDfVxT4N20D6, & + WkDfVxT4N01D7,WkDfVxT4N02D7,WkDfVxT4N03D7,WkDfVxT4N04D7,WkDfVxT4N05D7,WkDfVxT4N06D7,WkDfVxT4N07D7,WkDfVxT4N08D7,WkDfVxT4N09D7,WkDfVxT4N10D7, & + WkDfVxT4N11D7,WkDfVxT4N12D7,WkDfVxT4N13D7,WkDfVxT4N14D7,WkDfVxT4N15D7,WkDfVxT4N16D7,WkDfVxT4N17D7,WkDfVxT4N18D7,WkDfVxT4N19D7,WkDfVxT4N20D7, & + WkDfVxT4N01D8,WkDfVxT4N02D8,WkDfVxT4N03D8,WkDfVxT4N04D8,WkDfVxT4N05D8,WkDfVxT4N06D8,WkDfVxT4N07D8,WkDfVxT4N08D8,WkDfVxT4N09D8,WkDfVxT4N10D8, & + WkDfVxT4N11D8,WkDfVxT4N12D8,WkDfVxT4N13D8,WkDfVxT4N14D8,WkDfVxT4N15D8,WkDfVxT4N16D8,WkDfVxT4N17D8,WkDfVxT4N18D8,WkDfVxT4N19D8,WkDfVxT4N20D8, & + WkDfVxT4N01D9,WkDfVxT4N02D9,WkDfVxT4N03D9,WkDfVxT4N04D9,WkDfVxT4N05D9,WkDfVxT4N06D9,WkDfVxT4N07D9,WkDfVxT4N08D9,WkDfVxT4N09D9,WkDfVxT4N10D9, & + WkDfVxT4N11D9,WkDfVxT4N12D9,WkDfVxT4N13D9,WkDfVxT4N14D9,WkDfVxT4N15D9,WkDfVxT4N16D9,WkDfVxT4N17D9,WkDfVxT4N18D9,WkDfVxT4N19D9,WkDfVxT4N20D9/), (/20,9/) ) + +WkDfVxTND(:,:,5) = RESHAPE( & + (/WkDfVxT5N01D1,WkDfVxT5N02D1,WkDfVxT5N03D1,WkDfVxT5N04D1,WkDfVxT5N05D1,WkDfVxT5N06D1,WkDfVxT5N07D1,WkDfVxT5N08D1,WkDfVxT5N09D1,WkDfVxT5N10D1, & + WkDfVxT5N11D1,WkDfVxT5N12D1,WkDfVxT5N13D1,WkDfVxT5N14D1,WkDfVxT5N15D1,WkDfVxT5N16D1,WkDfVxT5N17D1,WkDfVxT5N18D1,WkDfVxT5N19D1,WkDfVxT5N20D1, & + WkDfVxT5N01D2,WkDfVxT5N02D2,WkDfVxT5N03D2,WkDfVxT5N04D2,WkDfVxT5N05D2,WkDfVxT5N06D2,WkDfVxT5N07D2,WkDfVxT5N08D2,WkDfVxT5N09D2,WkDfVxT5N10D2, & + WkDfVxT5N11D2,WkDfVxT5N12D2,WkDfVxT5N13D2,WkDfVxT5N14D2,WkDfVxT5N15D2,WkDfVxT5N16D2,WkDfVxT5N17D2,WkDfVxT5N18D2,WkDfVxT5N19D2,WkDfVxT5N20D2, & + WkDfVxT5N01D3,WkDfVxT5N02D3,WkDfVxT5N03D3,WkDfVxT5N04D3,WkDfVxT5N05D3,WkDfVxT5N06D3,WkDfVxT5N07D3,WkDfVxT5N08D3,WkDfVxT5N09D3,WkDfVxT5N10D3, & + WkDfVxT5N11D3,WkDfVxT5N12D3,WkDfVxT5N13D3,WkDfVxT5N14D3,WkDfVxT5N15D3,WkDfVxT5N16D3,WkDfVxT5N17D3,WkDfVxT5N18D3,WkDfVxT5N19D3,WkDfVxT5N20D3, & + WkDfVxT5N01D4,WkDfVxT5N02D4,WkDfVxT5N03D4,WkDfVxT5N04D4,WkDfVxT5N05D4,WkDfVxT5N06D4,WkDfVxT5N07D4,WkDfVxT5N08D4,WkDfVxT5N09D4,WkDfVxT5N10D4, & + WkDfVxT5N11D4,WkDfVxT5N12D4,WkDfVxT5N13D4,WkDfVxT5N14D4,WkDfVxT5N15D4,WkDfVxT5N16D4,WkDfVxT5N17D4,WkDfVxT5N18D4,WkDfVxT5N19D4,WkDfVxT5N20D4, & + WkDfVxT5N01D5,WkDfVxT5N02D5,WkDfVxT5N03D5,WkDfVxT5N04D5,WkDfVxT5N05D5,WkDfVxT5N06D5,WkDfVxT5N07D5,WkDfVxT5N08D5,WkDfVxT5N09D5,WkDfVxT5N10D5, & + WkDfVxT5N11D5,WkDfVxT5N12D5,WkDfVxT5N13D5,WkDfVxT5N14D5,WkDfVxT5N15D5,WkDfVxT5N16D5,WkDfVxT5N17D5,WkDfVxT5N18D5,WkDfVxT5N19D5,WkDfVxT5N20D5, & + WkDfVxT5N01D6,WkDfVxT5N02D6,WkDfVxT5N03D6,WkDfVxT5N04D6,WkDfVxT5N05D6,WkDfVxT5N06D6,WkDfVxT5N07D6,WkDfVxT5N08D6,WkDfVxT5N09D6,WkDfVxT5N10D6, & + WkDfVxT5N11D6,WkDfVxT5N12D6,WkDfVxT5N13D6,WkDfVxT5N14D6,WkDfVxT5N15D6,WkDfVxT5N16D6,WkDfVxT5N17D6,WkDfVxT5N18D6,WkDfVxT5N19D6,WkDfVxT5N20D6, & + WkDfVxT5N01D7,WkDfVxT5N02D7,WkDfVxT5N03D7,WkDfVxT5N04D7,WkDfVxT5N05D7,WkDfVxT5N06D7,WkDfVxT5N07D7,WkDfVxT5N08D7,WkDfVxT5N09D7,WkDfVxT5N10D7, & + WkDfVxT5N11D7,WkDfVxT5N12D7,WkDfVxT5N13D7,WkDfVxT5N14D7,WkDfVxT5N15D7,WkDfVxT5N16D7,WkDfVxT5N17D7,WkDfVxT5N18D7,WkDfVxT5N19D7,WkDfVxT5N20D7, & + WkDfVxT5N01D8,WkDfVxT5N02D8,WkDfVxT5N03D8,WkDfVxT5N04D8,WkDfVxT5N05D8,WkDfVxT5N06D8,WkDfVxT5N07D8,WkDfVxT5N08D8,WkDfVxT5N09D8,WkDfVxT5N10D8, & + WkDfVxT5N11D8,WkDfVxT5N12D8,WkDfVxT5N13D8,WkDfVxT5N14D8,WkDfVxT5N15D8,WkDfVxT5N16D8,WkDfVxT5N17D8,WkDfVxT5N18D8,WkDfVxT5N19D8,WkDfVxT5N20D8, & + WkDfVxT5N01D9,WkDfVxT5N02D9,WkDfVxT5N03D9,WkDfVxT5N04D9,WkDfVxT5N05D9,WkDfVxT5N06D9,WkDfVxT5N07D9,WkDfVxT5N08D9,WkDfVxT5N09D9,WkDfVxT5N10D9, & + WkDfVxT5N11D9,WkDfVxT5N12D9,WkDfVxT5N13D9,WkDfVxT5N14D9,WkDfVxT5N15D9,WkDfVxT5N16D9,WkDfVxT5N17D9,WkDfVxT5N18D9,WkDfVxT5N19D9,WkDfVxT5N20D9/), (/20,9/) ) +WkDfVxTND(:,:,6) = RESHAPE( & + (/WkDfVxT6N01D1,WkDfVxT6N02D1,WkDfVxT6N03D1,WkDfVxT6N04D1,WkDfVxT6N05D1,WkDfVxT6N06D1,WkDfVxT6N07D1,WkDfVxT6N08D1,WkDfVxT6N09D1,WkDfVxT6N10D1, & + WkDfVxT6N11D1,WkDfVxT6N12D1,WkDfVxT6N13D1,WkDfVxT6N14D1,WkDfVxT6N15D1,WkDfVxT6N16D1,WkDfVxT6N17D1,WkDfVxT6N18D1,WkDfVxT6N19D1,WkDfVxT6N20D1, & + WkDfVxT6N01D2,WkDfVxT6N02D2,WkDfVxT6N03D2,WkDfVxT6N04D2,WkDfVxT6N05D2,WkDfVxT6N06D2,WkDfVxT6N07D2,WkDfVxT6N08D2,WkDfVxT6N09D2,WkDfVxT6N10D2, & + WkDfVxT6N11D2,WkDfVxT6N12D2,WkDfVxT6N13D2,WkDfVxT6N14D2,WkDfVxT6N15D2,WkDfVxT6N16D2,WkDfVxT6N17D2,WkDfVxT6N18D2,WkDfVxT6N19D2,WkDfVxT6N20D2, & + WkDfVxT6N01D3,WkDfVxT6N02D3,WkDfVxT6N03D3,WkDfVxT6N04D3,WkDfVxT6N05D3,WkDfVxT6N06D3,WkDfVxT6N07D3,WkDfVxT6N08D3,WkDfVxT6N09D3,WkDfVxT6N10D3, & + WkDfVxT6N11D3,WkDfVxT6N12D3,WkDfVxT6N13D3,WkDfVxT6N14D3,WkDfVxT6N15D3,WkDfVxT6N16D3,WkDfVxT6N17D3,WkDfVxT6N18D3,WkDfVxT6N19D3,WkDfVxT6N20D3, & + WkDfVxT6N01D4,WkDfVxT6N02D4,WkDfVxT6N03D4,WkDfVxT6N04D4,WkDfVxT6N05D4,WkDfVxT6N06D4,WkDfVxT6N07D4,WkDfVxT6N08D4,WkDfVxT6N09D4,WkDfVxT6N10D4, & + WkDfVxT6N11D4,WkDfVxT6N12D4,WkDfVxT6N13D4,WkDfVxT6N14D4,WkDfVxT6N15D4,WkDfVxT6N16D4,WkDfVxT6N17D4,WkDfVxT6N18D4,WkDfVxT6N19D4,WkDfVxT6N20D4, & + WkDfVxT6N01D5,WkDfVxT6N02D5,WkDfVxT6N03D5,WkDfVxT6N04D5,WkDfVxT6N05D5,WkDfVxT6N06D5,WkDfVxT6N07D5,WkDfVxT6N08D5,WkDfVxT6N09D5,WkDfVxT6N10D5, & + WkDfVxT6N11D5,WkDfVxT6N12D5,WkDfVxT6N13D5,WkDfVxT6N14D5,WkDfVxT6N15D5,WkDfVxT6N16D5,WkDfVxT6N17D5,WkDfVxT6N18D5,WkDfVxT6N19D5,WkDfVxT6N20D5, & + WkDfVxT6N01D6,WkDfVxT6N02D6,WkDfVxT6N03D6,WkDfVxT6N04D6,WkDfVxT6N05D6,WkDfVxT6N06D6,WkDfVxT6N07D6,WkDfVxT6N08D6,WkDfVxT6N09D6,WkDfVxT6N10D6, & + WkDfVxT6N11D6,WkDfVxT6N12D6,WkDfVxT6N13D6,WkDfVxT6N14D6,WkDfVxT6N15D6,WkDfVxT6N16D6,WkDfVxT6N17D6,WkDfVxT6N18D6,WkDfVxT6N19D6,WkDfVxT6N20D6, & + WkDfVxT6N01D7,WkDfVxT6N02D7,WkDfVxT6N03D7,WkDfVxT6N04D7,WkDfVxT6N05D7,WkDfVxT6N06D7,WkDfVxT6N07D7,WkDfVxT6N08D7,WkDfVxT6N09D7,WkDfVxT6N10D7, & + WkDfVxT6N11D7,WkDfVxT6N12D7,WkDfVxT6N13D7,WkDfVxT6N14D7,WkDfVxT6N15D7,WkDfVxT6N16D7,WkDfVxT6N17D7,WkDfVxT6N18D7,WkDfVxT6N19D7,WkDfVxT6N20D7, & + WkDfVxT6N01D8,WkDfVxT6N02D8,WkDfVxT6N03D8,WkDfVxT6N04D8,WkDfVxT6N05D8,WkDfVxT6N06D8,WkDfVxT6N07D8,WkDfVxT6N08D8,WkDfVxT6N09D8,WkDfVxT6N10D8, & + WkDfVxT6N11D8,WkDfVxT6N12D8,WkDfVxT6N13D8,WkDfVxT6N14D8,WkDfVxT6N15D8,WkDfVxT6N16D8,WkDfVxT6N17D8,WkDfVxT6N18D8,WkDfVxT6N19D8,WkDfVxT6N20D8, & + WkDfVxT6N01D9,WkDfVxT6N02D9,WkDfVxT6N03D9,WkDfVxT6N04D9,WkDfVxT6N05D9,WkDfVxT6N06D9,WkDfVxT6N07D9,WkDfVxT6N08D9,WkDfVxT6N09D9,WkDfVxT6N10D9, & + WkDfVxT6N11D9,WkDfVxT6N12D9,WkDfVxT6N13D9,WkDfVxT6N14D9,WkDfVxT6N15D9,WkDfVxT6N16D9,WkDfVxT6N17D9,WkDfVxT6N18D9,WkDfVxT6N19D9,WkDfVxT6N20D9/), (/20,9/) ) +WkDfVxTND(:,:,7) = RESHAPE( & + (/WkDfVxT7N01D1,WkDfVxT7N02D1,WkDfVxT7N03D1,WkDfVxT7N04D1,WkDfVxT7N05D1,WkDfVxT7N06D1,WkDfVxT7N07D1,WkDfVxT7N08D1,WkDfVxT7N09D1,WkDfVxT7N10D1, & + WkDfVxT7N11D1,WkDfVxT7N12D1,WkDfVxT7N13D1,WkDfVxT7N14D1,WkDfVxT7N15D1,WkDfVxT7N16D1,WkDfVxT7N17D1,WkDfVxT7N18D1,WkDfVxT7N19D1,WkDfVxT7N20D1, & + WkDfVxT7N01D2,WkDfVxT7N02D2,WkDfVxT7N03D2,WkDfVxT7N04D2,WkDfVxT7N05D2,WkDfVxT7N06D2,WkDfVxT7N07D2,WkDfVxT7N08D2,WkDfVxT7N09D2,WkDfVxT7N10D2, & + WkDfVxT7N11D2,WkDfVxT7N12D2,WkDfVxT7N13D2,WkDfVxT7N14D2,WkDfVxT7N15D2,WkDfVxT7N16D2,WkDfVxT7N17D2,WkDfVxT7N18D2,WkDfVxT7N19D2,WkDfVxT7N20D2, & + WkDfVxT7N01D3,WkDfVxT7N02D3,WkDfVxT7N03D3,WkDfVxT7N04D3,WkDfVxT7N05D3,WkDfVxT7N06D3,WkDfVxT7N07D3,WkDfVxT7N08D3,WkDfVxT7N09D3,WkDfVxT7N10D3, & + WkDfVxT7N11D3,WkDfVxT7N12D3,WkDfVxT7N13D3,WkDfVxT7N14D3,WkDfVxT7N15D3,WkDfVxT7N16D3,WkDfVxT7N17D3,WkDfVxT7N18D3,WkDfVxT7N19D3,WkDfVxT7N20D3, & + WkDfVxT7N01D4,WkDfVxT7N02D4,WkDfVxT7N03D4,WkDfVxT7N04D4,WkDfVxT7N05D4,WkDfVxT7N06D4,WkDfVxT7N07D4,WkDfVxT7N08D4,WkDfVxT7N09D4,WkDfVxT7N10D4, & + WkDfVxT7N11D4,WkDfVxT7N12D4,WkDfVxT7N13D4,WkDfVxT7N14D4,WkDfVxT7N15D4,WkDfVxT7N16D4,WkDfVxT7N17D4,WkDfVxT7N18D4,WkDfVxT7N19D4,WkDfVxT7N20D4, & + WkDfVxT7N01D5,WkDfVxT7N02D5,WkDfVxT7N03D5,WkDfVxT7N04D5,WkDfVxT7N05D5,WkDfVxT7N06D5,WkDfVxT7N07D5,WkDfVxT7N08D5,WkDfVxT7N09D5,WkDfVxT7N10D5, & + WkDfVxT7N11D5,WkDfVxT7N12D5,WkDfVxT7N13D5,WkDfVxT7N14D5,WkDfVxT7N15D5,WkDfVxT7N16D5,WkDfVxT7N17D5,WkDfVxT7N18D5,WkDfVxT7N19D5,WkDfVxT7N20D5, & + WkDfVxT7N01D6,WkDfVxT7N02D6,WkDfVxT7N03D6,WkDfVxT7N04D6,WkDfVxT7N05D6,WkDfVxT7N06D6,WkDfVxT7N07D6,WkDfVxT7N08D6,WkDfVxT7N09D6,WkDfVxT7N10D6, & + WkDfVxT7N11D6,WkDfVxT7N12D6,WkDfVxT7N13D6,WkDfVxT7N14D6,WkDfVxT7N15D6,WkDfVxT7N16D6,WkDfVxT7N17D6,WkDfVxT7N18D6,WkDfVxT7N19D6,WkDfVxT7N20D6, & + WkDfVxT7N01D7,WkDfVxT7N02D7,WkDfVxT7N03D7,WkDfVxT7N04D7,WkDfVxT7N05D7,WkDfVxT7N06D7,WkDfVxT7N07D7,WkDfVxT7N08D7,WkDfVxT7N09D7,WkDfVxT7N10D7, & + WkDfVxT7N11D7,WkDfVxT7N12D7,WkDfVxT7N13D7,WkDfVxT7N14D7,WkDfVxT7N15D7,WkDfVxT7N16D7,WkDfVxT7N17D7,WkDfVxT7N18D7,WkDfVxT7N19D7,WkDfVxT7N20D7, & + WkDfVxT7N01D8,WkDfVxT7N02D8,WkDfVxT7N03D8,WkDfVxT7N04D8,WkDfVxT7N05D8,WkDfVxT7N06D8,WkDfVxT7N07D8,WkDfVxT7N08D8,WkDfVxT7N09D8,WkDfVxT7N10D8, & + WkDfVxT7N11D8,WkDfVxT7N12D8,WkDfVxT7N13D8,WkDfVxT7N14D8,WkDfVxT7N15D8,WkDfVxT7N16D8,WkDfVxT7N17D8,WkDfVxT7N18D8,WkDfVxT7N19D8,WkDfVxT7N20D8, & + WkDfVxT7N01D9,WkDfVxT7N02D9,WkDfVxT7N03D9,WkDfVxT7N04D9,WkDfVxT7N05D9,WkDfVxT7N06D9,WkDfVxT7N07D9,WkDfVxT7N08D9,WkDfVxT7N09D9,WkDfVxT7N10D9, & + WkDfVxT7N11D9,WkDfVxT7N12D9,WkDfVxT7N13D9,WkDfVxT7N14D9,WkDfVxT7N15D9,WkDfVxT7N16D9,WkDfVxT7N17D9,WkDfVxT7N18D9,WkDfVxT7N19D9,WkDfVxT7N20D9/), (/20,9/) ) +WkDfVxTND(:,:,8) = RESHAPE( & + (/WkDfVxT8N01D1,WkDfVxT8N02D1,WkDfVxT8N03D1,WkDfVxT8N04D1,WkDfVxT8N05D1,WkDfVxT8N06D1,WkDfVxT8N07D1,WkDfVxT8N08D1,WkDfVxT8N09D1,WkDfVxT8N10D1, & + WkDfVxT8N11D1,WkDfVxT8N12D1,WkDfVxT8N13D1,WkDfVxT8N14D1,WkDfVxT8N15D1,WkDfVxT8N16D1,WkDfVxT8N17D1,WkDfVxT8N18D1,WkDfVxT8N19D1,WkDfVxT8N20D1, & + WkDfVxT8N01D2,WkDfVxT8N02D2,WkDfVxT8N03D2,WkDfVxT8N04D2,WkDfVxT8N05D2,WkDfVxT8N06D2,WkDfVxT8N07D2,WkDfVxT8N08D2,WkDfVxT8N09D2,WkDfVxT8N10D2, & + WkDfVxT8N11D2,WkDfVxT8N12D2,WkDfVxT8N13D2,WkDfVxT8N14D2,WkDfVxT8N15D2,WkDfVxT8N16D2,WkDfVxT8N17D2,WkDfVxT8N18D2,WkDfVxT8N19D2,WkDfVxT8N20D2, & + WkDfVxT8N01D3,WkDfVxT8N02D3,WkDfVxT8N03D3,WkDfVxT8N04D3,WkDfVxT8N05D3,WkDfVxT8N06D3,WkDfVxT8N07D3,WkDfVxT8N08D3,WkDfVxT8N09D3,WkDfVxT8N10D3, & + WkDfVxT8N11D3,WkDfVxT8N12D3,WkDfVxT8N13D3,WkDfVxT8N14D3,WkDfVxT8N15D3,WkDfVxT8N16D3,WkDfVxT8N17D3,WkDfVxT8N18D3,WkDfVxT8N19D3,WkDfVxT8N20D3, & + WkDfVxT8N01D4,WkDfVxT8N02D4,WkDfVxT8N03D4,WkDfVxT8N04D4,WkDfVxT8N05D4,WkDfVxT8N06D4,WkDfVxT8N07D4,WkDfVxT8N08D4,WkDfVxT8N09D4,WkDfVxT8N10D4, & + WkDfVxT8N11D4,WkDfVxT8N12D4,WkDfVxT8N13D4,WkDfVxT8N14D4,WkDfVxT8N15D4,WkDfVxT8N16D4,WkDfVxT8N17D4,WkDfVxT8N18D4,WkDfVxT8N19D4,WkDfVxT8N20D4, & + WkDfVxT8N01D5,WkDfVxT8N02D5,WkDfVxT8N03D5,WkDfVxT8N04D5,WkDfVxT8N05D5,WkDfVxT8N06D5,WkDfVxT8N07D5,WkDfVxT8N08D5,WkDfVxT8N09D5,WkDfVxT8N10D5, & + WkDfVxT8N11D5,WkDfVxT8N12D5,WkDfVxT8N13D5,WkDfVxT8N14D5,WkDfVxT8N15D5,WkDfVxT8N16D5,WkDfVxT8N17D5,WkDfVxT8N18D5,WkDfVxT8N19D5,WkDfVxT8N20D5, & + WkDfVxT8N01D6,WkDfVxT8N02D6,WkDfVxT8N03D6,WkDfVxT8N04D6,WkDfVxT8N05D6,WkDfVxT8N06D6,WkDfVxT8N07D6,WkDfVxT8N08D6,WkDfVxT8N09D6,WkDfVxT8N10D6, & + WkDfVxT8N11D6,WkDfVxT8N12D6,WkDfVxT8N13D6,WkDfVxT8N14D6,WkDfVxT8N15D6,WkDfVxT8N16D6,WkDfVxT8N17D6,WkDfVxT8N18D6,WkDfVxT8N19D6,WkDfVxT8N20D6, & + WkDfVxT8N01D7,WkDfVxT8N02D7,WkDfVxT8N03D7,WkDfVxT8N04D7,WkDfVxT8N05D7,WkDfVxT8N06D7,WkDfVxT8N07D7,WkDfVxT8N08D7,WkDfVxT8N09D7,WkDfVxT8N10D7, & + WkDfVxT8N11D7,WkDfVxT8N12D7,WkDfVxT8N13D7,WkDfVxT8N14D7,WkDfVxT8N15D7,WkDfVxT8N16D7,WkDfVxT8N17D7,WkDfVxT8N18D7,WkDfVxT8N19D7,WkDfVxT8N20D7, & + WkDfVxT8N01D8,WkDfVxT8N02D8,WkDfVxT8N03D8,WkDfVxT8N04D8,WkDfVxT8N05D8,WkDfVxT8N06D8,WkDfVxT8N07D8,WkDfVxT8N08D8,WkDfVxT8N09D8,WkDfVxT8N10D8, & + WkDfVxT8N11D8,WkDfVxT8N12D8,WkDfVxT8N13D8,WkDfVxT8N14D8,WkDfVxT8N15D8,WkDfVxT8N16D8,WkDfVxT8N17D8,WkDfVxT8N18D8,WkDfVxT8N19D8,WkDfVxT8N20D8, & + WkDfVxT8N01D9,WkDfVxT8N02D9,WkDfVxT8N03D9,WkDfVxT8N04D9,WkDfVxT8N05D9,WkDfVxT8N06D9,WkDfVxT8N07D9,WkDfVxT8N08D9,WkDfVxT8N09D9,WkDfVxT8N10D9, & + WkDfVxT8N11D9,WkDfVxT8N12D9,WkDfVxT8N13D9,WkDfVxT8N14D9,WkDfVxT8N15D9,WkDfVxT8N16D9,WkDfVxT8N17D9,WkDfVxT8N18D9,WkDfVxT8N19D9,WkDfVxT8N20D9/), (/20,9/) ) + +WkDfVxTND(:,:,9) = RESHAPE( & + (/WkDfVxT9N01D1,WkDfVxT9N02D1,WkDfVxT9N03D1,WkDfVxT9N04D1,WkDfVxT9N05D1,WkDfVxT9N06D1,WkDfVxT9N07D1,WkDfVxT9N08D1,WkDfVxT9N09D1,WkDfVxT9N10D1, & + WkDfVxT9N11D1,WkDfVxT9N12D1,WkDfVxT9N13D1,WkDfVxT9N14D1,WkDfVxT9N15D1,WkDfVxT9N16D1,WkDfVxT9N17D1,WkDfVxT9N18D1,WkDfVxT9N19D1,WkDfVxT9N20D1, & + WkDfVxT9N01D2,WkDfVxT9N02D2,WkDfVxT9N03D2,WkDfVxT9N04D2,WkDfVxT9N05D2,WkDfVxT9N06D2,WkDfVxT9N07D2,WkDfVxT9N08D2,WkDfVxT9N09D2,WkDfVxT9N10D2, & + WkDfVxT9N11D2,WkDfVxT9N12D2,WkDfVxT9N13D2,WkDfVxT9N14D2,WkDfVxT9N15D2,WkDfVxT9N16D2,WkDfVxT9N17D2,WkDfVxT9N18D2,WkDfVxT9N19D2,WkDfVxT9N20D2, & + WkDfVxT9N01D3,WkDfVxT9N02D3,WkDfVxT9N03D3,WkDfVxT9N04D3,WkDfVxT9N05D3,WkDfVxT9N06D3,WkDfVxT9N07D3,WkDfVxT9N08D3,WkDfVxT9N09D3,WkDfVxT9N10D3, & + WkDfVxT9N11D3,WkDfVxT9N12D3,WkDfVxT9N13D3,WkDfVxT9N14D3,WkDfVxT9N15D3,WkDfVxT9N16D3,WkDfVxT9N17D3,WkDfVxT9N18D3,WkDfVxT9N19D3,WkDfVxT9N20D3, & + WkDfVxT9N01D4,WkDfVxT9N02D4,WkDfVxT9N03D4,WkDfVxT9N04D4,WkDfVxT9N05D4,WkDfVxT9N06D4,WkDfVxT9N07D4,WkDfVxT9N08D4,WkDfVxT9N09D4,WkDfVxT9N10D4, & + WkDfVxT9N11D4,WkDfVxT9N12D4,WkDfVxT9N13D4,WkDfVxT9N14D4,WkDfVxT9N15D4,WkDfVxT9N16D4,WkDfVxT9N17D4,WkDfVxT9N18D4,WkDfVxT9N19D4,WkDfVxT9N20D4, & + WkDfVxT9N01D5,WkDfVxT9N02D5,WkDfVxT9N03D5,WkDfVxT9N04D5,WkDfVxT9N05D5,WkDfVxT9N06D5,WkDfVxT9N07D5,WkDfVxT9N08D5,WkDfVxT9N09D5,WkDfVxT9N10D5, & + WkDfVxT9N11D5,WkDfVxT9N12D5,WkDfVxT9N13D5,WkDfVxT9N14D5,WkDfVxT9N15D5,WkDfVxT9N16D5,WkDfVxT9N17D5,WkDfVxT9N18D5,WkDfVxT9N19D5,WkDfVxT9N20D5, & + WkDfVxT9N01D6,WkDfVxT9N02D6,WkDfVxT9N03D6,WkDfVxT9N04D6,WkDfVxT9N05D6,WkDfVxT9N06D6,WkDfVxT9N07D6,WkDfVxT9N08D6,WkDfVxT9N09D6,WkDfVxT9N10D6, & + WkDfVxT9N11D6,WkDfVxT9N12D6,WkDfVxT9N13D6,WkDfVxT9N14D6,WkDfVxT9N15D6,WkDfVxT9N16D6,WkDfVxT9N17D6,WkDfVxT9N18D6,WkDfVxT9N19D6,WkDfVxT9N20D6, & + WkDfVxT9N01D7,WkDfVxT9N02D7,WkDfVxT9N03D7,WkDfVxT9N04D7,WkDfVxT9N05D7,WkDfVxT9N06D7,WkDfVxT9N07D7,WkDfVxT9N08D7,WkDfVxT9N09D7,WkDfVxT9N10D7, & + WkDfVxT9N11D7,WkDfVxT9N12D7,WkDfVxT9N13D7,WkDfVxT9N14D7,WkDfVxT9N15D7,WkDfVxT9N16D7,WkDfVxT9N17D7,WkDfVxT9N18D7,WkDfVxT9N19D7,WkDfVxT9N20D7, & + WkDfVxT9N01D8,WkDfVxT9N02D8,WkDfVxT9N03D8,WkDfVxT9N04D8,WkDfVxT9N05D8,WkDfVxT9N06D8,WkDfVxT9N07D8,WkDfVxT9N08D8,WkDfVxT9N09D8,WkDfVxT9N10D8, & + WkDfVxT9N11D8,WkDfVxT9N12D8,WkDfVxT9N13D8,WkDfVxT9N14D8,WkDfVxT9N15D8,WkDfVxT9N16D8,WkDfVxT9N17D8,WkDfVxT9N18D8,WkDfVxT9N19D8,WkDfVxT9N20D8, & + WkDfVxT9N01D9,WkDfVxT9N02D9,WkDfVxT9N03D9,WkDfVxT9N04D9,WkDfVxT9N05D9,WkDfVxT9N06D9,WkDfVxT9N07D9,WkDfVxT9N08D9,WkDfVxT9N09D9,WkDfVxT9N10D9, & + WkDfVxT9N11D9,WkDfVxT9N12D9,WkDfVxT9N13D9,WkDfVxT9N14D9,WkDfVxT9N15D9,WkDfVxT9N16D9,WkDfVxT9N17D9,WkDfVxT9N18D9,WkDfVxT9N19D9,WkDfVxT9N20D9/), (/20,9/) ) + + +WkDfVrTND(:,:,1) = RESHAPE( & + (/WkDfVrT1N01D1,WkDfVrT1N02D1,WkDfVrT1N03D1,WkDfVrT1N04D1,WkDfVrT1N05D1,WkDfVrT1N06D1,WkDfVrT1N07D1,WkDfVrT1N08D1,WkDfVrT1N09D1,WkDfVrT1N10D1, & + WkDfVrT1N11D1,WkDfVrT1N12D1,WkDfVrT1N13D1,WkDfVrT1N14D1,WkDfVrT1N15D1,WkDfVrT1N16D1,WkDfVrT1N17D1,WkDfVrT1N18D1,WkDfVrT1N19D1,WkDfVrT1N20D1, & + WkDfVrT1N01D2,WkDfVrT1N02D2,WkDfVrT1N03D2,WkDfVrT1N04D2,WkDfVrT1N05D2,WkDfVrT1N06D2,WkDfVrT1N07D2,WkDfVrT1N08D2,WkDfVrT1N09D2,WkDfVrT1N10D2, & + WkDfVrT1N11D2,WkDfVrT1N12D2,WkDfVrT1N13D2,WkDfVrT1N14D2,WkDfVrT1N15D2,WkDfVrT1N16D2,WkDfVrT1N17D2,WkDfVrT1N18D2,WkDfVrT1N19D2,WkDfVrT1N20D2, & + WkDfVrT1N01D3,WkDfVrT1N02D3,WkDfVrT1N03D3,WkDfVrT1N04D3,WkDfVrT1N05D3,WkDfVrT1N06D3,WkDfVrT1N07D3,WkDfVrT1N08D3,WkDfVrT1N09D3,WkDfVrT1N10D3, & + WkDfVrT1N11D3,WkDfVrT1N12D3,WkDfVrT1N13D3,WkDfVrT1N14D3,WkDfVrT1N15D3,WkDfVrT1N16D3,WkDfVrT1N17D3,WkDfVrT1N18D3,WkDfVrT1N19D3,WkDfVrT1N20D3, & + WkDfVrT1N01D4,WkDfVrT1N02D4,WkDfVrT1N03D4,WkDfVrT1N04D4,WkDfVrT1N05D4,WkDfVrT1N06D4,WkDfVrT1N07D4,WkDfVrT1N08D4,WkDfVrT1N09D4,WkDfVrT1N10D4, & + WkDfVrT1N11D4,WkDfVrT1N12D4,WkDfVrT1N13D4,WkDfVrT1N14D4,WkDfVrT1N15D4,WkDfVrT1N16D4,WkDfVrT1N17D4,WkDfVrT1N18D4,WkDfVrT1N19D4,WkDfVrT1N20D4, & + WkDfVrT1N01D5,WkDfVrT1N02D5,WkDfVrT1N03D5,WkDfVrT1N04D5,WkDfVrT1N05D5,WkDfVrT1N06D5,WkDfVrT1N07D5,WkDfVrT1N08D5,WkDfVrT1N09D5,WkDfVrT1N10D5, & + WkDfVrT1N11D5,WkDfVrT1N12D5,WkDfVrT1N13D5,WkDfVrT1N14D5,WkDfVrT1N15D5,WkDfVrT1N16D5,WkDfVrT1N17D5,WkDfVrT1N18D5,WkDfVrT1N19D5,WkDfVrT1N20D5, & + WkDfVrT1N01D6,WkDfVrT1N02D6,WkDfVrT1N03D6,WkDfVrT1N04D6,WkDfVrT1N05D6,WkDfVrT1N06D6,WkDfVrT1N07D6,WkDfVrT1N08D6,WkDfVrT1N09D6,WkDfVrT1N10D6, & + WkDfVrT1N11D6,WkDfVrT1N12D6,WkDfVrT1N13D6,WkDfVrT1N14D6,WkDfVrT1N15D6,WkDfVrT1N16D6,WkDfVrT1N17D6,WkDfVrT1N18D6,WkDfVrT1N19D6,WkDfVrT1N20D6, & + WkDfVrT1N01D7,WkDfVrT1N02D7,WkDfVrT1N03D7,WkDfVrT1N04D7,WkDfVrT1N05D7,WkDfVrT1N06D7,WkDfVrT1N07D7,WkDfVrT1N08D7,WkDfVrT1N09D7,WkDfVrT1N10D7, & + WkDfVrT1N11D7,WkDfVrT1N12D7,WkDfVrT1N13D7,WkDfVrT1N14D7,WkDfVrT1N15D7,WkDfVrT1N16D7,WkDfVrT1N17D7,WkDfVrT1N18D7,WkDfVrT1N19D7,WkDfVrT1N20D7, & + WkDfVrT1N01D8,WkDfVrT1N02D8,WkDfVrT1N03D8,WkDfVrT1N04D8,WkDfVrT1N05D8,WkDfVrT1N06D8,WkDfVrT1N07D8,WkDfVrT1N08D8,WkDfVrT1N09D8,WkDfVrT1N10D8, & + WkDfVrT1N11D8,WkDfVrT1N12D8,WkDfVrT1N13D8,WkDfVrT1N14D8,WkDfVrT1N15D8,WkDfVrT1N16D8,WkDfVrT1N17D8,WkDfVrT1N18D8,WkDfVrT1N19D8,WkDfVrT1N20D8, & + WkDfVrT1N01D9,WkDfVrT1N02D9,WkDfVrT1N03D9,WkDfVrT1N04D9,WkDfVrT1N05D9,WkDfVrT1N06D9,WkDfVrT1N07D9,WkDfVrT1N08D9,WkDfVrT1N09D9,WkDfVrT1N10D9, & + WkDfVrT1N11D9,WkDfVrT1N12D9,WkDfVrT1N13D9,WkDfVrT1N14D9,WkDfVrT1N15D9,WkDfVrT1N16D9,WkDfVrT1N17D9,WkDfVrT1N18D9,WkDfVrT1N19D9,WkDfVrT1N20D9/), (/20,9/) ) +WkDfVrTND(:,:,2) = RESHAPE( & + (/WkDfVrT2N01D1,WkDfVrT2N02D1,WkDfVrT2N03D1,WkDfVrT2N04D1,WkDfVrT2N05D1,WkDfVrT2N06D1,WkDfVrT2N07D1,WkDfVrT2N08D1,WkDfVrT2N09D1,WkDfVrT2N10D1, & + WkDfVrT2N11D1,WkDfVrT2N12D1,WkDfVrT2N13D1,WkDfVrT2N14D1,WkDfVrT2N15D1,WkDfVrT2N16D1,WkDfVrT2N17D1,WkDfVrT2N18D1,WkDfVrT2N19D1,WkDfVrT2N20D1, & + WkDfVrT2N01D2,WkDfVrT2N02D2,WkDfVrT2N03D2,WkDfVrT2N04D2,WkDfVrT2N05D2,WkDfVrT2N06D2,WkDfVrT2N07D2,WkDfVrT2N08D2,WkDfVrT2N09D2,WkDfVrT2N10D2, & + WkDfVrT2N11D2,WkDfVrT2N12D2,WkDfVrT2N13D2,WkDfVrT2N14D2,WkDfVrT2N15D2,WkDfVrT2N16D2,WkDfVrT2N17D2,WkDfVrT2N18D2,WkDfVrT2N19D2,WkDfVrT2N20D2, & + WkDfVrT2N01D3,WkDfVrT2N02D3,WkDfVrT2N03D3,WkDfVrT2N04D3,WkDfVrT2N05D3,WkDfVrT2N06D3,WkDfVrT2N07D3,WkDfVrT2N08D3,WkDfVrT2N09D3,WkDfVrT2N10D3, & + WkDfVrT2N11D3,WkDfVrT2N12D3,WkDfVrT2N13D3,WkDfVrT2N14D3,WkDfVrT2N15D3,WkDfVrT2N16D3,WkDfVrT2N17D3,WkDfVrT2N18D3,WkDfVrT2N19D3,WkDfVrT2N20D3, & + WkDfVrT2N01D4,WkDfVrT2N02D4,WkDfVrT2N03D4,WkDfVrT2N04D4,WkDfVrT2N05D4,WkDfVrT2N06D4,WkDfVrT2N07D4,WkDfVrT2N08D4,WkDfVrT2N09D4,WkDfVrT2N10D4, & + WkDfVrT2N11D4,WkDfVrT2N12D4,WkDfVrT2N13D4,WkDfVrT2N14D4,WkDfVrT2N15D4,WkDfVrT2N16D4,WkDfVrT2N17D4,WkDfVrT2N18D4,WkDfVrT2N19D4,WkDfVrT2N20D4, & + WkDfVrT2N01D5,WkDfVrT2N02D5,WkDfVrT2N03D5,WkDfVrT2N04D5,WkDfVrT2N05D5,WkDfVrT2N06D5,WkDfVrT2N07D5,WkDfVrT2N08D5,WkDfVrT2N09D5,WkDfVrT2N10D5, & + WkDfVrT2N11D5,WkDfVrT2N12D5,WkDfVrT2N13D5,WkDfVrT2N14D5,WkDfVrT2N15D5,WkDfVrT2N16D5,WkDfVrT2N17D5,WkDfVrT2N18D5,WkDfVrT2N19D5,WkDfVrT2N20D5, & + WkDfVrT2N01D6,WkDfVrT2N02D6,WkDfVrT2N03D6,WkDfVrT2N04D6,WkDfVrT2N05D6,WkDfVrT2N06D6,WkDfVrT2N07D6,WkDfVrT2N08D6,WkDfVrT2N09D6,WkDfVrT2N10D6, & + WkDfVrT2N11D6,WkDfVrT2N12D6,WkDfVrT2N13D6,WkDfVrT2N14D6,WkDfVrT2N15D6,WkDfVrT2N16D6,WkDfVrT2N17D6,WkDfVrT2N18D6,WkDfVrT2N19D6,WkDfVrT2N20D6, & + WkDfVrT2N01D7,WkDfVrT2N02D7,WkDfVrT2N03D7,WkDfVrT2N04D7,WkDfVrT2N05D7,WkDfVrT2N06D7,WkDfVrT2N07D7,WkDfVrT2N08D7,WkDfVrT2N09D7,WkDfVrT2N10D7, & + WkDfVrT2N11D7,WkDfVrT2N12D7,WkDfVrT2N13D7,WkDfVrT2N14D7,WkDfVrT2N15D7,WkDfVrT2N16D7,WkDfVrT2N17D7,WkDfVrT2N18D7,WkDfVrT2N19D7,WkDfVrT2N20D7, & + WkDfVrT2N01D8,WkDfVrT2N02D8,WkDfVrT2N03D8,WkDfVrT2N04D8,WkDfVrT2N05D8,WkDfVrT2N06D8,WkDfVrT2N07D8,WkDfVrT2N08D8,WkDfVrT2N09D8,WkDfVrT2N10D8, & + WkDfVrT2N11D8,WkDfVrT2N12D8,WkDfVrT2N13D8,WkDfVrT2N14D8,WkDfVrT2N15D8,WkDfVrT2N16D8,WkDfVrT2N17D8,WkDfVrT2N18D8,WkDfVrT2N19D8,WkDfVrT2N20D8, & + WkDfVrT2N01D9,WkDfVrT2N02D9,WkDfVrT2N03D9,WkDfVrT2N04D9,WkDfVrT2N05D9,WkDfVrT2N06D9,WkDfVrT2N07D9,WkDfVrT2N08D9,WkDfVrT2N09D9,WkDfVrT2N10D9, & + WkDfVrT2N11D9,WkDfVrT2N12D9,WkDfVrT2N13D9,WkDfVrT2N14D9,WkDfVrT2N15D9,WkDfVrT2N16D9,WkDfVrT2N17D9,WkDfVrT2N18D9,WkDfVrT2N19D9,WkDfVrT2N20D9/), (/20,9/) ) +WkDfVrTND(:,:,3) = RESHAPE( & + (/WkDfVrT3N01D1,WkDfVrT3N02D1,WkDfVrT3N03D1,WkDfVrT3N04D1,WkDfVrT3N05D1,WkDfVrT3N06D1,WkDfVrT3N07D1,WkDfVrT3N08D1,WkDfVrT3N09D1,WkDfVrT3N10D1, & + WkDfVrT3N11D1,WkDfVrT3N12D1,WkDfVrT3N13D1,WkDfVrT3N14D1,WkDfVrT3N15D1,WkDfVrT3N16D1,WkDfVrT3N17D1,WkDfVrT3N18D1,WkDfVrT3N19D1,WkDfVrT3N20D1, & + WkDfVrT3N01D2,WkDfVrT3N02D2,WkDfVrT3N03D2,WkDfVrT3N04D2,WkDfVrT3N05D2,WkDfVrT3N06D2,WkDfVrT3N07D2,WkDfVrT3N08D2,WkDfVrT3N09D2,WkDfVrT3N10D2, & + WkDfVrT3N11D2,WkDfVrT3N12D2,WkDfVrT3N13D2,WkDfVrT3N14D2,WkDfVrT3N15D2,WkDfVrT3N16D2,WkDfVrT3N17D2,WkDfVrT3N18D2,WkDfVrT3N19D2,WkDfVrT3N20D2, & + WkDfVrT3N01D3,WkDfVrT3N02D3,WkDfVrT3N03D3,WkDfVrT3N04D3,WkDfVrT3N05D3,WkDfVrT3N06D3,WkDfVrT3N07D3,WkDfVrT3N08D3,WkDfVrT3N09D3,WkDfVrT3N10D3, & + WkDfVrT3N11D3,WkDfVrT3N12D3,WkDfVrT3N13D3,WkDfVrT3N14D3,WkDfVrT3N15D3,WkDfVrT3N16D3,WkDfVrT3N17D3,WkDfVrT3N18D3,WkDfVrT3N19D3,WkDfVrT3N20D3, & + WkDfVrT3N01D4,WkDfVrT3N02D4,WkDfVrT3N03D4,WkDfVrT3N04D4,WkDfVrT3N05D4,WkDfVrT3N06D4,WkDfVrT3N07D4,WkDfVrT3N08D4,WkDfVrT3N09D4,WkDfVrT3N10D4, & + WkDfVrT3N11D4,WkDfVrT3N12D4,WkDfVrT3N13D4,WkDfVrT3N14D4,WkDfVrT3N15D4,WkDfVrT3N16D4,WkDfVrT3N17D4,WkDfVrT3N18D4,WkDfVrT3N19D4,WkDfVrT3N20D4, & + WkDfVrT3N01D5,WkDfVrT3N02D5,WkDfVrT3N03D5,WkDfVrT3N04D5,WkDfVrT3N05D5,WkDfVrT3N06D5,WkDfVrT3N07D5,WkDfVrT3N08D5,WkDfVrT3N09D5,WkDfVrT3N10D5, & + WkDfVrT3N11D5,WkDfVrT3N12D5,WkDfVrT3N13D5,WkDfVrT3N14D5,WkDfVrT3N15D5,WkDfVrT3N16D5,WkDfVrT3N17D5,WkDfVrT3N18D5,WkDfVrT3N19D5,WkDfVrT3N20D5, & + WkDfVrT3N01D6,WkDfVrT3N02D6,WkDfVrT3N03D6,WkDfVrT3N04D6,WkDfVrT3N05D6,WkDfVrT3N06D6,WkDfVrT3N07D6,WkDfVrT3N08D6,WkDfVrT3N09D6,WkDfVrT3N10D6, & + WkDfVrT3N11D6,WkDfVrT3N12D6,WkDfVrT3N13D6,WkDfVrT3N14D6,WkDfVrT3N15D6,WkDfVrT3N16D6,WkDfVrT3N17D6,WkDfVrT3N18D6,WkDfVrT3N19D6,WkDfVrT3N20D6, & + WkDfVrT3N01D7,WkDfVrT3N02D7,WkDfVrT3N03D7,WkDfVrT3N04D7,WkDfVrT3N05D7,WkDfVrT3N06D7,WkDfVrT3N07D7,WkDfVrT3N08D7,WkDfVrT3N09D7,WkDfVrT3N10D7, & + WkDfVrT3N11D7,WkDfVrT3N12D7,WkDfVrT3N13D7,WkDfVrT3N14D7,WkDfVrT3N15D7,WkDfVrT3N16D7,WkDfVrT3N17D7,WkDfVrT3N18D7,WkDfVrT3N19D7,WkDfVrT3N20D7, & + WkDfVrT3N01D8,WkDfVrT3N02D8,WkDfVrT3N03D8,WkDfVrT3N04D8,WkDfVrT3N05D8,WkDfVrT3N06D8,WkDfVrT3N07D8,WkDfVrT3N08D8,WkDfVrT3N09D8,WkDfVrT3N10D8, & + WkDfVrT3N11D8,WkDfVrT3N12D8,WkDfVrT3N13D8,WkDfVrT3N14D8,WkDfVrT3N15D8,WkDfVrT3N16D8,WkDfVrT3N17D8,WkDfVrT3N18D8,WkDfVrT3N19D8,WkDfVrT3N20D8, & + WkDfVrT3N01D9,WkDfVrT3N02D9,WkDfVrT3N03D9,WkDfVrT3N04D9,WkDfVrT3N05D9,WkDfVrT3N06D9,WkDfVrT3N07D9,WkDfVrT3N08D9,WkDfVrT3N09D9,WkDfVrT3N10D9, & + WkDfVrT3N11D9,WkDfVrT3N12D9,WkDfVrT3N13D9,WkDfVrT3N14D9,WkDfVrT3N15D9,WkDfVrT3N16D9,WkDfVrT3N17D9,WkDfVrT3N18D9,WkDfVrT3N19D9,WkDfVrT3N20D9/), (/20,9/) ) +WkDfVrTND(:,:,4) = RESHAPE( & + (/WkDfVrT4N01D1,WkDfVrT4N02D1,WkDfVrT4N03D1,WkDfVrT4N04D1,WkDfVrT4N05D1,WkDfVrT4N06D1,WkDfVrT4N07D1,WkDfVrT4N08D1,WkDfVrT4N09D1,WkDfVrT4N10D1, & + WkDfVrT4N11D1,WkDfVrT4N12D1,WkDfVrT4N13D1,WkDfVrT4N14D1,WkDfVrT4N15D1,WkDfVrT4N16D1,WkDfVrT4N17D1,WkDfVrT4N18D1,WkDfVrT4N19D1,WkDfVrT4N20D1, & + WkDfVrT4N01D2,WkDfVrT4N02D2,WkDfVrT4N03D2,WkDfVrT4N04D2,WkDfVrT4N05D2,WkDfVrT4N06D2,WkDfVrT4N07D2,WkDfVrT4N08D2,WkDfVrT4N09D2,WkDfVrT4N10D2, & + WkDfVrT4N11D2,WkDfVrT4N12D2,WkDfVrT4N13D2,WkDfVrT4N14D2,WkDfVrT4N15D2,WkDfVrT4N16D2,WkDfVrT4N17D2,WkDfVrT4N18D2,WkDfVrT4N19D2,WkDfVrT4N20D2, & + WkDfVrT4N01D3,WkDfVrT4N02D3,WkDfVrT4N03D3,WkDfVrT4N04D3,WkDfVrT4N05D3,WkDfVrT4N06D3,WkDfVrT4N07D3,WkDfVrT4N08D3,WkDfVrT4N09D3,WkDfVrT4N10D3, & + WkDfVrT4N11D3,WkDfVrT4N12D3,WkDfVrT4N13D3,WkDfVrT4N14D3,WkDfVrT4N15D3,WkDfVrT4N16D3,WkDfVrT4N17D3,WkDfVrT4N18D3,WkDfVrT4N19D3,WkDfVrT4N20D3, & + WkDfVrT4N01D4,WkDfVrT4N02D4,WkDfVrT4N03D4,WkDfVrT4N04D4,WkDfVrT4N05D4,WkDfVrT4N06D4,WkDfVrT4N07D4,WkDfVrT4N08D4,WkDfVrT4N09D4,WkDfVrT4N10D4, & + WkDfVrT4N11D4,WkDfVrT4N12D4,WkDfVrT4N13D4,WkDfVrT4N14D4,WkDfVrT4N15D4,WkDfVrT4N16D4,WkDfVrT4N17D4,WkDfVrT4N18D4,WkDfVrT4N19D4,WkDfVrT4N20D4, & + WkDfVrT4N01D5,WkDfVrT4N02D5,WkDfVrT4N03D5,WkDfVrT4N04D5,WkDfVrT4N05D5,WkDfVrT4N06D5,WkDfVrT4N07D5,WkDfVrT4N08D5,WkDfVrT4N09D5,WkDfVrT4N10D5, & + WkDfVrT4N11D5,WkDfVrT4N12D5,WkDfVrT4N13D5,WkDfVrT4N14D5,WkDfVrT4N15D5,WkDfVrT4N16D5,WkDfVrT4N17D5,WkDfVrT4N18D5,WkDfVrT4N19D5,WkDfVrT4N20D5, & + WkDfVrT4N01D6,WkDfVrT4N02D6,WkDfVrT4N03D6,WkDfVrT4N04D6,WkDfVrT4N05D6,WkDfVrT4N06D6,WkDfVrT4N07D6,WkDfVrT4N08D6,WkDfVrT4N09D6,WkDfVrT4N10D6, & + WkDfVrT4N11D6,WkDfVrT4N12D6,WkDfVrT4N13D6,WkDfVrT4N14D6,WkDfVrT4N15D6,WkDfVrT4N16D6,WkDfVrT4N17D6,WkDfVrT4N18D6,WkDfVrT4N19D6,WkDfVrT4N20D6, & + WkDfVrT4N01D7,WkDfVrT4N02D7,WkDfVrT4N03D7,WkDfVrT4N04D7,WkDfVrT4N05D7,WkDfVrT4N06D7,WkDfVrT4N07D7,WkDfVrT4N08D7,WkDfVrT4N09D7,WkDfVrT4N10D7, & + WkDfVrT4N11D7,WkDfVrT4N12D7,WkDfVrT4N13D7,WkDfVrT4N14D7,WkDfVrT4N15D7,WkDfVrT4N16D7,WkDfVrT4N17D7,WkDfVrT4N18D7,WkDfVrT4N19D7,WkDfVrT4N20D7, & + WkDfVrT4N01D8,WkDfVrT4N02D8,WkDfVrT4N03D8,WkDfVrT4N04D8,WkDfVrT4N05D8,WkDfVrT4N06D8,WkDfVrT4N07D8,WkDfVrT4N08D8,WkDfVrT4N09D8,WkDfVrT4N10D8, & + WkDfVrT4N11D8,WkDfVrT4N12D8,WkDfVrT4N13D8,WkDfVrT4N14D8,WkDfVrT4N15D8,WkDfVrT4N16D8,WkDfVrT4N17D8,WkDfVrT4N18D8,WkDfVrT4N19D8,WkDfVrT4N20D8, & + WkDfVrT4N01D9,WkDfVrT4N02D9,WkDfVrT4N03D9,WkDfVrT4N04D9,WkDfVrT4N05D9,WkDfVrT4N06D9,WkDfVrT4N07D9,WkDfVrT4N08D9,WkDfVrT4N09D9,WkDfVrT4N10D9, & + WkDfVrT4N11D9,WkDfVrT4N12D9,WkDfVrT4N13D9,WkDfVrT4N14D9,WkDfVrT4N15D9,WkDfVrT4N16D9,WkDfVrT4N17D9,WkDfVrT4N18D9,WkDfVrT4N19D9,WkDfVrT4N20D9/), (/20,9/) ) + +WkDfVrTND(:,:,5) = RESHAPE( & + (/WkDfVrT5N01D1,WkDfVrT5N02D1,WkDfVrT5N03D1,WkDfVrT5N04D1,WkDfVrT5N05D1,WkDfVrT5N06D1,WkDfVrT5N07D1,WkDfVrT5N08D1,WkDfVrT5N09D1,WkDfVrT5N10D1, & + WkDfVrT5N11D1,WkDfVrT5N12D1,WkDfVrT5N13D1,WkDfVrT5N14D1,WkDfVrT5N15D1,WkDfVrT5N16D1,WkDfVrT5N17D1,WkDfVrT5N18D1,WkDfVrT5N19D1,WkDfVrT5N20D1, & + WkDfVrT5N01D2,WkDfVrT5N02D2,WkDfVrT5N03D2,WkDfVrT5N04D2,WkDfVrT5N05D2,WkDfVrT5N06D2,WkDfVrT5N07D2,WkDfVrT5N08D2,WkDfVrT5N09D2,WkDfVrT5N10D2, & + WkDfVrT5N11D2,WkDfVrT5N12D2,WkDfVrT5N13D2,WkDfVrT5N14D2,WkDfVrT5N15D2,WkDfVrT5N16D2,WkDfVrT5N17D2,WkDfVrT5N18D2,WkDfVrT5N19D2,WkDfVrT5N20D2, & + WkDfVrT5N01D3,WkDfVrT5N02D3,WkDfVrT5N03D3,WkDfVrT5N04D3,WkDfVrT5N05D3,WkDfVrT5N06D3,WkDfVrT5N07D3,WkDfVrT5N08D3,WkDfVrT5N09D3,WkDfVrT5N10D3, & + WkDfVrT5N11D3,WkDfVrT5N12D3,WkDfVrT5N13D3,WkDfVrT5N14D3,WkDfVrT5N15D3,WkDfVrT5N16D3,WkDfVrT5N17D3,WkDfVrT5N18D3,WkDfVrT5N19D3,WkDfVrT5N20D3, & + WkDfVrT5N01D4,WkDfVrT5N02D4,WkDfVrT5N03D4,WkDfVrT5N04D4,WkDfVrT5N05D4,WkDfVrT5N06D4,WkDfVrT5N07D4,WkDfVrT5N08D4,WkDfVrT5N09D4,WkDfVrT5N10D4, & + WkDfVrT5N11D4,WkDfVrT5N12D4,WkDfVrT5N13D4,WkDfVrT5N14D4,WkDfVrT5N15D4,WkDfVrT5N16D4,WkDfVrT5N17D4,WkDfVrT5N18D4,WkDfVrT5N19D4,WkDfVrT5N20D4, & + WkDfVrT5N01D5,WkDfVrT5N02D5,WkDfVrT5N03D5,WkDfVrT5N04D5,WkDfVrT5N05D5,WkDfVrT5N06D5,WkDfVrT5N07D5,WkDfVrT5N08D5,WkDfVrT5N09D5,WkDfVrT5N10D5, & + WkDfVrT5N11D5,WkDfVrT5N12D5,WkDfVrT5N13D5,WkDfVrT5N14D5,WkDfVrT5N15D5,WkDfVrT5N16D5,WkDfVrT5N17D5,WkDfVrT5N18D5,WkDfVrT5N19D5,WkDfVrT5N20D5, & + WkDfVrT5N01D6,WkDfVrT5N02D6,WkDfVrT5N03D6,WkDfVrT5N04D6,WkDfVrT5N05D6,WkDfVrT5N06D6,WkDfVrT5N07D6,WkDfVrT5N08D6,WkDfVrT5N09D6,WkDfVrT5N10D6, & + WkDfVrT5N11D6,WkDfVrT5N12D6,WkDfVrT5N13D6,WkDfVrT5N14D6,WkDfVrT5N15D6,WkDfVrT5N16D6,WkDfVrT5N17D6,WkDfVrT5N18D6,WkDfVrT5N19D6,WkDfVrT5N20D6, & + WkDfVrT5N01D7,WkDfVrT5N02D7,WkDfVrT5N03D7,WkDfVrT5N04D7,WkDfVrT5N05D7,WkDfVrT5N06D7,WkDfVrT5N07D7,WkDfVrT5N08D7,WkDfVrT5N09D7,WkDfVrT5N10D7, & + WkDfVrT5N11D7,WkDfVrT5N12D7,WkDfVrT5N13D7,WkDfVrT5N14D7,WkDfVrT5N15D7,WkDfVrT5N16D7,WkDfVrT5N17D7,WkDfVrT5N18D7,WkDfVrT5N19D7,WkDfVrT5N20D7, & + WkDfVrT5N01D8,WkDfVrT5N02D8,WkDfVrT5N03D8,WkDfVrT5N04D8,WkDfVrT5N05D8,WkDfVrT5N06D8,WkDfVrT5N07D8,WkDfVrT5N08D8,WkDfVrT5N09D8,WkDfVrT5N10D8, & + WkDfVrT5N11D8,WkDfVrT5N12D8,WkDfVrT5N13D8,WkDfVrT5N14D8,WkDfVrT5N15D8,WkDfVrT5N16D8,WkDfVrT5N17D8,WkDfVrT5N18D8,WkDfVrT5N19D8,WkDfVrT5N20D8, & + WkDfVrT5N01D9,WkDfVrT5N02D9,WkDfVrT5N03D9,WkDfVrT5N04D9,WkDfVrT5N05D9,WkDfVrT5N06D9,WkDfVrT5N07D9,WkDfVrT5N08D9,WkDfVrT5N09D9,WkDfVrT5N10D9, & + WkDfVrT5N11D9,WkDfVrT5N12D9,WkDfVrT5N13D9,WkDfVrT5N14D9,WkDfVrT5N15D9,WkDfVrT5N16D9,WkDfVrT5N17D9,WkDfVrT5N18D9,WkDfVrT5N19D9,WkDfVrT5N20D9/), (/20,9/) ) +WkDfVrTND(:,:,6) = RESHAPE( & + (/WkDfVrT6N01D1,WkDfVrT6N02D1,WkDfVrT6N03D1,WkDfVrT6N04D1,WkDfVrT6N05D1,WkDfVrT6N06D1,WkDfVrT6N07D1,WkDfVrT6N08D1,WkDfVrT6N09D1,WkDfVrT6N10D1, & + WkDfVrT6N11D1,WkDfVrT6N12D1,WkDfVrT6N13D1,WkDfVrT6N14D1,WkDfVrT6N15D1,WkDfVrT6N16D1,WkDfVrT6N17D1,WkDfVrT6N18D1,WkDfVrT6N19D1,WkDfVrT6N20D1, & + WkDfVrT6N01D2,WkDfVrT6N02D2,WkDfVrT6N03D2,WkDfVrT6N04D2,WkDfVrT6N05D2,WkDfVrT6N06D2,WkDfVrT6N07D2,WkDfVrT6N08D2,WkDfVrT6N09D2,WkDfVrT6N10D2, & + WkDfVrT6N11D2,WkDfVrT6N12D2,WkDfVrT6N13D2,WkDfVrT6N14D2,WkDfVrT6N15D2,WkDfVrT6N16D2,WkDfVrT6N17D2,WkDfVrT6N18D2,WkDfVrT6N19D2,WkDfVrT6N20D2, & + WkDfVrT6N01D3,WkDfVrT6N02D3,WkDfVrT6N03D3,WkDfVrT6N04D3,WkDfVrT6N05D3,WkDfVrT6N06D3,WkDfVrT6N07D3,WkDfVrT6N08D3,WkDfVrT6N09D3,WkDfVrT6N10D3, & + WkDfVrT6N11D3,WkDfVrT6N12D3,WkDfVrT6N13D3,WkDfVrT6N14D3,WkDfVrT6N15D3,WkDfVrT6N16D3,WkDfVrT6N17D3,WkDfVrT6N18D3,WkDfVrT6N19D3,WkDfVrT6N20D3, & + WkDfVrT6N01D4,WkDfVrT6N02D4,WkDfVrT6N03D4,WkDfVrT6N04D4,WkDfVrT6N05D4,WkDfVrT6N06D4,WkDfVrT6N07D4,WkDfVrT6N08D4,WkDfVrT6N09D4,WkDfVrT6N10D4, & + WkDfVrT6N11D4,WkDfVrT6N12D4,WkDfVrT6N13D4,WkDfVrT6N14D4,WkDfVrT6N15D4,WkDfVrT6N16D4,WkDfVrT6N17D4,WkDfVrT6N18D4,WkDfVrT6N19D4,WkDfVrT6N20D4, & + WkDfVrT6N01D5,WkDfVrT6N02D5,WkDfVrT6N03D5,WkDfVrT6N04D5,WkDfVrT6N05D5,WkDfVrT6N06D5,WkDfVrT6N07D5,WkDfVrT6N08D5,WkDfVrT6N09D5,WkDfVrT6N10D5, & + WkDfVrT6N11D5,WkDfVrT6N12D5,WkDfVrT6N13D5,WkDfVrT6N14D5,WkDfVrT6N15D5,WkDfVrT6N16D5,WkDfVrT6N17D5,WkDfVrT6N18D5,WkDfVrT6N19D5,WkDfVrT6N20D5, & + WkDfVrT6N01D6,WkDfVrT6N02D6,WkDfVrT6N03D6,WkDfVrT6N04D6,WkDfVrT6N05D6,WkDfVrT6N06D6,WkDfVrT6N07D6,WkDfVrT6N08D6,WkDfVrT6N09D6,WkDfVrT6N10D6, & + WkDfVrT6N11D6,WkDfVrT6N12D6,WkDfVrT6N13D6,WkDfVrT6N14D6,WkDfVrT6N15D6,WkDfVrT6N16D6,WkDfVrT6N17D6,WkDfVrT6N18D6,WkDfVrT6N19D6,WkDfVrT6N20D6, & + WkDfVrT6N01D7,WkDfVrT6N02D7,WkDfVrT6N03D7,WkDfVrT6N04D7,WkDfVrT6N05D7,WkDfVrT6N06D7,WkDfVrT6N07D7,WkDfVrT6N08D7,WkDfVrT6N09D7,WkDfVrT6N10D7, & + WkDfVrT6N11D7,WkDfVrT6N12D7,WkDfVrT6N13D7,WkDfVrT6N14D7,WkDfVrT6N15D7,WkDfVrT6N16D7,WkDfVrT6N17D7,WkDfVrT6N18D7,WkDfVrT6N19D7,WkDfVrT6N20D7, & + WkDfVrT6N01D8,WkDfVrT6N02D8,WkDfVrT6N03D8,WkDfVrT6N04D8,WkDfVrT6N05D8,WkDfVrT6N06D8,WkDfVrT6N07D8,WkDfVrT6N08D8,WkDfVrT6N09D8,WkDfVrT6N10D8, & + WkDfVrT6N11D8,WkDfVrT6N12D8,WkDfVrT6N13D8,WkDfVrT6N14D8,WkDfVrT6N15D8,WkDfVrT6N16D8,WkDfVrT6N17D8,WkDfVrT6N18D8,WkDfVrT6N19D8,WkDfVrT6N20D8, & + WkDfVrT6N01D9,WkDfVrT6N02D9,WkDfVrT6N03D9,WkDfVrT6N04D9,WkDfVrT6N05D9,WkDfVrT6N06D9,WkDfVrT6N07D9,WkDfVrT6N08D9,WkDfVrT6N09D9,WkDfVrT6N10D9, & + WkDfVrT6N11D9,WkDfVrT6N12D9,WkDfVrT6N13D9,WkDfVrT6N14D9,WkDfVrT6N15D9,WkDfVrT6N16D9,WkDfVrT6N17D9,WkDfVrT6N18D9,WkDfVrT6N19D9,WkDfVrT6N20D9/), (/20,9/) ) +WkDfVrTND(:,:,7) = RESHAPE( & + (/WkDfVrT7N01D1,WkDfVrT7N02D1,WkDfVrT7N03D1,WkDfVrT7N04D1,WkDfVrT7N05D1,WkDfVrT7N06D1,WkDfVrT7N07D1,WkDfVrT7N08D1,WkDfVrT7N09D1,WkDfVrT7N10D1, & + WkDfVrT7N11D1,WkDfVrT7N12D1,WkDfVrT7N13D1,WkDfVrT7N14D1,WkDfVrT7N15D1,WkDfVrT7N16D1,WkDfVrT7N17D1,WkDfVrT7N18D1,WkDfVrT7N19D1,WkDfVrT7N20D1, & + WkDfVrT7N01D2,WkDfVrT7N02D2,WkDfVrT7N03D2,WkDfVrT7N04D2,WkDfVrT7N05D2,WkDfVrT7N06D2,WkDfVrT7N07D2,WkDfVrT7N08D2,WkDfVrT7N09D2,WkDfVrT7N10D2, & + WkDfVrT7N11D2,WkDfVrT7N12D2,WkDfVrT7N13D2,WkDfVrT7N14D2,WkDfVrT7N15D2,WkDfVrT7N16D2,WkDfVrT7N17D2,WkDfVrT7N18D2,WkDfVrT7N19D2,WkDfVrT7N20D2, & + WkDfVrT7N01D3,WkDfVrT7N02D3,WkDfVrT7N03D3,WkDfVrT7N04D3,WkDfVrT7N05D3,WkDfVrT7N06D3,WkDfVrT7N07D3,WkDfVrT7N08D3,WkDfVrT7N09D3,WkDfVrT7N10D3, & + WkDfVrT7N11D3,WkDfVrT7N12D3,WkDfVrT7N13D3,WkDfVrT7N14D3,WkDfVrT7N15D3,WkDfVrT7N16D3,WkDfVrT7N17D3,WkDfVrT7N18D3,WkDfVrT7N19D3,WkDfVrT7N20D3, & + WkDfVrT7N01D4,WkDfVrT7N02D4,WkDfVrT7N03D4,WkDfVrT7N04D4,WkDfVrT7N05D4,WkDfVrT7N06D4,WkDfVrT7N07D4,WkDfVrT7N08D4,WkDfVrT7N09D4,WkDfVrT7N10D4, & + WkDfVrT7N11D4,WkDfVrT7N12D4,WkDfVrT7N13D4,WkDfVrT7N14D4,WkDfVrT7N15D4,WkDfVrT7N16D4,WkDfVrT7N17D4,WkDfVrT7N18D4,WkDfVrT7N19D4,WkDfVrT7N20D4, & + WkDfVrT7N01D5,WkDfVrT7N02D5,WkDfVrT7N03D5,WkDfVrT7N04D5,WkDfVrT7N05D5,WkDfVrT7N06D5,WkDfVrT7N07D5,WkDfVrT7N08D5,WkDfVrT7N09D5,WkDfVrT7N10D5, & + WkDfVrT7N11D5,WkDfVrT7N12D5,WkDfVrT7N13D5,WkDfVrT7N14D5,WkDfVrT7N15D5,WkDfVrT7N16D5,WkDfVrT7N17D5,WkDfVrT7N18D5,WkDfVrT7N19D5,WkDfVrT7N20D5, & + WkDfVrT7N01D6,WkDfVrT7N02D6,WkDfVrT7N03D6,WkDfVrT7N04D6,WkDfVrT7N05D6,WkDfVrT7N06D6,WkDfVrT7N07D6,WkDfVrT7N08D6,WkDfVrT7N09D6,WkDfVrT7N10D6, & + WkDfVrT7N11D6,WkDfVrT7N12D6,WkDfVrT7N13D6,WkDfVrT7N14D6,WkDfVrT7N15D6,WkDfVrT7N16D6,WkDfVrT7N17D6,WkDfVrT7N18D6,WkDfVrT7N19D6,WkDfVrT7N20D6, & + WkDfVrT7N01D7,WkDfVrT7N02D7,WkDfVrT7N03D7,WkDfVrT7N04D7,WkDfVrT7N05D7,WkDfVrT7N06D7,WkDfVrT7N07D7,WkDfVrT7N08D7,WkDfVrT7N09D7,WkDfVrT7N10D7, & + WkDfVrT7N11D7,WkDfVrT7N12D7,WkDfVrT7N13D7,WkDfVrT7N14D7,WkDfVrT7N15D7,WkDfVrT7N16D7,WkDfVrT7N17D7,WkDfVrT7N18D7,WkDfVrT7N19D7,WkDfVrT7N20D7, & + WkDfVrT7N01D8,WkDfVrT7N02D8,WkDfVrT7N03D8,WkDfVrT7N04D8,WkDfVrT7N05D8,WkDfVrT7N06D8,WkDfVrT7N07D8,WkDfVrT7N08D8,WkDfVrT7N09D8,WkDfVrT7N10D8, & + WkDfVrT7N11D8,WkDfVrT7N12D8,WkDfVrT7N13D8,WkDfVrT7N14D8,WkDfVrT7N15D8,WkDfVrT7N16D8,WkDfVrT7N17D8,WkDfVrT7N18D8,WkDfVrT7N19D8,WkDfVrT7N20D8, & + WkDfVrT7N01D9,WkDfVrT7N02D9,WkDfVrT7N03D9,WkDfVrT7N04D9,WkDfVrT7N05D9,WkDfVrT7N06D9,WkDfVrT7N07D9,WkDfVrT7N08D9,WkDfVrT7N09D9,WkDfVrT7N10D9, & + WkDfVrT7N11D9,WkDfVrT7N12D9,WkDfVrT7N13D9,WkDfVrT7N14D9,WkDfVrT7N15D9,WkDfVrT7N16D9,WkDfVrT7N17D9,WkDfVrT7N18D9,WkDfVrT7N19D9,WkDfVrT7N20D9/), (/20,9/) ) +WkDfVrTND(:,:,8) = RESHAPE( & + (/WkDfVrT8N01D1,WkDfVrT8N02D1,WkDfVrT8N03D1,WkDfVrT8N04D1,WkDfVrT8N05D1,WkDfVrT8N06D1,WkDfVrT8N07D1,WkDfVrT8N08D1,WkDfVrT8N09D1,WkDfVrT8N10D1, & + WkDfVrT8N11D1,WkDfVrT8N12D1,WkDfVrT8N13D1,WkDfVrT8N14D1,WkDfVrT8N15D1,WkDfVrT8N16D1,WkDfVrT8N17D1,WkDfVrT8N18D1,WkDfVrT8N19D1,WkDfVrT8N20D1, & + WkDfVrT8N01D2,WkDfVrT8N02D2,WkDfVrT8N03D2,WkDfVrT8N04D2,WkDfVrT8N05D2,WkDfVrT8N06D2,WkDfVrT8N07D2,WkDfVrT8N08D2,WkDfVrT8N09D2,WkDfVrT8N10D2, & + WkDfVrT8N11D2,WkDfVrT8N12D2,WkDfVrT8N13D2,WkDfVrT8N14D2,WkDfVrT8N15D2,WkDfVrT8N16D2,WkDfVrT8N17D2,WkDfVrT8N18D2,WkDfVrT8N19D2,WkDfVrT8N20D2, & + WkDfVrT8N01D3,WkDfVrT8N02D3,WkDfVrT8N03D3,WkDfVrT8N04D3,WkDfVrT8N05D3,WkDfVrT8N06D3,WkDfVrT8N07D3,WkDfVrT8N08D3,WkDfVrT8N09D3,WkDfVrT8N10D3, & + WkDfVrT8N11D3,WkDfVrT8N12D3,WkDfVrT8N13D3,WkDfVrT8N14D3,WkDfVrT8N15D3,WkDfVrT8N16D3,WkDfVrT8N17D3,WkDfVrT8N18D3,WkDfVrT8N19D3,WkDfVrT8N20D3, & + WkDfVrT8N01D4,WkDfVrT8N02D4,WkDfVrT8N03D4,WkDfVrT8N04D4,WkDfVrT8N05D4,WkDfVrT8N06D4,WkDfVrT8N07D4,WkDfVrT8N08D4,WkDfVrT8N09D4,WkDfVrT8N10D4, & + WkDfVrT8N11D4,WkDfVrT8N12D4,WkDfVrT8N13D4,WkDfVrT8N14D4,WkDfVrT8N15D4,WkDfVrT8N16D4,WkDfVrT8N17D4,WkDfVrT8N18D4,WkDfVrT8N19D4,WkDfVrT8N20D4, & + WkDfVrT8N01D5,WkDfVrT8N02D5,WkDfVrT8N03D5,WkDfVrT8N04D5,WkDfVrT8N05D5,WkDfVrT8N06D5,WkDfVrT8N07D5,WkDfVrT8N08D5,WkDfVrT8N09D5,WkDfVrT8N10D5, & + WkDfVrT8N11D5,WkDfVrT8N12D5,WkDfVrT8N13D5,WkDfVrT8N14D5,WkDfVrT8N15D5,WkDfVrT8N16D5,WkDfVrT8N17D5,WkDfVrT8N18D5,WkDfVrT8N19D5,WkDfVrT8N20D5, & + WkDfVrT8N01D6,WkDfVrT8N02D6,WkDfVrT8N03D6,WkDfVrT8N04D6,WkDfVrT8N05D6,WkDfVrT8N06D6,WkDfVrT8N07D6,WkDfVrT8N08D6,WkDfVrT8N09D6,WkDfVrT8N10D6, & + WkDfVrT8N11D6,WkDfVrT8N12D6,WkDfVrT8N13D6,WkDfVrT8N14D6,WkDfVrT8N15D6,WkDfVrT8N16D6,WkDfVrT8N17D6,WkDfVrT8N18D6,WkDfVrT8N19D6,WkDfVrT8N20D6, & + WkDfVrT8N01D7,WkDfVrT8N02D7,WkDfVrT8N03D7,WkDfVrT8N04D7,WkDfVrT8N05D7,WkDfVrT8N06D7,WkDfVrT8N07D7,WkDfVrT8N08D7,WkDfVrT8N09D7,WkDfVrT8N10D7, & + WkDfVrT8N11D7,WkDfVrT8N12D7,WkDfVrT8N13D7,WkDfVrT8N14D7,WkDfVrT8N15D7,WkDfVrT8N16D7,WkDfVrT8N17D7,WkDfVrT8N18D7,WkDfVrT8N19D7,WkDfVrT8N20D7, & + WkDfVrT8N01D8,WkDfVrT8N02D8,WkDfVrT8N03D8,WkDfVrT8N04D8,WkDfVrT8N05D8,WkDfVrT8N06D8,WkDfVrT8N07D8,WkDfVrT8N08D8,WkDfVrT8N09D8,WkDfVrT8N10D8, & + WkDfVrT8N11D8,WkDfVrT8N12D8,WkDfVrT8N13D8,WkDfVrT8N14D8,WkDfVrT8N15D8,WkDfVrT8N16D8,WkDfVrT8N17D8,WkDfVrT8N18D8,WkDfVrT8N19D8,WkDfVrT8N20D8, & + WkDfVrT8N01D9,WkDfVrT8N02D9,WkDfVrT8N03D9,WkDfVrT8N04D9,WkDfVrT8N05D9,WkDfVrT8N06D9,WkDfVrT8N07D9,WkDfVrT8N08D9,WkDfVrT8N09D9,WkDfVrT8N10D9, & + WkDfVrT8N11D9,WkDfVrT8N12D9,WkDfVrT8N13D9,WkDfVrT8N14D9,WkDfVrT8N15D9,WkDfVrT8N16D9,WkDfVrT8N17D9,WkDfVrT8N18D9,WkDfVrT8N19D9,WkDfVrT8N20D9/), (/20,9/) ) +WkDfVrTND(:,:,9) = RESHAPE( & + (/WkDfVrT9N01D1,WkDfVrT9N02D1,WkDfVrT9N03D1,WkDfVrT9N04D1,WkDfVrT9N05D1,WkDfVrT9N06D1,WkDfVrT9N07D1,WkDfVrT9N08D1,WkDfVrT9N09D1,WkDfVrT9N10D1, & + WkDfVrT9N11D1,WkDfVrT9N12D1,WkDfVrT9N13D1,WkDfVrT9N14D1,WkDfVrT9N15D1,WkDfVrT9N16D1,WkDfVrT9N17D1,WkDfVrT9N18D1,WkDfVrT9N19D1,WkDfVrT9N20D1, & + WkDfVrT9N01D2,WkDfVrT9N02D2,WkDfVrT9N03D2,WkDfVrT9N04D2,WkDfVrT9N05D2,WkDfVrT9N06D2,WkDfVrT9N07D2,WkDfVrT9N08D2,WkDfVrT9N09D2,WkDfVrT9N10D2, & + WkDfVrT9N11D2,WkDfVrT9N12D2,WkDfVrT9N13D2,WkDfVrT9N14D2,WkDfVrT9N15D2,WkDfVrT9N16D2,WkDfVrT9N17D2,WkDfVrT9N18D2,WkDfVrT9N19D2,WkDfVrT9N20D2, & + WkDfVrT9N01D3,WkDfVrT9N02D3,WkDfVrT9N03D3,WkDfVrT9N04D3,WkDfVrT9N05D3,WkDfVrT9N06D3,WkDfVrT9N07D3,WkDfVrT9N08D3,WkDfVrT9N09D3,WkDfVrT9N10D3, & + WkDfVrT9N11D3,WkDfVrT9N12D3,WkDfVrT9N13D3,WkDfVrT9N14D3,WkDfVrT9N15D3,WkDfVrT9N16D3,WkDfVrT9N17D3,WkDfVrT9N18D3,WkDfVrT9N19D3,WkDfVrT9N20D3, & + WkDfVrT9N01D4,WkDfVrT9N02D4,WkDfVrT9N03D4,WkDfVrT9N04D4,WkDfVrT9N05D4,WkDfVrT9N06D4,WkDfVrT9N07D4,WkDfVrT9N08D4,WkDfVrT9N09D4,WkDfVrT9N10D4, & + WkDfVrT9N11D4,WkDfVrT9N12D4,WkDfVrT9N13D4,WkDfVrT9N14D4,WkDfVrT9N15D4,WkDfVrT9N16D4,WkDfVrT9N17D4,WkDfVrT9N18D4,WkDfVrT9N19D4,WkDfVrT9N20D4, & + WkDfVrT9N01D5,WkDfVrT9N02D5,WkDfVrT9N03D5,WkDfVrT9N04D5,WkDfVrT9N05D5,WkDfVrT9N06D5,WkDfVrT9N07D5,WkDfVrT9N08D5,WkDfVrT9N09D5,WkDfVrT9N10D5, & + WkDfVrT9N11D5,WkDfVrT9N12D5,WkDfVrT9N13D5,WkDfVrT9N14D5,WkDfVrT9N15D5,WkDfVrT9N16D5,WkDfVrT9N17D5,WkDfVrT9N18D5,WkDfVrT9N19D5,WkDfVrT9N20D5, & + WkDfVrT9N01D6,WkDfVrT9N02D6,WkDfVrT9N03D6,WkDfVrT9N04D6,WkDfVrT9N05D6,WkDfVrT9N06D6,WkDfVrT9N07D6,WkDfVrT9N08D6,WkDfVrT9N09D6,WkDfVrT9N10D6, & + WkDfVrT9N11D6,WkDfVrT9N12D6,WkDfVrT9N13D6,WkDfVrT9N14D6,WkDfVrT9N15D6,WkDfVrT9N16D6,WkDfVrT9N17D6,WkDfVrT9N18D6,WkDfVrT9N19D6,WkDfVrT9N20D6, & + WkDfVrT9N01D7,WkDfVrT9N02D7,WkDfVrT9N03D7,WkDfVrT9N04D7,WkDfVrT9N05D7,WkDfVrT9N06D7,WkDfVrT9N07D7,WkDfVrT9N08D7,WkDfVrT9N09D7,WkDfVrT9N10D7, & + WkDfVrT9N11D7,WkDfVrT9N12D7,WkDfVrT9N13D7,WkDfVrT9N14D7,WkDfVrT9N15D7,WkDfVrT9N16D7,WkDfVrT9N17D7,WkDfVrT9N18D7,WkDfVrT9N19D7,WkDfVrT9N20D7, & + WkDfVrT9N01D8,WkDfVrT9N02D8,WkDfVrT9N03D8,WkDfVrT9N04D8,WkDfVrT9N05D8,WkDfVrT9N06D8,WkDfVrT9N07D8,WkDfVrT9N08D8,WkDfVrT9N09D8,WkDfVrT9N10D8, & + WkDfVrT9N11D8,WkDfVrT9N12D8,WkDfVrT9N13D8,WkDfVrT9N14D8,WkDfVrT9N15D8,WkDfVrT9N16D8,WkDfVrT9N17D8,WkDfVrT9N18D8,WkDfVrT9N19D8,WkDfVrT9N20D8, & + WkDfVrT9N01D9,WkDfVrT9N02D9,WkDfVrT9N03D9,WkDfVrT9N04D9,WkDfVrT9N05D9,WkDfVrT9N06D9,WkDfVrT9N07D9,WkDfVrT9N08D9,WkDfVrT9N09D9,WkDfVrT9N10D9, & + WkDfVrT9N11D9,WkDfVrT9N12D9,WkDfVrT9N13D9,WkDfVrT9N14D9,WkDfVrT9N15D9,WkDfVrT9N16D9,WkDfVrT9N17D9,WkDfVrT9N18D9,WkDfVrT9N19D9,WkDfVrT9N20D9/), (/20,9/) ) - - - +EddVisTND(:,:,1) = RESHAPE( & + (/EddVisT1N01D1,EddVisT1N02D1,EddVisT1N03D1,EddVisT1N04D1,EddVisT1N05D1,EddVisT1N06D1,EddVisT1N07D1,EddVisT1N08D1,EddVisT1N09D1,EddVisT1N10D1, & + EddVisT1N11D1,EddVisT1N12D1,EddVisT1N13D1,EddVisT1N14D1,EddVisT1N15D1,EddVisT1N16D1,EddVisT1N17D1,EddVisT1N18D1,EddVisT1N19D1,EddVisT1N20D1, & + EddVisT1N01D2,EddVisT1N02D2,EddVisT1N03D2,EddVisT1N04D2,EddVisT1N05D2,EddVisT1N06D2,EddVisT1N07D2,EddVisT1N08D2,EddVisT1N09D2,EddVisT1N10D2, & + EddVisT1N11D2,EddVisT1N12D2,EddVisT1N13D2,EddVisT1N14D2,EddVisT1N15D2,EddVisT1N16D2,EddVisT1N17D2,EddVisT1N18D2,EddVisT1N19D2,EddVisT1N20D2, & + EddVisT1N01D3,EddVisT1N02D3,EddVisT1N03D3,EddVisT1N04D3,EddVisT1N05D3,EddVisT1N06D3,EddVisT1N07D3,EddVisT1N08D3,EddVisT1N09D3,EddVisT1N10D3, & + EddVisT1N11D3,EddVisT1N12D3,EddVisT1N13D3,EddVisT1N14D3,EddVisT1N15D3,EddVisT1N16D3,EddVisT1N17D3,EddVisT1N18D3,EddVisT1N19D3,EddVisT1N20D3, & + EddVisT1N01D4,EddVisT1N02D4,EddVisT1N03D4,EddVisT1N04D4,EddVisT1N05D4,EddVisT1N06D4,EddVisT1N07D4,EddVisT1N08D4,EddVisT1N09D4,EddVisT1N10D4, & + EddVisT1N11D4,EddVisT1N12D4,EddVisT1N13D4,EddVisT1N14D4,EddVisT1N15D4,EddVisT1N16D4,EddVisT1N17D4,EddVisT1N18D4,EddVisT1N19D4,EddVisT1N20D4, & + EddVisT1N01D5,EddVisT1N02D5,EddVisT1N03D5,EddVisT1N04D5,EddVisT1N05D5,EddVisT1N06D5,EddVisT1N07D5,EddVisT1N08D5,EddVisT1N09D5,EddVisT1N10D5, & + EddVisT1N11D5,EddVisT1N12D5,EddVisT1N13D5,EddVisT1N14D5,EddVisT1N15D5,EddVisT1N16D5,EddVisT1N17D5,EddVisT1N18D5,EddVisT1N19D5,EddVisT1N20D5, & + EddVisT1N01D6,EddVisT1N02D6,EddVisT1N03D6,EddVisT1N04D6,EddVisT1N05D6,EddVisT1N06D6,EddVisT1N07D6,EddVisT1N08D6,EddVisT1N09D6,EddVisT1N10D6, & + EddVisT1N11D6,EddVisT1N12D6,EddVisT1N13D6,EddVisT1N14D6,EddVisT1N15D6,EddVisT1N16D6,EddVisT1N17D6,EddVisT1N18D6,EddVisT1N19D6,EddVisT1N20D6, & + EddVisT1N01D7,EddVisT1N02D7,EddVisT1N03D7,EddVisT1N04D7,EddVisT1N05D7,EddVisT1N06D7,EddVisT1N07D7,EddVisT1N08D7,EddVisT1N09D7,EddVisT1N10D7, & + EddVisT1N11D7,EddVisT1N12D7,EddVisT1N13D7,EddVisT1N14D7,EddVisT1N15D7,EddVisT1N16D7,EddVisT1N17D7,EddVisT1N18D7,EddVisT1N19D7,EddVisT1N20D7, & + EddVisT1N01D8,EddVisT1N02D8,EddVisT1N03D8,EddVisT1N04D8,EddVisT1N05D8,EddVisT1N06D8,EddVisT1N07D8,EddVisT1N08D8,EddVisT1N09D8,EddVisT1N10D8, & + EddVisT1N11D8,EddVisT1N12D8,EddVisT1N13D8,EddVisT1N14D8,EddVisT1N15D8,EddVisT1N16D8,EddVisT1N17D8,EddVisT1N18D8,EddVisT1N19D8,EddVisT1N20D8, & + EddVisT1N01D9,EddVisT1N02D9,EddVisT1N03D9,EddVisT1N04D9,EddVisT1N05D9,EddVisT1N06D9,EddVisT1N07D9,EddVisT1N08D9,EddVisT1N09D9,EddVisT1N10D9, & + EddVisT1N11D9,EddVisT1N12D9,EddVisT1N13D9,EddVisT1N14D9,EddVisT1N15D9,EddVisT1N16D9,EddVisT1N17D9,EddVisT1N18D9,EddVisT1N19D9,EddVisT1N20D9/), (/20,9/) ) +EddVisTND(:,:,2) = RESHAPE( & + (/EddVisT2N01D1,EddVisT2N02D1,EddVisT2N03D1,EddVisT2N04D1,EddVisT2N05D1,EddVisT2N06D1,EddVisT2N07D1,EddVisT2N08D1,EddVisT2N09D1,EddVisT2N10D1, & + EddVisT2N11D1,EddVisT2N12D1,EddVisT2N13D1,EddVisT2N14D1,EddVisT2N15D1,EddVisT2N16D1,EddVisT2N17D1,EddVisT2N18D1,EddVisT2N19D1,EddVisT2N20D1, & + EddVisT2N01D2,EddVisT2N02D2,EddVisT2N03D2,EddVisT2N04D2,EddVisT2N05D2,EddVisT2N06D2,EddVisT2N07D2,EddVisT2N08D2,EddVisT2N09D2,EddVisT2N10D2, & + EddVisT2N11D2,EddVisT2N12D2,EddVisT2N13D2,EddVisT2N14D2,EddVisT2N15D2,EddVisT2N16D2,EddVisT2N17D2,EddVisT2N18D2,EddVisT2N19D2,EddVisT2N20D2, & + EddVisT2N01D3,EddVisT2N02D3,EddVisT2N03D3,EddVisT2N04D3,EddVisT2N05D3,EddVisT2N06D3,EddVisT2N07D3,EddVisT2N08D3,EddVisT2N09D3,EddVisT2N10D3, & + EddVisT2N11D3,EddVisT2N12D3,EddVisT2N13D3,EddVisT2N14D3,EddVisT2N15D3,EddVisT2N16D3,EddVisT2N17D3,EddVisT2N18D3,EddVisT2N19D3,EddVisT2N20D3, & + EddVisT2N01D4,EddVisT2N02D4,EddVisT2N03D4,EddVisT2N04D4,EddVisT2N05D4,EddVisT2N06D4,EddVisT2N07D4,EddVisT2N08D4,EddVisT2N09D4,EddVisT2N10D4, & + EddVisT2N11D4,EddVisT2N12D4,EddVisT2N13D4,EddVisT2N14D4,EddVisT2N15D4,EddVisT2N16D4,EddVisT2N17D4,EddVisT2N18D4,EddVisT2N19D4,EddVisT2N20D4, & + EddVisT2N01D5,EddVisT2N02D5,EddVisT2N03D5,EddVisT2N04D5,EddVisT2N05D5,EddVisT2N06D5,EddVisT2N07D5,EddVisT2N08D5,EddVisT2N09D5,EddVisT2N10D5, & + EddVisT2N11D5,EddVisT2N12D5,EddVisT2N13D5,EddVisT2N14D5,EddVisT2N15D5,EddVisT2N16D5,EddVisT2N17D5,EddVisT2N18D5,EddVisT2N19D5,EddVisT2N20D5, & + EddVisT2N01D6,EddVisT2N02D6,EddVisT2N03D6,EddVisT2N04D6,EddVisT2N05D6,EddVisT2N06D6,EddVisT2N07D6,EddVisT2N08D6,EddVisT2N09D6,EddVisT2N10D6, & + EddVisT2N11D6,EddVisT2N12D6,EddVisT2N13D6,EddVisT2N14D6,EddVisT2N15D6,EddVisT2N16D6,EddVisT2N17D6,EddVisT2N18D6,EddVisT2N19D6,EddVisT2N20D6, & + EddVisT2N01D7,EddVisT2N02D7,EddVisT2N03D7,EddVisT2N04D7,EddVisT2N05D7,EddVisT2N06D7,EddVisT2N07D7,EddVisT2N08D7,EddVisT2N09D7,EddVisT2N10D7, & + EddVisT2N11D7,EddVisT2N12D7,EddVisT2N13D7,EddVisT2N14D7,EddVisT2N15D7,EddVisT2N16D7,EddVisT2N17D7,EddVisT2N18D7,EddVisT2N19D7,EddVisT2N20D7, & + EddVisT2N01D8,EddVisT2N02D8,EddVisT2N03D8,EddVisT2N04D8,EddVisT2N05D8,EddVisT2N06D8,EddVisT2N07D8,EddVisT2N08D8,EddVisT2N09D8,EddVisT2N10D8, & + EddVisT2N11D8,EddVisT2N12D8,EddVisT2N13D8,EddVisT2N14D8,EddVisT2N15D8,EddVisT2N16D8,EddVisT2N17D8,EddVisT2N18D8,EddVisT2N19D8,EddVisT2N20D8, & + EddVisT2N01D9,EddVisT2N02D9,EddVisT2N03D9,EddVisT2N04D9,EddVisT2N05D9,EddVisT2N06D9,EddVisT2N07D9,EddVisT2N08D9,EddVisT2N09D9,EddVisT2N10D9, & + EddVisT2N11D9,EddVisT2N12D9,EddVisT2N13D9,EddVisT2N14D9,EddVisT2N15D9,EddVisT2N16D9,EddVisT2N17D9,EddVisT2N18D9,EddVisT2N19D9,EddVisT2N20D9/), (/20,9/) ) +EddVisTND(:,:,3) = RESHAPE( & + (/EddVisT3N01D1,EddVisT3N02D1,EddVisT3N03D1,EddVisT3N04D1,EddVisT3N05D1,EddVisT3N06D1,EddVisT3N07D1,EddVisT3N08D1,EddVisT3N09D1,EddVisT3N10D1, & + EddVisT3N11D1,EddVisT3N12D1,EddVisT3N13D1,EddVisT3N14D1,EddVisT3N15D1,EddVisT3N16D1,EddVisT3N17D1,EddVisT3N18D1,EddVisT3N19D1,EddVisT3N20D1, & + EddVisT3N01D2,EddVisT3N02D2,EddVisT3N03D2,EddVisT3N04D2,EddVisT3N05D2,EddVisT3N06D2,EddVisT3N07D2,EddVisT3N08D2,EddVisT3N09D2,EddVisT3N10D2, & + EddVisT3N11D2,EddVisT3N12D2,EddVisT3N13D2,EddVisT3N14D2,EddVisT3N15D2,EddVisT3N16D2,EddVisT3N17D2,EddVisT3N18D2,EddVisT3N19D2,EddVisT3N20D2, & + EddVisT3N01D3,EddVisT3N02D3,EddVisT3N03D3,EddVisT3N04D3,EddVisT3N05D3,EddVisT3N06D3,EddVisT3N07D3,EddVisT3N08D3,EddVisT3N09D3,EddVisT3N10D3, & + EddVisT3N11D3,EddVisT3N12D3,EddVisT3N13D3,EddVisT3N14D3,EddVisT3N15D3,EddVisT3N16D3,EddVisT3N17D3,EddVisT3N18D3,EddVisT3N19D3,EddVisT3N20D3, & + EddVisT3N01D4,EddVisT3N02D4,EddVisT3N03D4,EddVisT3N04D4,EddVisT3N05D4,EddVisT3N06D4,EddVisT3N07D4,EddVisT3N08D4,EddVisT3N09D4,EddVisT3N10D4, & + EddVisT3N11D4,EddVisT3N12D4,EddVisT3N13D4,EddVisT3N14D4,EddVisT3N15D4,EddVisT3N16D4,EddVisT3N17D4,EddVisT3N18D4,EddVisT3N19D4,EddVisT3N20D4, & + EddVisT3N01D5,EddVisT3N02D5,EddVisT3N03D5,EddVisT3N04D5,EddVisT3N05D5,EddVisT3N06D5,EddVisT3N07D5,EddVisT3N08D5,EddVisT3N09D5,EddVisT3N10D5, & + EddVisT3N11D5,EddVisT3N12D5,EddVisT3N13D5,EddVisT3N14D5,EddVisT3N15D5,EddVisT3N16D5,EddVisT3N17D5,EddVisT3N18D5,EddVisT3N19D5,EddVisT3N20D5, & + EddVisT3N01D6,EddVisT3N02D6,EddVisT3N03D6,EddVisT3N04D6,EddVisT3N05D6,EddVisT3N06D6,EddVisT3N07D6,EddVisT3N08D6,EddVisT3N09D6,EddVisT3N10D6, & + EddVisT3N11D6,EddVisT3N12D6,EddVisT3N13D6,EddVisT3N14D6,EddVisT3N15D6,EddVisT3N16D6,EddVisT3N17D6,EddVisT3N18D6,EddVisT3N19D6,EddVisT3N20D6, & + EddVisT3N01D7,EddVisT3N02D7,EddVisT3N03D7,EddVisT3N04D7,EddVisT3N05D7,EddVisT3N06D7,EddVisT3N07D7,EddVisT3N08D7,EddVisT3N09D7,EddVisT3N10D7, & + EddVisT3N11D7,EddVisT3N12D7,EddVisT3N13D7,EddVisT3N14D7,EddVisT3N15D7,EddVisT3N16D7,EddVisT3N17D7,EddVisT3N18D7,EddVisT3N19D7,EddVisT3N20D7, & + EddVisT3N01D8,EddVisT3N02D8,EddVisT3N03D8,EddVisT3N04D8,EddVisT3N05D8,EddVisT3N06D8,EddVisT3N07D8,EddVisT3N08D8,EddVisT3N09D8,EddVisT3N10D8, & + EddVisT3N11D8,EddVisT3N12D8,EddVisT3N13D8,EddVisT3N14D8,EddVisT3N15D8,EddVisT3N16D8,EddVisT3N17D8,EddVisT3N18D8,EddVisT3N19D8,EddVisT3N20D8, & + EddVisT3N01D9,EddVisT3N02D9,EddVisT3N03D9,EddVisT3N04D9,EddVisT3N05D9,EddVisT3N06D9,EddVisT3N07D9,EddVisT3N08D9,EddVisT3N09D9,EddVisT3N10D9, & + EddVisT3N11D9,EddVisT3N12D9,EddVisT3N13D9,EddVisT3N14D9,EddVisT3N15D9,EddVisT3N16D9,EddVisT3N17D9,EddVisT3N18D9,EddVisT3N19D9,EddVisT3N20D9/), (/20,9/) ) +EddVisTND(:,:,4) = RESHAPE( & + (/EddVisT4N01D1,EddVisT4N02D1,EddVisT4N03D1,EddVisT4N04D1,EddVisT4N05D1,EddVisT4N06D1,EddVisT4N07D1,EddVisT4N08D1,EddVisT4N09D1,EddVisT4N10D1, & + EddVisT4N11D1,EddVisT4N12D1,EddVisT4N13D1,EddVisT4N14D1,EddVisT4N15D1,EddVisT4N16D1,EddVisT4N17D1,EddVisT4N18D1,EddVisT4N19D1,EddVisT4N20D1, & + EddVisT4N01D2,EddVisT4N02D2,EddVisT4N03D2,EddVisT4N04D2,EddVisT4N05D2,EddVisT4N06D2,EddVisT4N07D2,EddVisT4N08D2,EddVisT4N09D2,EddVisT4N10D2, & + EddVisT4N11D2,EddVisT4N12D2,EddVisT4N13D2,EddVisT4N14D2,EddVisT4N15D2,EddVisT4N16D2,EddVisT4N17D2,EddVisT4N18D2,EddVisT4N19D2,EddVisT4N20D2, & + EddVisT4N01D3,EddVisT4N02D3,EddVisT4N03D3,EddVisT4N04D3,EddVisT4N05D3,EddVisT4N06D3,EddVisT4N07D3,EddVisT4N08D3,EddVisT4N09D3,EddVisT4N10D3, & + EddVisT4N11D3,EddVisT4N12D3,EddVisT4N13D3,EddVisT4N14D3,EddVisT4N15D3,EddVisT4N16D3,EddVisT4N17D3,EddVisT4N18D3,EddVisT4N19D3,EddVisT4N20D3, & + EddVisT4N01D4,EddVisT4N02D4,EddVisT4N03D4,EddVisT4N04D4,EddVisT4N05D4,EddVisT4N06D4,EddVisT4N07D4,EddVisT4N08D4,EddVisT4N09D4,EddVisT4N10D4, & + EddVisT4N11D4,EddVisT4N12D4,EddVisT4N13D4,EddVisT4N14D4,EddVisT4N15D4,EddVisT4N16D4,EddVisT4N17D4,EddVisT4N18D4,EddVisT4N19D4,EddVisT4N20D4, & + EddVisT4N01D5,EddVisT4N02D5,EddVisT4N03D5,EddVisT4N04D5,EddVisT4N05D5,EddVisT4N06D5,EddVisT4N07D5,EddVisT4N08D5,EddVisT4N09D5,EddVisT4N10D5, & + EddVisT4N11D5,EddVisT4N12D5,EddVisT4N13D5,EddVisT4N14D5,EddVisT4N15D5,EddVisT4N16D5,EddVisT4N17D5,EddVisT4N18D5,EddVisT4N19D5,EddVisT4N20D5, & + EddVisT4N01D6,EddVisT4N02D6,EddVisT4N03D6,EddVisT4N04D6,EddVisT4N05D6,EddVisT4N06D6,EddVisT4N07D6,EddVisT4N08D6,EddVisT4N09D6,EddVisT4N10D6, & + EddVisT4N11D6,EddVisT4N12D6,EddVisT4N13D6,EddVisT4N14D6,EddVisT4N15D6,EddVisT4N16D6,EddVisT4N17D6,EddVisT4N18D6,EddVisT4N19D6,EddVisT4N20D6, & + EddVisT4N01D7,EddVisT4N02D7,EddVisT4N03D7,EddVisT4N04D7,EddVisT4N05D7,EddVisT4N06D7,EddVisT4N07D7,EddVisT4N08D7,EddVisT4N09D7,EddVisT4N10D7, & + EddVisT4N11D7,EddVisT4N12D7,EddVisT4N13D7,EddVisT4N14D7,EddVisT4N15D7,EddVisT4N16D7,EddVisT4N17D7,EddVisT4N18D7,EddVisT4N19D7,EddVisT4N20D7, & + EddVisT4N01D8,EddVisT4N02D8,EddVisT4N03D8,EddVisT4N04D8,EddVisT4N05D8,EddVisT4N06D8,EddVisT4N07D8,EddVisT4N08D8,EddVisT4N09D8,EddVisT4N10D8, & + EddVisT4N11D8,EddVisT4N12D8,EddVisT4N13D8,EddVisT4N14D8,EddVisT4N15D8,EddVisT4N16D8,EddVisT4N17D8,EddVisT4N18D8,EddVisT4N19D8,EddVisT4N20D8, & + EddVisT4N01D9,EddVisT4N02D9,EddVisT4N03D9,EddVisT4N04D9,EddVisT4N05D9,EddVisT4N06D9,EddVisT4N07D9,EddVisT4N08D9,EddVisT4N09D9,EddVisT4N10D9, & + EddVisT4N11D9,EddVisT4N12D9,EddVisT4N13D9,EddVisT4N14D9,EddVisT4N15D9,EddVisT4N16D9,EddVisT4N17D9,EddVisT4N18D9,EddVisT4N19D9,EddVisT4N20D9/), (/20,9/) ) + +EddVisTND(:,:,5) = RESHAPE( & + (/EddVisT5N01D1,EddVisT5N02D1,EddVisT5N03D1,EddVisT5N04D1,EddVisT5N05D1,EddVisT5N06D1,EddVisT5N07D1,EddVisT5N08D1,EddVisT5N09D1,EddVisT5N10D1, & + EddVisT5N11D1,EddVisT5N12D1,EddVisT5N13D1,EddVisT5N14D1,EddVisT5N15D1,EddVisT5N16D1,EddVisT5N17D1,EddVisT5N18D1,EddVisT5N19D1,EddVisT5N20D1, & + EddVisT5N01D2,EddVisT5N02D2,EddVisT5N03D2,EddVisT5N04D2,EddVisT5N05D2,EddVisT5N06D2,EddVisT5N07D2,EddVisT5N08D2,EddVisT5N09D2,EddVisT5N10D2, & + EddVisT5N11D2,EddVisT5N12D2,EddVisT5N13D2,EddVisT5N14D2,EddVisT5N15D2,EddVisT5N16D2,EddVisT5N17D2,EddVisT5N18D2,EddVisT5N19D2,EddVisT5N20D2, & + EddVisT5N01D3,EddVisT5N02D3,EddVisT5N03D3,EddVisT5N04D3,EddVisT5N05D3,EddVisT5N06D3,EddVisT5N07D3,EddVisT5N08D3,EddVisT5N09D3,EddVisT5N10D3, & + EddVisT5N11D3,EddVisT5N12D3,EddVisT5N13D3,EddVisT5N14D3,EddVisT5N15D3,EddVisT5N16D3,EddVisT5N17D3,EddVisT5N18D3,EddVisT5N19D3,EddVisT5N20D3, & + EddVisT5N01D4,EddVisT5N02D4,EddVisT5N03D4,EddVisT5N04D4,EddVisT5N05D4,EddVisT5N06D4,EddVisT5N07D4,EddVisT5N08D4,EddVisT5N09D4,EddVisT5N10D4, & + EddVisT5N11D4,EddVisT5N12D4,EddVisT5N13D4,EddVisT5N14D4,EddVisT5N15D4,EddVisT5N16D4,EddVisT5N17D4,EddVisT5N18D4,EddVisT5N19D4,EddVisT5N20D4, & + EddVisT5N01D5,EddVisT5N02D5,EddVisT5N03D5,EddVisT5N04D5,EddVisT5N05D5,EddVisT5N06D5,EddVisT5N07D5,EddVisT5N08D5,EddVisT5N09D5,EddVisT5N10D5, & + EddVisT5N11D5,EddVisT5N12D5,EddVisT5N13D5,EddVisT5N14D5,EddVisT5N15D5,EddVisT5N16D5,EddVisT5N17D5,EddVisT5N18D5,EddVisT5N19D5,EddVisT5N20D5, & + EddVisT5N01D6,EddVisT5N02D6,EddVisT5N03D6,EddVisT5N04D6,EddVisT5N05D6,EddVisT5N06D6,EddVisT5N07D6,EddVisT5N08D6,EddVisT5N09D6,EddVisT5N10D6, & + EddVisT5N11D6,EddVisT5N12D6,EddVisT5N13D6,EddVisT5N14D6,EddVisT5N15D6,EddVisT5N16D6,EddVisT5N17D6,EddVisT5N18D6,EddVisT5N19D6,EddVisT5N20D6, & + EddVisT5N01D7,EddVisT5N02D7,EddVisT5N03D7,EddVisT5N04D7,EddVisT5N05D7,EddVisT5N06D7,EddVisT5N07D7,EddVisT5N08D7,EddVisT5N09D7,EddVisT5N10D7, & + EddVisT5N11D7,EddVisT5N12D7,EddVisT5N13D7,EddVisT5N14D7,EddVisT5N15D7,EddVisT5N16D7,EddVisT5N17D7,EddVisT5N18D7,EddVisT5N19D7,EddVisT5N20D7, & + EddVisT5N01D8,EddVisT5N02D8,EddVisT5N03D8,EddVisT5N04D8,EddVisT5N05D8,EddVisT5N06D8,EddVisT5N07D8,EddVisT5N08D8,EddVisT5N09D8,EddVisT5N10D8, & + EddVisT5N11D8,EddVisT5N12D8,EddVisT5N13D8,EddVisT5N14D8,EddVisT5N15D8,EddVisT5N16D8,EddVisT5N17D8,EddVisT5N18D8,EddVisT5N19D8,EddVisT5N20D8, & + EddVisT5N01D9,EddVisT5N02D9,EddVisT5N03D9,EddVisT5N04D9,EddVisT5N05D9,EddVisT5N06D9,EddVisT5N07D9,EddVisT5N08D9,EddVisT5N09D9,EddVisT5N10D9, & + EddVisT5N11D9,EddVisT5N12D9,EddVisT5N13D9,EddVisT5N14D9,EddVisT5N15D9,EddVisT5N16D9,EddVisT5N17D9,EddVisT5N18D9,EddVisT5N19D9,EddVisT5N20D9/), (/20,9/) ) +EddVisTND(:,:,6) = RESHAPE( & + (/EddVisT6N01D1,EddVisT6N02D1,EddVisT6N03D1,EddVisT6N04D1,EddVisT6N05D1,EddVisT6N06D1,EddVisT6N07D1,EddVisT6N08D1,EddVisT6N09D1,EddVisT6N10D1, & + EddVisT6N11D1,EddVisT6N12D1,EddVisT6N13D1,EddVisT6N14D1,EddVisT6N15D1,EddVisT6N16D1,EddVisT6N17D1,EddVisT6N18D1,EddVisT6N19D1,EddVisT6N20D1, & + EddVisT6N01D2,EddVisT6N02D2,EddVisT6N03D2,EddVisT6N04D2,EddVisT6N05D2,EddVisT6N06D2,EddVisT6N07D2,EddVisT6N08D2,EddVisT6N09D2,EddVisT6N10D2, & + EddVisT6N11D2,EddVisT6N12D2,EddVisT6N13D2,EddVisT6N14D2,EddVisT6N15D2,EddVisT6N16D2,EddVisT6N17D2,EddVisT6N18D2,EddVisT6N19D2,EddVisT6N20D2, & + EddVisT6N01D3,EddVisT6N02D3,EddVisT6N03D3,EddVisT6N04D3,EddVisT6N05D3,EddVisT6N06D3,EddVisT6N07D3,EddVisT6N08D3,EddVisT6N09D3,EddVisT6N10D3, & + EddVisT6N11D3,EddVisT6N12D3,EddVisT6N13D3,EddVisT6N14D3,EddVisT6N15D3,EddVisT6N16D3,EddVisT6N17D3,EddVisT6N18D3,EddVisT6N19D3,EddVisT6N20D3, & + EddVisT6N01D4,EddVisT6N02D4,EddVisT6N03D4,EddVisT6N04D4,EddVisT6N05D4,EddVisT6N06D4,EddVisT6N07D4,EddVisT6N08D4,EddVisT6N09D4,EddVisT6N10D4, & + EddVisT6N11D4,EddVisT6N12D4,EddVisT6N13D4,EddVisT6N14D4,EddVisT6N15D4,EddVisT6N16D4,EddVisT6N17D4,EddVisT6N18D4,EddVisT6N19D4,EddVisT6N20D4, & + EddVisT6N01D5,EddVisT6N02D5,EddVisT6N03D5,EddVisT6N04D5,EddVisT6N05D5,EddVisT6N06D5,EddVisT6N07D5,EddVisT6N08D5,EddVisT6N09D5,EddVisT6N10D5, & + EddVisT6N11D5,EddVisT6N12D5,EddVisT6N13D5,EddVisT6N14D5,EddVisT6N15D5,EddVisT6N16D5,EddVisT6N17D5,EddVisT6N18D5,EddVisT6N19D5,EddVisT6N20D5, & + EddVisT6N01D6,EddVisT6N02D6,EddVisT6N03D6,EddVisT6N04D6,EddVisT6N05D6,EddVisT6N06D6,EddVisT6N07D6,EddVisT6N08D6,EddVisT6N09D6,EddVisT6N10D6, & + EddVisT6N11D6,EddVisT6N12D6,EddVisT6N13D6,EddVisT6N14D6,EddVisT6N15D6,EddVisT6N16D6,EddVisT6N17D6,EddVisT6N18D6,EddVisT6N19D6,EddVisT6N20D6, & + EddVisT6N01D7,EddVisT6N02D7,EddVisT6N03D7,EddVisT6N04D7,EddVisT6N05D7,EddVisT6N06D7,EddVisT6N07D7,EddVisT6N08D7,EddVisT6N09D7,EddVisT6N10D7, & + EddVisT6N11D7,EddVisT6N12D7,EddVisT6N13D7,EddVisT6N14D7,EddVisT6N15D7,EddVisT6N16D7,EddVisT6N17D7,EddVisT6N18D7,EddVisT6N19D7,EddVisT6N20D7, & + EddVisT6N01D8,EddVisT6N02D8,EddVisT6N03D8,EddVisT6N04D8,EddVisT6N05D8,EddVisT6N06D8,EddVisT6N07D8,EddVisT6N08D8,EddVisT6N09D8,EddVisT6N10D8, & + EddVisT6N11D8,EddVisT6N12D8,EddVisT6N13D8,EddVisT6N14D8,EddVisT6N15D8,EddVisT6N16D8,EddVisT6N17D8,EddVisT6N18D8,EddVisT6N19D8,EddVisT6N20D8, & + EddVisT6N01D9,EddVisT6N02D9,EddVisT6N03D9,EddVisT6N04D9,EddVisT6N05D9,EddVisT6N06D9,EddVisT6N07D9,EddVisT6N08D9,EddVisT6N09D9,EddVisT6N10D9, & + EddVisT6N11D9,EddVisT6N12D9,EddVisT6N13D9,EddVisT6N14D9,EddVisT6N15D9,EddVisT6N16D9,EddVisT6N17D9,EddVisT6N18D9,EddVisT6N19D9,EddVisT6N20D9/), (/20,9/) ) +EddVisTND(:,:,7) = RESHAPE( & + (/EddVisT7N01D1,EddVisT7N02D1,EddVisT7N03D1,EddVisT7N04D1,EddVisT7N05D1,EddVisT7N06D1,EddVisT7N07D1,EddVisT7N08D1,EddVisT7N09D1,EddVisT7N10D1, & + EddVisT7N11D1,EddVisT7N12D1,EddVisT7N13D1,EddVisT7N14D1,EddVisT7N15D1,EddVisT7N16D1,EddVisT7N17D1,EddVisT7N18D1,EddVisT7N19D1,EddVisT7N20D1, & + EddVisT7N01D2,EddVisT7N02D2,EddVisT7N03D2,EddVisT7N04D2,EddVisT7N05D2,EddVisT7N06D2,EddVisT7N07D2,EddVisT7N08D2,EddVisT7N09D2,EddVisT7N10D2, & + EddVisT7N11D2,EddVisT7N12D2,EddVisT7N13D2,EddVisT7N14D2,EddVisT7N15D2,EddVisT7N16D2,EddVisT7N17D2,EddVisT7N18D2,EddVisT7N19D2,EddVisT7N20D2, & + EddVisT7N01D3,EddVisT7N02D3,EddVisT7N03D3,EddVisT7N04D3,EddVisT7N05D3,EddVisT7N06D3,EddVisT7N07D3,EddVisT7N08D3,EddVisT7N09D3,EddVisT7N10D3, & + EddVisT7N11D3,EddVisT7N12D3,EddVisT7N13D3,EddVisT7N14D3,EddVisT7N15D3,EddVisT7N16D3,EddVisT7N17D3,EddVisT7N18D3,EddVisT7N19D3,EddVisT7N20D3, & + EddVisT7N01D4,EddVisT7N02D4,EddVisT7N03D4,EddVisT7N04D4,EddVisT7N05D4,EddVisT7N06D4,EddVisT7N07D4,EddVisT7N08D4,EddVisT7N09D4,EddVisT7N10D4, & + EddVisT7N11D4,EddVisT7N12D4,EddVisT7N13D4,EddVisT7N14D4,EddVisT7N15D4,EddVisT7N16D4,EddVisT7N17D4,EddVisT7N18D4,EddVisT7N19D4,EddVisT7N20D4, & + EddVisT7N01D5,EddVisT7N02D5,EddVisT7N03D5,EddVisT7N04D5,EddVisT7N05D5,EddVisT7N06D5,EddVisT7N07D5,EddVisT7N08D5,EddVisT7N09D5,EddVisT7N10D5, & + EddVisT7N11D5,EddVisT7N12D5,EddVisT7N13D5,EddVisT7N14D5,EddVisT7N15D5,EddVisT7N16D5,EddVisT7N17D5,EddVisT7N18D5,EddVisT7N19D5,EddVisT7N20D5, & + EddVisT7N01D6,EddVisT7N02D6,EddVisT7N03D6,EddVisT7N04D6,EddVisT7N05D6,EddVisT7N06D6,EddVisT7N07D6,EddVisT7N08D6,EddVisT7N09D6,EddVisT7N10D6, & + EddVisT7N11D6,EddVisT7N12D6,EddVisT7N13D6,EddVisT7N14D6,EddVisT7N15D6,EddVisT7N16D6,EddVisT7N17D6,EddVisT7N18D6,EddVisT7N19D6,EddVisT7N20D6, & + EddVisT7N01D7,EddVisT7N02D7,EddVisT7N03D7,EddVisT7N04D7,EddVisT7N05D7,EddVisT7N06D7,EddVisT7N07D7,EddVisT7N08D7,EddVisT7N09D7,EddVisT7N10D7, & + EddVisT7N11D7,EddVisT7N12D7,EddVisT7N13D7,EddVisT7N14D7,EddVisT7N15D7,EddVisT7N16D7,EddVisT7N17D7,EddVisT7N18D7,EddVisT7N19D7,EddVisT7N20D7, & + EddVisT7N01D8,EddVisT7N02D8,EddVisT7N03D8,EddVisT7N04D8,EddVisT7N05D8,EddVisT7N06D8,EddVisT7N07D8,EddVisT7N08D8,EddVisT7N09D8,EddVisT7N10D8, & + EddVisT7N11D8,EddVisT7N12D8,EddVisT7N13D8,EddVisT7N14D8,EddVisT7N15D8,EddVisT7N16D8,EddVisT7N17D8,EddVisT7N18D8,EddVisT7N19D8,EddVisT7N20D8, & + EddVisT7N01D9,EddVisT7N02D9,EddVisT7N03D9,EddVisT7N04D9,EddVisT7N05D9,EddVisT7N06D9,EddVisT7N07D9,EddVisT7N08D9,EddVisT7N09D9,EddVisT7N10D9, & + EddVisT7N11D9,EddVisT7N12D9,EddVisT7N13D9,EddVisT7N14D9,EddVisT7N15D9,EddVisT7N16D9,EddVisT7N17D9,EddVisT7N18D9,EddVisT7N19D9,EddVisT7N20D9/), (/20,9/) ) +EddVisTND(:,:,8) = RESHAPE( & + (/EddVisT8N01D1,EddVisT8N02D1,EddVisT8N03D1,EddVisT8N04D1,EddVisT8N05D1,EddVisT8N06D1,EddVisT8N07D1,EddVisT8N08D1,EddVisT8N09D1,EddVisT8N10D1, & + EddVisT8N11D1,EddVisT8N12D1,EddVisT8N13D1,EddVisT8N14D1,EddVisT8N15D1,EddVisT8N16D1,EddVisT8N17D1,EddVisT8N18D1,EddVisT8N19D1,EddVisT8N20D1, & + EddVisT8N01D2,EddVisT8N02D2,EddVisT8N03D2,EddVisT8N04D2,EddVisT8N05D2,EddVisT8N06D2,EddVisT8N07D2,EddVisT8N08D2,EddVisT8N09D2,EddVisT8N10D2, & + EddVisT8N11D2,EddVisT8N12D2,EddVisT8N13D2,EddVisT8N14D2,EddVisT8N15D2,EddVisT8N16D2,EddVisT8N17D2,EddVisT8N18D2,EddVisT8N19D2,EddVisT8N20D2, & + EddVisT8N01D3,EddVisT8N02D3,EddVisT8N03D3,EddVisT8N04D3,EddVisT8N05D3,EddVisT8N06D3,EddVisT8N07D3,EddVisT8N08D3,EddVisT8N09D3,EddVisT8N10D3, & + EddVisT8N11D3,EddVisT8N12D3,EddVisT8N13D3,EddVisT8N14D3,EddVisT8N15D3,EddVisT8N16D3,EddVisT8N17D3,EddVisT8N18D3,EddVisT8N19D3,EddVisT8N20D3, & + EddVisT8N01D4,EddVisT8N02D4,EddVisT8N03D4,EddVisT8N04D4,EddVisT8N05D4,EddVisT8N06D4,EddVisT8N07D4,EddVisT8N08D4,EddVisT8N09D4,EddVisT8N10D4, & + EddVisT8N11D4,EddVisT8N12D4,EddVisT8N13D4,EddVisT8N14D4,EddVisT8N15D4,EddVisT8N16D4,EddVisT8N17D4,EddVisT8N18D4,EddVisT8N19D4,EddVisT8N20D4, & + EddVisT8N01D5,EddVisT8N02D5,EddVisT8N03D5,EddVisT8N04D5,EddVisT8N05D5,EddVisT8N06D5,EddVisT8N07D5,EddVisT8N08D5,EddVisT8N09D5,EddVisT8N10D5, & + EddVisT8N11D5,EddVisT8N12D5,EddVisT8N13D5,EddVisT8N14D5,EddVisT8N15D5,EddVisT8N16D5,EddVisT8N17D5,EddVisT8N18D5,EddVisT8N19D5,EddVisT8N20D5, & + EddVisT8N01D6,EddVisT8N02D6,EddVisT8N03D6,EddVisT8N04D6,EddVisT8N05D6,EddVisT8N06D6,EddVisT8N07D6,EddVisT8N08D6,EddVisT8N09D6,EddVisT8N10D6, & + EddVisT8N11D6,EddVisT8N12D6,EddVisT8N13D6,EddVisT8N14D6,EddVisT8N15D6,EddVisT8N16D6,EddVisT8N17D6,EddVisT8N18D6,EddVisT8N19D6,EddVisT8N20D6, & + EddVisT8N01D7,EddVisT8N02D7,EddVisT8N03D7,EddVisT8N04D7,EddVisT8N05D7,EddVisT8N06D7,EddVisT8N07D7,EddVisT8N08D7,EddVisT8N09D7,EddVisT8N10D7, & + EddVisT8N11D7,EddVisT8N12D7,EddVisT8N13D7,EddVisT8N14D7,EddVisT8N15D7,EddVisT8N16D7,EddVisT8N17D7,EddVisT8N18D7,EddVisT8N19D7,EddVisT8N20D7, & + EddVisT8N01D8,EddVisT8N02D8,EddVisT8N03D8,EddVisT8N04D8,EddVisT8N05D8,EddVisT8N06D8,EddVisT8N07D8,EddVisT8N08D8,EddVisT8N09D8,EddVisT8N10D8, & + EddVisT8N11D8,EddVisT8N12D8,EddVisT8N13D8,EddVisT8N14D8,EddVisT8N15D8,EddVisT8N16D8,EddVisT8N17D8,EddVisT8N18D8,EddVisT8N19D8,EddVisT8N20D8, & + EddVisT8N01D9,EddVisT8N02D9,EddVisT8N03D9,EddVisT8N04D9,EddVisT8N05D9,EddVisT8N06D9,EddVisT8N07D9,EddVisT8N08D9,EddVisT8N09D9,EddVisT8N10D9, & + EddVisT8N11D9,EddVisT8N12D9,EddVisT8N13D9,EddVisT8N14D9,EddVisT8N15D9,EddVisT8N16D9,EddVisT8N17D9,EddVisT8N18D9,EddVisT8N19D9,EddVisT8N20D9/), (/20,9/) ) +EddVisTND(:,:,9) = RESHAPE( & + (/EddVisT9N01D1,EddVisT9N02D1,EddVisT9N03D1,EddVisT9N04D1,EddVisT9N05D1,EddVisT9N06D1,EddVisT9N07D1,EddVisT9N08D1,EddVisT9N09D1,EddVisT9N10D1, & + EddVisT9N11D1,EddVisT9N12D1,EddVisT9N13D1,EddVisT9N14D1,EddVisT9N15D1,EddVisT9N16D1,EddVisT9N17D1,EddVisT9N18D1,EddVisT9N19D1,EddVisT9N20D1, & + EddVisT9N01D2,EddVisT9N02D2,EddVisT9N03D2,EddVisT9N04D2,EddVisT9N05D2,EddVisT9N06D2,EddVisT9N07D2,EddVisT9N08D2,EddVisT9N09D2,EddVisT9N10D2, & + EddVisT9N11D2,EddVisT9N12D2,EddVisT9N13D2,EddVisT9N14D2,EddVisT9N15D2,EddVisT9N16D2,EddVisT9N17D2,EddVisT9N18D2,EddVisT9N19D2,EddVisT9N20D2, & + EddVisT9N01D3,EddVisT9N02D3,EddVisT9N03D3,EddVisT9N04D3,EddVisT9N05D3,EddVisT9N06D3,EddVisT9N07D3,EddVisT9N08D3,EddVisT9N09D3,EddVisT9N10D3, & + EddVisT9N11D3,EddVisT9N12D3,EddVisT9N13D3,EddVisT9N14D3,EddVisT9N15D3,EddVisT9N16D3,EddVisT9N17D3,EddVisT9N18D3,EddVisT9N19D3,EddVisT9N20D3, & + EddVisT9N01D4,EddVisT9N02D4,EddVisT9N03D4,EddVisT9N04D4,EddVisT9N05D4,EddVisT9N06D4,EddVisT9N07D4,EddVisT9N08D4,EddVisT9N09D4,EddVisT9N10D4, & + EddVisT9N11D4,EddVisT9N12D4,EddVisT9N13D4,EddVisT9N14D4,EddVisT9N15D4,EddVisT9N16D4,EddVisT9N17D4,EddVisT9N18D4,EddVisT9N19D4,EddVisT9N20D4, & + EddVisT9N01D5,EddVisT9N02D5,EddVisT9N03D5,EddVisT9N04D5,EddVisT9N05D5,EddVisT9N06D5,EddVisT9N07D5,EddVisT9N08D5,EddVisT9N09D5,EddVisT9N10D5, & + EddVisT9N11D5,EddVisT9N12D5,EddVisT9N13D5,EddVisT9N14D5,EddVisT9N15D5,EddVisT9N16D5,EddVisT9N17D5,EddVisT9N18D5,EddVisT9N19D5,EddVisT9N20D5, & + EddVisT9N01D6,EddVisT9N02D6,EddVisT9N03D6,EddVisT9N04D6,EddVisT9N05D6,EddVisT9N06D6,EddVisT9N07D6,EddVisT9N08D6,EddVisT9N09D6,EddVisT9N10D6, & + EddVisT9N11D6,EddVisT9N12D6,EddVisT9N13D6,EddVisT9N14D6,EddVisT9N15D6,EddVisT9N16D6,EddVisT9N17D6,EddVisT9N18D6,EddVisT9N19D6,EddVisT9N20D6, & + EddVisT9N01D7,EddVisT9N02D7,EddVisT9N03D7,EddVisT9N04D7,EddVisT9N05D7,EddVisT9N06D7,EddVisT9N07D7,EddVisT9N08D7,EddVisT9N09D7,EddVisT9N10D7, & + EddVisT9N11D7,EddVisT9N12D7,EddVisT9N13D7,EddVisT9N14D7,EddVisT9N15D7,EddVisT9N16D7,EddVisT9N17D7,EddVisT9N18D7,EddVisT9N19D7,EddVisT9N20D7, & + EddVisT9N01D8,EddVisT9N02D8,EddVisT9N03D8,EddVisT9N04D8,EddVisT9N05D8,EddVisT9N06D8,EddVisT9N07D8,EddVisT9N08D8,EddVisT9N09D8,EddVisT9N10D8, & + EddVisT9N11D8,EddVisT9N12D8,EddVisT9N13D8,EddVisT9N14D8,EddVisT9N15D8,EddVisT9N16D8,EddVisT9N17D8,EddVisT9N18D8,EddVisT9N19D8,EddVisT9N20D8, & + EddVisT9N01D9,EddVisT9N02D9,EddVisT9N03D9,EddVisT9N04D9,EddVisT9N05D9,EddVisT9N06D9,EddVisT9N07D9,EddVisT9N08D9,EddVisT9N09D9,EddVisT9N10D9, & + EddVisT9N11D9,EddVisT9N12D9,EddVisT9N13D9,EddVisT9N14D9,EddVisT9N15D9,EddVisT9N16D9,EddVisT9N17D9,EddVisT9N18D9,EddVisT9N19D9,EddVisT9N20D9/), (/20,9/) ) + + +EddAmbTND(:,:,1) = RESHAPE( & + (/EddAmbT1N01D1,EddAmbT1N02D1,EddAmbT1N03D1,EddAmbT1N04D1,EddAmbT1N05D1,EddAmbT1N06D1,EddAmbT1N07D1,EddAmbT1N08D1,EddAmbT1N09D1,EddAmbT1N10D1, & + EddAmbT1N11D1,EddAmbT1N12D1,EddAmbT1N13D1,EddAmbT1N14D1,EddAmbT1N15D1,EddAmbT1N16D1,EddAmbT1N17D1,EddAmbT1N18D1,EddAmbT1N19D1,EddAmbT1N20D1, & + EddAmbT1N01D2,EddAmbT1N02D2,EddAmbT1N03D2,EddAmbT1N04D2,EddAmbT1N05D2,EddAmbT1N06D2,EddAmbT1N07D2,EddAmbT1N08D2,EddAmbT1N09D2,EddAmbT1N10D2, & + EddAmbT1N11D2,EddAmbT1N12D2,EddAmbT1N13D2,EddAmbT1N14D2,EddAmbT1N15D2,EddAmbT1N16D2,EddAmbT1N17D2,EddAmbT1N18D2,EddAmbT1N19D2,EddAmbT1N20D2, & + EddAmbT1N01D3,EddAmbT1N02D3,EddAmbT1N03D3,EddAmbT1N04D3,EddAmbT1N05D3,EddAmbT1N06D3,EddAmbT1N07D3,EddAmbT1N08D3,EddAmbT1N09D3,EddAmbT1N10D3, & + EddAmbT1N11D3,EddAmbT1N12D3,EddAmbT1N13D3,EddAmbT1N14D3,EddAmbT1N15D3,EddAmbT1N16D3,EddAmbT1N17D3,EddAmbT1N18D3,EddAmbT1N19D3,EddAmbT1N20D3, & + EddAmbT1N01D4,EddAmbT1N02D4,EddAmbT1N03D4,EddAmbT1N04D4,EddAmbT1N05D4,EddAmbT1N06D4,EddAmbT1N07D4,EddAmbT1N08D4,EddAmbT1N09D4,EddAmbT1N10D4, & + EddAmbT1N11D4,EddAmbT1N12D4,EddAmbT1N13D4,EddAmbT1N14D4,EddAmbT1N15D4,EddAmbT1N16D4,EddAmbT1N17D4,EddAmbT1N18D4,EddAmbT1N19D4,EddAmbT1N20D4, & + EddAmbT1N01D5,EddAmbT1N02D5,EddAmbT1N03D5,EddAmbT1N04D5,EddAmbT1N05D5,EddAmbT1N06D5,EddAmbT1N07D5,EddAmbT1N08D5,EddAmbT1N09D5,EddAmbT1N10D5, & + EddAmbT1N11D5,EddAmbT1N12D5,EddAmbT1N13D5,EddAmbT1N14D5,EddAmbT1N15D5,EddAmbT1N16D5,EddAmbT1N17D5,EddAmbT1N18D5,EddAmbT1N19D5,EddAmbT1N20D5, & + EddAmbT1N01D6,EddAmbT1N02D6,EddAmbT1N03D6,EddAmbT1N04D6,EddAmbT1N05D6,EddAmbT1N06D6,EddAmbT1N07D6,EddAmbT1N08D6,EddAmbT1N09D6,EddAmbT1N10D6, & + EddAmbT1N11D6,EddAmbT1N12D6,EddAmbT1N13D6,EddAmbT1N14D6,EddAmbT1N15D6,EddAmbT1N16D6,EddAmbT1N17D6,EddAmbT1N18D6,EddAmbT1N19D6,EddAmbT1N20D6, & + EddAmbT1N01D7,EddAmbT1N02D7,EddAmbT1N03D7,EddAmbT1N04D7,EddAmbT1N05D7,EddAmbT1N06D7,EddAmbT1N07D7,EddAmbT1N08D7,EddAmbT1N09D7,EddAmbT1N10D7, & + EddAmbT1N11D7,EddAmbT1N12D7,EddAmbT1N13D7,EddAmbT1N14D7,EddAmbT1N15D7,EddAmbT1N16D7,EddAmbT1N17D7,EddAmbT1N18D7,EddAmbT1N19D7,EddAmbT1N20D7, & + EddAmbT1N01D8,EddAmbT1N02D8,EddAmbT1N03D8,EddAmbT1N04D8,EddAmbT1N05D8,EddAmbT1N06D8,EddAmbT1N07D8,EddAmbT1N08D8,EddAmbT1N09D8,EddAmbT1N10D8, & + EddAmbT1N11D8,EddAmbT1N12D8,EddAmbT1N13D8,EddAmbT1N14D8,EddAmbT1N15D8,EddAmbT1N16D8,EddAmbT1N17D8,EddAmbT1N18D8,EddAmbT1N19D8,EddAmbT1N20D8, & + EddAmbT1N01D9,EddAmbT1N02D9,EddAmbT1N03D9,EddAmbT1N04D9,EddAmbT1N05D9,EddAmbT1N06D9,EddAmbT1N07D9,EddAmbT1N08D9,EddAmbT1N09D9,EddAmbT1N10D9, & + EddAmbT1N11D9,EddAmbT1N12D9,EddAmbT1N13D9,EddAmbT1N14D9,EddAmbT1N15D9,EddAmbT1N16D9,EddAmbT1N17D9,EddAmbT1N18D9,EddAmbT1N19D9,EddAmbT1N20D9/), (/20,9/) ) +EddAmbTND(:,:,2) = RESHAPE( & + (/EddAmbT2N01D1,EddAmbT2N02D1,EddAmbT2N03D1,EddAmbT2N04D1,EddAmbT2N05D1,EddAmbT2N06D1,EddAmbT2N07D1,EddAmbT2N08D1,EddAmbT2N09D1,EddAmbT2N10D1, & + EddAmbT2N11D1,EddAmbT2N12D1,EddAmbT2N13D1,EddAmbT2N14D1,EddAmbT2N15D1,EddAmbT2N16D1,EddAmbT2N17D1,EddAmbT2N18D1,EddAmbT2N19D1,EddAmbT2N20D1, & + EddAmbT2N01D2,EddAmbT2N02D2,EddAmbT2N03D2,EddAmbT2N04D2,EddAmbT2N05D2,EddAmbT2N06D2,EddAmbT2N07D2,EddAmbT2N08D2,EddAmbT2N09D2,EddAmbT2N10D2, & + EddAmbT2N11D2,EddAmbT2N12D2,EddAmbT2N13D2,EddAmbT2N14D2,EddAmbT2N15D2,EddAmbT2N16D2,EddAmbT2N17D2,EddAmbT2N18D2,EddAmbT2N19D2,EddAmbT2N20D2, & + EddAmbT2N01D3,EddAmbT2N02D3,EddAmbT2N03D3,EddAmbT2N04D3,EddAmbT2N05D3,EddAmbT2N06D3,EddAmbT2N07D3,EddAmbT2N08D3,EddAmbT2N09D3,EddAmbT2N10D3, & + EddAmbT2N11D3,EddAmbT2N12D3,EddAmbT2N13D3,EddAmbT2N14D3,EddAmbT2N15D3,EddAmbT2N16D3,EddAmbT2N17D3,EddAmbT2N18D3,EddAmbT2N19D3,EddAmbT2N20D3, & + EddAmbT2N01D4,EddAmbT2N02D4,EddAmbT2N03D4,EddAmbT2N04D4,EddAmbT2N05D4,EddAmbT2N06D4,EddAmbT2N07D4,EddAmbT2N08D4,EddAmbT2N09D4,EddAmbT2N10D4, & + EddAmbT2N11D4,EddAmbT2N12D4,EddAmbT2N13D4,EddAmbT2N14D4,EddAmbT2N15D4,EddAmbT2N16D4,EddAmbT2N17D4,EddAmbT2N18D4,EddAmbT2N19D4,EddAmbT2N20D4, & + EddAmbT2N01D5,EddAmbT2N02D5,EddAmbT2N03D5,EddAmbT2N04D5,EddAmbT2N05D5,EddAmbT2N06D5,EddAmbT2N07D5,EddAmbT2N08D5,EddAmbT2N09D5,EddAmbT2N10D5, & + EddAmbT2N11D5,EddAmbT2N12D5,EddAmbT2N13D5,EddAmbT2N14D5,EddAmbT2N15D5,EddAmbT2N16D5,EddAmbT2N17D5,EddAmbT2N18D5,EddAmbT2N19D5,EddAmbT2N20D5, & + EddAmbT2N01D6,EddAmbT2N02D6,EddAmbT2N03D6,EddAmbT2N04D6,EddAmbT2N05D6,EddAmbT2N06D6,EddAmbT2N07D6,EddAmbT2N08D6,EddAmbT2N09D6,EddAmbT2N10D6, & + EddAmbT2N11D6,EddAmbT2N12D6,EddAmbT2N13D6,EddAmbT2N14D6,EddAmbT2N15D6,EddAmbT2N16D6,EddAmbT2N17D6,EddAmbT2N18D6,EddAmbT2N19D6,EddAmbT2N20D6, & + EddAmbT2N01D7,EddAmbT2N02D7,EddAmbT2N03D7,EddAmbT2N04D7,EddAmbT2N05D7,EddAmbT2N06D7,EddAmbT2N07D7,EddAmbT2N08D7,EddAmbT2N09D7,EddAmbT2N10D7, & + EddAmbT2N11D7,EddAmbT2N12D7,EddAmbT2N13D7,EddAmbT2N14D7,EddAmbT2N15D7,EddAmbT2N16D7,EddAmbT2N17D7,EddAmbT2N18D7,EddAmbT2N19D7,EddAmbT2N20D7, & + EddAmbT2N01D8,EddAmbT2N02D8,EddAmbT2N03D8,EddAmbT2N04D8,EddAmbT2N05D8,EddAmbT2N06D8,EddAmbT2N07D8,EddAmbT2N08D8,EddAmbT2N09D8,EddAmbT2N10D8, & + EddAmbT2N11D8,EddAmbT2N12D8,EddAmbT2N13D8,EddAmbT2N14D8,EddAmbT2N15D8,EddAmbT2N16D8,EddAmbT2N17D8,EddAmbT2N18D8,EddAmbT2N19D8,EddAmbT2N20D8, & + EddAmbT2N01D9,EddAmbT2N02D9,EddAmbT2N03D9,EddAmbT2N04D9,EddAmbT2N05D9,EddAmbT2N06D9,EddAmbT2N07D9,EddAmbT2N08D9,EddAmbT2N09D9,EddAmbT2N10D9, & + EddAmbT2N11D9,EddAmbT2N12D9,EddAmbT2N13D9,EddAmbT2N14D9,EddAmbT2N15D9,EddAmbT2N16D9,EddAmbT2N17D9,EddAmbT2N18D9,EddAmbT2N19D9,EddAmbT2N20D9/), (/20,9/) ) +EddAmbTND(:,:,3) = RESHAPE( & + (/EddAmbT3N01D1,EddAmbT3N02D1,EddAmbT3N03D1,EddAmbT3N04D1,EddAmbT3N05D1,EddAmbT3N06D1,EddAmbT3N07D1,EddAmbT3N08D1,EddAmbT3N09D1,EddAmbT3N10D1, & + EddAmbT3N11D1,EddAmbT3N12D1,EddAmbT3N13D1,EddAmbT3N14D1,EddAmbT3N15D1,EddAmbT3N16D1,EddAmbT3N17D1,EddAmbT3N18D1,EddAmbT3N19D1,EddAmbT3N20D1, & + EddAmbT3N01D2,EddAmbT3N02D2,EddAmbT3N03D2,EddAmbT3N04D2,EddAmbT3N05D2,EddAmbT3N06D2,EddAmbT3N07D2,EddAmbT3N08D2,EddAmbT3N09D2,EddAmbT3N10D2, & + EddAmbT3N11D2,EddAmbT3N12D2,EddAmbT3N13D2,EddAmbT3N14D2,EddAmbT3N15D2,EddAmbT3N16D2,EddAmbT3N17D2,EddAmbT3N18D2,EddAmbT3N19D2,EddAmbT3N20D2, & + EddAmbT3N01D3,EddAmbT3N02D3,EddAmbT3N03D3,EddAmbT3N04D3,EddAmbT3N05D3,EddAmbT3N06D3,EddAmbT3N07D3,EddAmbT3N08D3,EddAmbT3N09D3,EddAmbT3N10D3, & + EddAmbT3N11D3,EddAmbT3N12D3,EddAmbT3N13D3,EddAmbT3N14D3,EddAmbT3N15D3,EddAmbT3N16D3,EddAmbT3N17D3,EddAmbT3N18D3,EddAmbT3N19D3,EddAmbT3N20D3, & + EddAmbT3N01D4,EddAmbT3N02D4,EddAmbT3N03D4,EddAmbT3N04D4,EddAmbT3N05D4,EddAmbT3N06D4,EddAmbT3N07D4,EddAmbT3N08D4,EddAmbT3N09D4,EddAmbT3N10D4, & + EddAmbT3N11D4,EddAmbT3N12D4,EddAmbT3N13D4,EddAmbT3N14D4,EddAmbT3N15D4,EddAmbT3N16D4,EddAmbT3N17D4,EddAmbT3N18D4,EddAmbT3N19D4,EddAmbT3N20D4, & + EddAmbT3N01D5,EddAmbT3N02D5,EddAmbT3N03D5,EddAmbT3N04D5,EddAmbT3N05D5,EddAmbT3N06D5,EddAmbT3N07D5,EddAmbT3N08D5,EddAmbT3N09D5,EddAmbT3N10D5, & + EddAmbT3N11D5,EddAmbT3N12D5,EddAmbT3N13D5,EddAmbT3N14D5,EddAmbT3N15D5,EddAmbT3N16D5,EddAmbT3N17D5,EddAmbT3N18D5,EddAmbT3N19D5,EddAmbT3N20D5, & + EddAmbT3N01D6,EddAmbT3N02D6,EddAmbT3N03D6,EddAmbT3N04D6,EddAmbT3N05D6,EddAmbT3N06D6,EddAmbT3N07D6,EddAmbT3N08D6,EddAmbT3N09D6,EddAmbT3N10D6, & + EddAmbT3N11D6,EddAmbT3N12D6,EddAmbT3N13D6,EddAmbT3N14D6,EddAmbT3N15D6,EddAmbT3N16D6,EddAmbT3N17D6,EddAmbT3N18D6,EddAmbT3N19D6,EddAmbT3N20D6, & + EddAmbT3N01D7,EddAmbT3N02D7,EddAmbT3N03D7,EddAmbT3N04D7,EddAmbT3N05D7,EddAmbT3N06D7,EddAmbT3N07D7,EddAmbT3N08D7,EddAmbT3N09D7,EddAmbT3N10D7, & + EddAmbT3N11D7,EddAmbT3N12D7,EddAmbT3N13D7,EddAmbT3N14D7,EddAmbT3N15D7,EddAmbT3N16D7,EddAmbT3N17D7,EddAmbT3N18D7,EddAmbT3N19D7,EddAmbT3N20D7, & + EddAmbT3N01D8,EddAmbT3N02D8,EddAmbT3N03D8,EddAmbT3N04D8,EddAmbT3N05D8,EddAmbT3N06D8,EddAmbT3N07D8,EddAmbT3N08D8,EddAmbT3N09D8,EddAmbT3N10D8, & + EddAmbT3N11D8,EddAmbT3N12D8,EddAmbT3N13D8,EddAmbT3N14D8,EddAmbT3N15D8,EddAmbT3N16D8,EddAmbT3N17D8,EddAmbT3N18D8,EddAmbT3N19D8,EddAmbT3N20D8, & + EddAmbT3N01D9,EddAmbT3N02D9,EddAmbT3N03D9,EddAmbT3N04D9,EddAmbT3N05D9,EddAmbT3N06D9,EddAmbT3N07D9,EddAmbT3N08D9,EddAmbT3N09D9,EddAmbT3N10D9, & + EddAmbT3N11D9,EddAmbT3N12D9,EddAmbT3N13D9,EddAmbT3N14D9,EddAmbT3N15D9,EddAmbT3N16D9,EddAmbT3N17D9,EddAmbT3N18D9,EddAmbT3N19D9,EddAmbT3N20D9/), (/20,9/) ) +EddAmbTND(:,:,4) = RESHAPE( & + (/EddAmbT4N01D1,EddAmbT4N02D1,EddAmbT4N03D1,EddAmbT4N04D1,EddAmbT4N05D1,EddAmbT4N06D1,EddAmbT4N07D1,EddAmbT4N08D1,EddAmbT4N09D1,EddAmbT4N10D1, & + EddAmbT4N11D1,EddAmbT4N12D1,EddAmbT4N13D1,EddAmbT4N14D1,EddAmbT4N15D1,EddAmbT4N16D1,EddAmbT4N17D1,EddAmbT4N18D1,EddAmbT4N19D1,EddAmbT4N20D1, & + EddAmbT4N01D2,EddAmbT4N02D2,EddAmbT4N03D2,EddAmbT4N04D2,EddAmbT4N05D2,EddAmbT4N06D2,EddAmbT4N07D2,EddAmbT4N08D2,EddAmbT4N09D2,EddAmbT4N10D2, & + EddAmbT4N11D2,EddAmbT4N12D2,EddAmbT4N13D2,EddAmbT4N14D2,EddAmbT4N15D2,EddAmbT4N16D2,EddAmbT4N17D2,EddAmbT4N18D2,EddAmbT4N19D2,EddAmbT4N20D2, & + EddAmbT4N01D3,EddAmbT4N02D3,EddAmbT4N03D3,EddAmbT4N04D3,EddAmbT4N05D3,EddAmbT4N06D3,EddAmbT4N07D3,EddAmbT4N08D3,EddAmbT4N09D3,EddAmbT4N10D3, & + EddAmbT4N11D3,EddAmbT4N12D3,EddAmbT4N13D3,EddAmbT4N14D3,EddAmbT4N15D3,EddAmbT4N16D3,EddAmbT4N17D3,EddAmbT4N18D3,EddAmbT4N19D3,EddAmbT4N20D3, & + EddAmbT4N01D4,EddAmbT4N02D4,EddAmbT4N03D4,EddAmbT4N04D4,EddAmbT4N05D4,EddAmbT4N06D4,EddAmbT4N07D4,EddAmbT4N08D4,EddAmbT4N09D4,EddAmbT4N10D4, & + EddAmbT4N11D4,EddAmbT4N12D4,EddAmbT4N13D4,EddAmbT4N14D4,EddAmbT4N15D4,EddAmbT4N16D4,EddAmbT4N17D4,EddAmbT4N18D4,EddAmbT4N19D4,EddAmbT4N20D4, & + EddAmbT4N01D5,EddAmbT4N02D5,EddAmbT4N03D5,EddAmbT4N04D5,EddAmbT4N05D5,EddAmbT4N06D5,EddAmbT4N07D5,EddAmbT4N08D5,EddAmbT4N09D5,EddAmbT4N10D5, & + EddAmbT4N11D5,EddAmbT4N12D5,EddAmbT4N13D5,EddAmbT4N14D5,EddAmbT4N15D5,EddAmbT4N16D5,EddAmbT4N17D5,EddAmbT4N18D5,EddAmbT4N19D5,EddAmbT4N20D5, & + EddAmbT4N01D6,EddAmbT4N02D6,EddAmbT4N03D6,EddAmbT4N04D6,EddAmbT4N05D6,EddAmbT4N06D6,EddAmbT4N07D6,EddAmbT4N08D6,EddAmbT4N09D6,EddAmbT4N10D6, & + EddAmbT4N11D6,EddAmbT4N12D6,EddAmbT4N13D6,EddAmbT4N14D6,EddAmbT4N15D6,EddAmbT4N16D6,EddAmbT4N17D6,EddAmbT4N18D6,EddAmbT4N19D6,EddAmbT4N20D6, & + EddAmbT4N01D7,EddAmbT4N02D7,EddAmbT4N03D7,EddAmbT4N04D7,EddAmbT4N05D7,EddAmbT4N06D7,EddAmbT4N07D7,EddAmbT4N08D7,EddAmbT4N09D7,EddAmbT4N10D7, & + EddAmbT4N11D7,EddAmbT4N12D7,EddAmbT4N13D7,EddAmbT4N14D7,EddAmbT4N15D7,EddAmbT4N16D7,EddAmbT4N17D7,EddAmbT4N18D7,EddAmbT4N19D7,EddAmbT4N20D7, & + EddAmbT4N01D8,EddAmbT4N02D8,EddAmbT4N03D8,EddAmbT4N04D8,EddAmbT4N05D8,EddAmbT4N06D8,EddAmbT4N07D8,EddAmbT4N08D8,EddAmbT4N09D8,EddAmbT4N10D8, & + EddAmbT4N11D8,EddAmbT4N12D8,EddAmbT4N13D8,EddAmbT4N14D8,EddAmbT4N15D8,EddAmbT4N16D8,EddAmbT4N17D8,EddAmbT4N18D8,EddAmbT4N19D8,EddAmbT4N20D8, & + EddAmbT4N01D9,EddAmbT4N02D9,EddAmbT4N03D9,EddAmbT4N04D9,EddAmbT4N05D9,EddAmbT4N06D9,EddAmbT4N07D9,EddAmbT4N08D9,EddAmbT4N09D9,EddAmbT4N10D9, & + EddAmbT4N11D9,EddAmbT4N12D9,EddAmbT4N13D9,EddAmbT4N14D9,EddAmbT4N15D9,EddAmbT4N16D9,EddAmbT4N17D9,EddAmbT4N18D9,EddAmbT4N19D9,EddAmbT4N20D9/), (/20,9/) ) + +EddAmbTND(:,:,5) = RESHAPE( & + (/EddAmbT5N01D1,EddAmbT5N02D1,EddAmbT5N03D1,EddAmbT5N04D1,EddAmbT5N05D1,EddAmbT5N06D1,EddAmbT5N07D1,EddAmbT5N08D1,EddAmbT5N09D1,EddAmbT5N10D1, & + EddAmbT5N11D1,EddAmbT5N12D1,EddAmbT5N13D1,EddAmbT5N14D1,EddAmbT5N15D1,EddAmbT5N16D1,EddAmbT5N17D1,EddAmbT5N18D1,EddAmbT5N19D1,EddAmbT5N20D1, & + EddAmbT5N01D2,EddAmbT5N02D2,EddAmbT5N03D2,EddAmbT5N04D2,EddAmbT5N05D2,EddAmbT5N06D2,EddAmbT5N07D2,EddAmbT5N08D2,EddAmbT5N09D2,EddAmbT5N10D2, & + EddAmbT5N11D2,EddAmbT5N12D2,EddAmbT5N13D2,EddAmbT5N14D2,EddAmbT5N15D2,EddAmbT5N16D2,EddAmbT5N17D2,EddAmbT5N18D2,EddAmbT5N19D2,EddAmbT5N20D2, & + EddAmbT5N01D3,EddAmbT5N02D3,EddAmbT5N03D3,EddAmbT5N04D3,EddAmbT5N05D3,EddAmbT5N06D3,EddAmbT5N07D3,EddAmbT5N08D3,EddAmbT5N09D3,EddAmbT5N10D3, & + EddAmbT5N11D3,EddAmbT5N12D3,EddAmbT5N13D3,EddAmbT5N14D3,EddAmbT5N15D3,EddAmbT5N16D3,EddAmbT5N17D3,EddAmbT5N18D3,EddAmbT5N19D3,EddAmbT5N20D3, & + EddAmbT5N01D4,EddAmbT5N02D4,EddAmbT5N03D4,EddAmbT5N04D4,EddAmbT5N05D4,EddAmbT5N06D4,EddAmbT5N07D4,EddAmbT5N08D4,EddAmbT5N09D4,EddAmbT5N10D4, & + EddAmbT5N11D4,EddAmbT5N12D4,EddAmbT5N13D4,EddAmbT5N14D4,EddAmbT5N15D4,EddAmbT5N16D4,EddAmbT5N17D4,EddAmbT5N18D4,EddAmbT5N19D4,EddAmbT5N20D4, & + EddAmbT5N01D5,EddAmbT5N02D5,EddAmbT5N03D5,EddAmbT5N04D5,EddAmbT5N05D5,EddAmbT5N06D5,EddAmbT5N07D5,EddAmbT5N08D5,EddAmbT5N09D5,EddAmbT5N10D5, & + EddAmbT5N11D5,EddAmbT5N12D5,EddAmbT5N13D5,EddAmbT5N14D5,EddAmbT5N15D5,EddAmbT5N16D5,EddAmbT5N17D5,EddAmbT5N18D5,EddAmbT5N19D5,EddAmbT5N20D5, & + EddAmbT5N01D6,EddAmbT5N02D6,EddAmbT5N03D6,EddAmbT5N04D6,EddAmbT5N05D6,EddAmbT5N06D6,EddAmbT5N07D6,EddAmbT5N08D6,EddAmbT5N09D6,EddAmbT5N10D6, & + EddAmbT5N11D6,EddAmbT5N12D6,EddAmbT5N13D6,EddAmbT5N14D6,EddAmbT5N15D6,EddAmbT5N16D6,EddAmbT5N17D6,EddAmbT5N18D6,EddAmbT5N19D6,EddAmbT5N20D6, & + EddAmbT5N01D7,EddAmbT5N02D7,EddAmbT5N03D7,EddAmbT5N04D7,EddAmbT5N05D7,EddAmbT5N06D7,EddAmbT5N07D7,EddAmbT5N08D7,EddAmbT5N09D7,EddAmbT5N10D7, & + EddAmbT5N11D7,EddAmbT5N12D7,EddAmbT5N13D7,EddAmbT5N14D7,EddAmbT5N15D7,EddAmbT5N16D7,EddAmbT5N17D7,EddAmbT5N18D7,EddAmbT5N19D7,EddAmbT5N20D7, & + EddAmbT5N01D8,EddAmbT5N02D8,EddAmbT5N03D8,EddAmbT5N04D8,EddAmbT5N05D8,EddAmbT5N06D8,EddAmbT5N07D8,EddAmbT5N08D8,EddAmbT5N09D8,EddAmbT5N10D8, & + EddAmbT5N11D8,EddAmbT5N12D8,EddAmbT5N13D8,EddAmbT5N14D8,EddAmbT5N15D8,EddAmbT5N16D8,EddAmbT5N17D8,EddAmbT5N18D8,EddAmbT5N19D8,EddAmbT5N20D8, & + EddAmbT5N01D9,EddAmbT5N02D9,EddAmbT5N03D9,EddAmbT5N04D9,EddAmbT5N05D9,EddAmbT5N06D9,EddAmbT5N07D9,EddAmbT5N08D9,EddAmbT5N09D9,EddAmbT5N10D9, & + EddAmbT5N11D9,EddAmbT5N12D9,EddAmbT5N13D9,EddAmbT5N14D9,EddAmbT5N15D9,EddAmbT5N16D9,EddAmbT5N17D9,EddAmbT5N18D9,EddAmbT5N19D9,EddAmbT5N20D9/), (/20,9/) ) +EddAmbTND(:,:,6) = RESHAPE( & + (/EddAmbT6N01D1,EddAmbT6N02D1,EddAmbT6N03D1,EddAmbT6N04D1,EddAmbT6N05D1,EddAmbT6N06D1,EddAmbT6N07D1,EddAmbT6N08D1,EddAmbT6N09D1,EddAmbT6N10D1, & + EddAmbT6N11D1,EddAmbT6N12D1,EddAmbT6N13D1,EddAmbT6N14D1,EddAmbT6N15D1,EddAmbT6N16D1,EddAmbT6N17D1,EddAmbT6N18D1,EddAmbT6N19D1,EddAmbT6N20D1, & + EddAmbT6N01D2,EddAmbT6N02D2,EddAmbT6N03D2,EddAmbT6N04D2,EddAmbT6N05D2,EddAmbT6N06D2,EddAmbT6N07D2,EddAmbT6N08D2,EddAmbT6N09D2,EddAmbT6N10D2, & + EddAmbT6N11D2,EddAmbT6N12D2,EddAmbT6N13D2,EddAmbT6N14D2,EddAmbT6N15D2,EddAmbT6N16D2,EddAmbT6N17D2,EddAmbT6N18D2,EddAmbT6N19D2,EddAmbT6N20D2, & + EddAmbT6N01D3,EddAmbT6N02D3,EddAmbT6N03D3,EddAmbT6N04D3,EddAmbT6N05D3,EddAmbT6N06D3,EddAmbT6N07D3,EddAmbT6N08D3,EddAmbT6N09D3,EddAmbT6N10D3, & + EddAmbT6N11D3,EddAmbT6N12D3,EddAmbT6N13D3,EddAmbT6N14D3,EddAmbT6N15D3,EddAmbT6N16D3,EddAmbT6N17D3,EddAmbT6N18D3,EddAmbT6N19D3,EddAmbT6N20D3, & + EddAmbT6N01D4,EddAmbT6N02D4,EddAmbT6N03D4,EddAmbT6N04D4,EddAmbT6N05D4,EddAmbT6N06D4,EddAmbT6N07D4,EddAmbT6N08D4,EddAmbT6N09D4,EddAmbT6N10D4, & + EddAmbT6N11D4,EddAmbT6N12D4,EddAmbT6N13D4,EddAmbT6N14D4,EddAmbT6N15D4,EddAmbT6N16D4,EddAmbT6N17D4,EddAmbT6N18D4,EddAmbT6N19D4,EddAmbT6N20D4, & + EddAmbT6N01D5,EddAmbT6N02D5,EddAmbT6N03D5,EddAmbT6N04D5,EddAmbT6N05D5,EddAmbT6N06D5,EddAmbT6N07D5,EddAmbT6N08D5,EddAmbT6N09D5,EddAmbT6N10D5, & + EddAmbT6N11D5,EddAmbT6N12D5,EddAmbT6N13D5,EddAmbT6N14D5,EddAmbT6N15D5,EddAmbT6N16D5,EddAmbT6N17D5,EddAmbT6N18D5,EddAmbT6N19D5,EddAmbT6N20D5, & + EddAmbT6N01D6,EddAmbT6N02D6,EddAmbT6N03D6,EddAmbT6N04D6,EddAmbT6N05D6,EddAmbT6N06D6,EddAmbT6N07D6,EddAmbT6N08D6,EddAmbT6N09D6,EddAmbT6N10D6, & + EddAmbT6N11D6,EddAmbT6N12D6,EddAmbT6N13D6,EddAmbT6N14D6,EddAmbT6N15D6,EddAmbT6N16D6,EddAmbT6N17D6,EddAmbT6N18D6,EddAmbT6N19D6,EddAmbT6N20D6, & + EddAmbT6N01D7,EddAmbT6N02D7,EddAmbT6N03D7,EddAmbT6N04D7,EddAmbT6N05D7,EddAmbT6N06D7,EddAmbT6N07D7,EddAmbT6N08D7,EddAmbT6N09D7,EddAmbT6N10D7, & + EddAmbT6N11D7,EddAmbT6N12D7,EddAmbT6N13D7,EddAmbT6N14D7,EddAmbT6N15D7,EddAmbT6N16D7,EddAmbT6N17D7,EddAmbT6N18D7,EddAmbT6N19D7,EddAmbT6N20D7, & + EddAmbT6N01D8,EddAmbT6N02D8,EddAmbT6N03D8,EddAmbT6N04D8,EddAmbT6N05D8,EddAmbT6N06D8,EddAmbT6N07D8,EddAmbT6N08D8,EddAmbT6N09D8,EddAmbT6N10D8, & + EddAmbT6N11D8,EddAmbT6N12D8,EddAmbT6N13D8,EddAmbT6N14D8,EddAmbT6N15D8,EddAmbT6N16D8,EddAmbT6N17D8,EddAmbT6N18D8,EddAmbT6N19D8,EddAmbT6N20D8, & + EddAmbT6N01D9,EddAmbT6N02D9,EddAmbT6N03D9,EddAmbT6N04D9,EddAmbT6N05D9,EddAmbT6N06D9,EddAmbT6N07D9,EddAmbT6N08D9,EddAmbT6N09D9,EddAmbT6N10D9, & + EddAmbT6N11D9,EddAmbT6N12D9,EddAmbT6N13D9,EddAmbT6N14D9,EddAmbT6N15D9,EddAmbT6N16D9,EddAmbT6N17D9,EddAmbT6N18D9,EddAmbT6N19D9,EddAmbT6N20D9/), (/20,9/) ) +EddAmbTND(:,:,7) = RESHAPE( & + (/EddAmbT7N01D1,EddAmbT7N02D1,EddAmbT7N03D1,EddAmbT7N04D1,EddAmbT7N05D1,EddAmbT7N06D1,EddAmbT7N07D1,EddAmbT7N08D1,EddAmbT7N09D1,EddAmbT7N10D1, & + EddAmbT7N11D1,EddAmbT7N12D1,EddAmbT7N13D1,EddAmbT7N14D1,EddAmbT7N15D1,EddAmbT7N16D1,EddAmbT7N17D1,EddAmbT7N18D1,EddAmbT7N19D1,EddAmbT7N20D1, & + EddAmbT7N01D2,EddAmbT7N02D2,EddAmbT7N03D2,EddAmbT7N04D2,EddAmbT7N05D2,EddAmbT7N06D2,EddAmbT7N07D2,EddAmbT7N08D2,EddAmbT7N09D2,EddAmbT7N10D2, & + EddAmbT7N11D2,EddAmbT7N12D2,EddAmbT7N13D2,EddAmbT7N14D2,EddAmbT7N15D2,EddAmbT7N16D2,EddAmbT7N17D2,EddAmbT7N18D2,EddAmbT7N19D2,EddAmbT7N20D2, & + EddAmbT7N01D3,EddAmbT7N02D3,EddAmbT7N03D3,EddAmbT7N04D3,EddAmbT7N05D3,EddAmbT7N06D3,EddAmbT7N07D3,EddAmbT7N08D3,EddAmbT7N09D3,EddAmbT7N10D3, & + EddAmbT7N11D3,EddAmbT7N12D3,EddAmbT7N13D3,EddAmbT7N14D3,EddAmbT7N15D3,EddAmbT7N16D3,EddAmbT7N17D3,EddAmbT7N18D3,EddAmbT7N19D3,EddAmbT7N20D3, & + EddAmbT7N01D4,EddAmbT7N02D4,EddAmbT7N03D4,EddAmbT7N04D4,EddAmbT7N05D4,EddAmbT7N06D4,EddAmbT7N07D4,EddAmbT7N08D4,EddAmbT7N09D4,EddAmbT7N10D4, & + EddAmbT7N11D4,EddAmbT7N12D4,EddAmbT7N13D4,EddAmbT7N14D4,EddAmbT7N15D4,EddAmbT7N16D4,EddAmbT7N17D4,EddAmbT7N18D4,EddAmbT7N19D4,EddAmbT7N20D4, & + EddAmbT7N01D5,EddAmbT7N02D5,EddAmbT7N03D5,EddAmbT7N04D5,EddAmbT7N05D5,EddAmbT7N06D5,EddAmbT7N07D5,EddAmbT7N08D5,EddAmbT7N09D5,EddAmbT7N10D5, & + EddAmbT7N11D5,EddAmbT7N12D5,EddAmbT7N13D5,EddAmbT7N14D5,EddAmbT7N15D5,EddAmbT7N16D5,EddAmbT7N17D5,EddAmbT7N18D5,EddAmbT7N19D5,EddAmbT7N20D5, & + EddAmbT7N01D6,EddAmbT7N02D6,EddAmbT7N03D6,EddAmbT7N04D6,EddAmbT7N05D6,EddAmbT7N06D6,EddAmbT7N07D6,EddAmbT7N08D6,EddAmbT7N09D6,EddAmbT7N10D6, & + EddAmbT7N11D6,EddAmbT7N12D6,EddAmbT7N13D6,EddAmbT7N14D6,EddAmbT7N15D6,EddAmbT7N16D6,EddAmbT7N17D6,EddAmbT7N18D6,EddAmbT7N19D6,EddAmbT7N20D6, & + EddAmbT7N01D7,EddAmbT7N02D7,EddAmbT7N03D7,EddAmbT7N04D7,EddAmbT7N05D7,EddAmbT7N06D7,EddAmbT7N07D7,EddAmbT7N08D7,EddAmbT7N09D7,EddAmbT7N10D7, & + EddAmbT7N11D7,EddAmbT7N12D7,EddAmbT7N13D7,EddAmbT7N14D7,EddAmbT7N15D7,EddAmbT7N16D7,EddAmbT7N17D7,EddAmbT7N18D7,EddAmbT7N19D7,EddAmbT7N20D7, & + EddAmbT7N01D8,EddAmbT7N02D8,EddAmbT7N03D8,EddAmbT7N04D8,EddAmbT7N05D8,EddAmbT7N06D8,EddAmbT7N07D8,EddAmbT7N08D8,EddAmbT7N09D8,EddAmbT7N10D8, & + EddAmbT7N11D8,EddAmbT7N12D8,EddAmbT7N13D8,EddAmbT7N14D8,EddAmbT7N15D8,EddAmbT7N16D8,EddAmbT7N17D8,EddAmbT7N18D8,EddAmbT7N19D8,EddAmbT7N20D8, & + EddAmbT7N01D9,EddAmbT7N02D9,EddAmbT7N03D9,EddAmbT7N04D9,EddAmbT7N05D9,EddAmbT7N06D9,EddAmbT7N07D9,EddAmbT7N08D9,EddAmbT7N09D9,EddAmbT7N10D9, & + EddAmbT7N11D9,EddAmbT7N12D9,EddAmbT7N13D9,EddAmbT7N14D9,EddAmbT7N15D9,EddAmbT7N16D9,EddAmbT7N17D9,EddAmbT7N18D9,EddAmbT7N19D9,EddAmbT7N20D9/), (/20,9/) ) +EddAmbTND(:,:,8) = RESHAPE( & + (/EddAmbT8N01D1,EddAmbT8N02D1,EddAmbT8N03D1,EddAmbT8N04D1,EddAmbT8N05D1,EddAmbT8N06D1,EddAmbT8N07D1,EddAmbT8N08D1,EddAmbT8N09D1,EddAmbT8N10D1, & + EddAmbT8N11D1,EddAmbT8N12D1,EddAmbT8N13D1,EddAmbT8N14D1,EddAmbT8N15D1,EddAmbT8N16D1,EddAmbT8N17D1,EddAmbT8N18D1,EddAmbT8N19D1,EddAmbT8N20D1, & + EddAmbT8N01D2,EddAmbT8N02D2,EddAmbT8N03D2,EddAmbT8N04D2,EddAmbT8N05D2,EddAmbT8N06D2,EddAmbT8N07D2,EddAmbT8N08D2,EddAmbT8N09D2,EddAmbT8N10D2, & + EddAmbT8N11D2,EddAmbT8N12D2,EddAmbT8N13D2,EddAmbT8N14D2,EddAmbT8N15D2,EddAmbT8N16D2,EddAmbT8N17D2,EddAmbT8N18D2,EddAmbT8N19D2,EddAmbT8N20D2, & + EddAmbT8N01D3,EddAmbT8N02D3,EddAmbT8N03D3,EddAmbT8N04D3,EddAmbT8N05D3,EddAmbT8N06D3,EddAmbT8N07D3,EddAmbT8N08D3,EddAmbT8N09D3,EddAmbT8N10D3, & + EddAmbT8N11D3,EddAmbT8N12D3,EddAmbT8N13D3,EddAmbT8N14D3,EddAmbT8N15D3,EddAmbT8N16D3,EddAmbT8N17D3,EddAmbT8N18D3,EddAmbT8N19D3,EddAmbT8N20D3, & + EddAmbT8N01D4,EddAmbT8N02D4,EddAmbT8N03D4,EddAmbT8N04D4,EddAmbT8N05D4,EddAmbT8N06D4,EddAmbT8N07D4,EddAmbT8N08D4,EddAmbT8N09D4,EddAmbT8N10D4, & + EddAmbT8N11D4,EddAmbT8N12D4,EddAmbT8N13D4,EddAmbT8N14D4,EddAmbT8N15D4,EddAmbT8N16D4,EddAmbT8N17D4,EddAmbT8N18D4,EddAmbT8N19D4,EddAmbT8N20D4, & + EddAmbT8N01D5,EddAmbT8N02D5,EddAmbT8N03D5,EddAmbT8N04D5,EddAmbT8N05D5,EddAmbT8N06D5,EddAmbT8N07D5,EddAmbT8N08D5,EddAmbT8N09D5,EddAmbT8N10D5, & + EddAmbT8N11D5,EddAmbT8N12D5,EddAmbT8N13D5,EddAmbT8N14D5,EddAmbT8N15D5,EddAmbT8N16D5,EddAmbT8N17D5,EddAmbT8N18D5,EddAmbT8N19D5,EddAmbT8N20D5, & + EddAmbT8N01D6,EddAmbT8N02D6,EddAmbT8N03D6,EddAmbT8N04D6,EddAmbT8N05D6,EddAmbT8N06D6,EddAmbT8N07D6,EddAmbT8N08D6,EddAmbT8N09D6,EddAmbT8N10D6, & + EddAmbT8N11D6,EddAmbT8N12D6,EddAmbT8N13D6,EddAmbT8N14D6,EddAmbT8N15D6,EddAmbT8N16D6,EddAmbT8N17D6,EddAmbT8N18D6,EddAmbT8N19D6,EddAmbT8N20D6, & + EddAmbT8N01D7,EddAmbT8N02D7,EddAmbT8N03D7,EddAmbT8N04D7,EddAmbT8N05D7,EddAmbT8N06D7,EddAmbT8N07D7,EddAmbT8N08D7,EddAmbT8N09D7,EddAmbT8N10D7, & + EddAmbT8N11D7,EddAmbT8N12D7,EddAmbT8N13D7,EddAmbT8N14D7,EddAmbT8N15D7,EddAmbT8N16D7,EddAmbT8N17D7,EddAmbT8N18D7,EddAmbT8N19D7,EddAmbT8N20D7, & + EddAmbT8N01D8,EddAmbT8N02D8,EddAmbT8N03D8,EddAmbT8N04D8,EddAmbT8N05D8,EddAmbT8N06D8,EddAmbT8N07D8,EddAmbT8N08D8,EddAmbT8N09D8,EddAmbT8N10D8, & + EddAmbT8N11D8,EddAmbT8N12D8,EddAmbT8N13D8,EddAmbT8N14D8,EddAmbT8N15D8,EddAmbT8N16D8,EddAmbT8N17D8,EddAmbT8N18D8,EddAmbT8N19D8,EddAmbT8N20D8, & + EddAmbT8N01D9,EddAmbT8N02D9,EddAmbT8N03D9,EddAmbT8N04D9,EddAmbT8N05D9,EddAmbT8N06D9,EddAmbT8N07D9,EddAmbT8N08D9,EddAmbT8N09D9,EddAmbT8N10D9, & + EddAmbT8N11D9,EddAmbT8N12D9,EddAmbT8N13D9,EddAmbT8N14D9,EddAmbT8N15D9,EddAmbT8N16D9,EddAmbT8N17D9,EddAmbT8N18D9,EddAmbT8N19D9,EddAmbT8N20D9/), (/20,9/) ) +EddAmbTND(:,:,9) = RESHAPE( & + (/EddAmbT9N01D1,EddAmbT9N02D1,EddAmbT9N03D1,EddAmbT9N04D1,EddAmbT9N05D1,EddAmbT9N06D1,EddAmbT9N07D1,EddAmbT9N08D1,EddAmbT9N09D1,EddAmbT9N10D1, & + EddAmbT9N11D1,EddAmbT9N12D1,EddAmbT9N13D1,EddAmbT9N14D1,EddAmbT9N15D1,EddAmbT9N16D1,EddAmbT9N17D1,EddAmbT9N18D1,EddAmbT9N19D1,EddAmbT9N20D1, & + EddAmbT9N01D2,EddAmbT9N02D2,EddAmbT9N03D2,EddAmbT9N04D2,EddAmbT9N05D2,EddAmbT9N06D2,EddAmbT9N07D2,EddAmbT9N08D2,EddAmbT9N09D2,EddAmbT9N10D2, & + EddAmbT9N11D2,EddAmbT9N12D2,EddAmbT9N13D2,EddAmbT9N14D2,EddAmbT9N15D2,EddAmbT9N16D2,EddAmbT9N17D2,EddAmbT9N18D2,EddAmbT9N19D2,EddAmbT9N20D2, & + EddAmbT9N01D3,EddAmbT9N02D3,EddAmbT9N03D3,EddAmbT9N04D3,EddAmbT9N05D3,EddAmbT9N06D3,EddAmbT9N07D3,EddAmbT9N08D3,EddAmbT9N09D3,EddAmbT9N10D3, & + EddAmbT9N11D3,EddAmbT9N12D3,EddAmbT9N13D3,EddAmbT9N14D3,EddAmbT9N15D3,EddAmbT9N16D3,EddAmbT9N17D3,EddAmbT9N18D3,EddAmbT9N19D3,EddAmbT9N20D3, & + EddAmbT9N01D4,EddAmbT9N02D4,EddAmbT9N03D4,EddAmbT9N04D4,EddAmbT9N05D4,EddAmbT9N06D4,EddAmbT9N07D4,EddAmbT9N08D4,EddAmbT9N09D4,EddAmbT9N10D4, & + EddAmbT9N11D4,EddAmbT9N12D4,EddAmbT9N13D4,EddAmbT9N14D4,EddAmbT9N15D4,EddAmbT9N16D4,EddAmbT9N17D4,EddAmbT9N18D4,EddAmbT9N19D4,EddAmbT9N20D4, & + EddAmbT9N01D5,EddAmbT9N02D5,EddAmbT9N03D5,EddAmbT9N04D5,EddAmbT9N05D5,EddAmbT9N06D5,EddAmbT9N07D5,EddAmbT9N08D5,EddAmbT9N09D5,EddAmbT9N10D5, & + EddAmbT9N11D5,EddAmbT9N12D5,EddAmbT9N13D5,EddAmbT9N14D5,EddAmbT9N15D5,EddAmbT9N16D5,EddAmbT9N17D5,EddAmbT9N18D5,EddAmbT9N19D5,EddAmbT9N20D5, & + EddAmbT9N01D6,EddAmbT9N02D6,EddAmbT9N03D6,EddAmbT9N04D6,EddAmbT9N05D6,EddAmbT9N06D6,EddAmbT9N07D6,EddAmbT9N08D6,EddAmbT9N09D6,EddAmbT9N10D6, & + EddAmbT9N11D6,EddAmbT9N12D6,EddAmbT9N13D6,EddAmbT9N14D6,EddAmbT9N15D6,EddAmbT9N16D6,EddAmbT9N17D6,EddAmbT9N18D6,EddAmbT9N19D6,EddAmbT9N20D6, & + EddAmbT9N01D7,EddAmbT9N02D7,EddAmbT9N03D7,EddAmbT9N04D7,EddAmbT9N05D7,EddAmbT9N06D7,EddAmbT9N07D7,EddAmbT9N08D7,EddAmbT9N09D7,EddAmbT9N10D7, & + EddAmbT9N11D7,EddAmbT9N12D7,EddAmbT9N13D7,EddAmbT9N14D7,EddAmbT9N15D7,EddAmbT9N16D7,EddAmbT9N17D7,EddAmbT9N18D7,EddAmbT9N19D7,EddAmbT9N20D7, & + EddAmbT9N01D8,EddAmbT9N02D8,EddAmbT9N03D8,EddAmbT9N04D8,EddAmbT9N05D8,EddAmbT9N06D8,EddAmbT9N07D8,EddAmbT9N08D8,EddAmbT9N09D8,EddAmbT9N10D8, & + EddAmbT9N11D8,EddAmbT9N12D8,EddAmbT9N13D8,EddAmbT9N14D8,EddAmbT9N15D8,EddAmbT9N16D8,EddAmbT9N17D8,EddAmbT9N18D8,EddAmbT9N19D8,EddAmbT9N20D8, & + EddAmbT9N01D9,EddAmbT9N02D9,EddAmbT9N03D9,EddAmbT9N04D9,EddAmbT9N05D9,EddAmbT9N06D9,EddAmbT9N07D9,EddAmbT9N08D9,EddAmbT9N09D9,EddAmbT9N10D9, & + EddAmbT9N11D9,EddAmbT9N12D9,EddAmbT9N13D9,EddAmbT9N14D9,EddAmbT9N15D9,EddAmbT9N16D9,EddAmbT9N17D9,EddAmbT9N18D9,EddAmbT9N19D9,EddAmbT9N20D9/), (/20,9/) ) + + +EddShrTND(:,:,1) = RESHAPE( & + (/EddShrT1N01D1,EddShrT1N02D1,EddShrT1N03D1,EddShrT1N04D1,EddShrT1N05D1,EddShrT1N06D1,EddShrT1N07D1,EddShrT1N08D1,EddShrT1N09D1,EddShrT1N10D1, & + EddShrT1N11D1,EddShrT1N12D1,EddShrT1N13D1,EddShrT1N14D1,EddShrT1N15D1,EddShrT1N16D1,EddShrT1N17D1,EddShrT1N18D1,EddShrT1N19D1,EddShrT1N20D1, & + EddShrT1N01D2,EddShrT1N02D2,EddShrT1N03D2,EddShrT1N04D2,EddShrT1N05D2,EddShrT1N06D2,EddShrT1N07D2,EddShrT1N08D2,EddShrT1N09D2,EddShrT1N10D2, & + EddShrT1N11D2,EddShrT1N12D2,EddShrT1N13D2,EddShrT1N14D2,EddShrT1N15D2,EddShrT1N16D2,EddShrT1N17D2,EddShrT1N18D2,EddShrT1N19D2,EddShrT1N20D2, & + EddShrT1N01D3,EddShrT1N02D3,EddShrT1N03D3,EddShrT1N04D3,EddShrT1N05D3,EddShrT1N06D3,EddShrT1N07D3,EddShrT1N08D3,EddShrT1N09D3,EddShrT1N10D3, & + EddShrT1N11D3,EddShrT1N12D3,EddShrT1N13D3,EddShrT1N14D3,EddShrT1N15D3,EddShrT1N16D3,EddShrT1N17D3,EddShrT1N18D3,EddShrT1N19D3,EddShrT1N20D3, & + EddShrT1N01D4,EddShrT1N02D4,EddShrT1N03D4,EddShrT1N04D4,EddShrT1N05D4,EddShrT1N06D4,EddShrT1N07D4,EddShrT1N08D4,EddShrT1N09D4,EddShrT1N10D4, & + EddShrT1N11D4,EddShrT1N12D4,EddShrT1N13D4,EddShrT1N14D4,EddShrT1N15D4,EddShrT1N16D4,EddShrT1N17D4,EddShrT1N18D4,EddShrT1N19D4,EddShrT1N20D4, & + EddShrT1N01D5,EddShrT1N02D5,EddShrT1N03D5,EddShrT1N04D5,EddShrT1N05D5,EddShrT1N06D5,EddShrT1N07D5,EddShrT1N08D5,EddShrT1N09D5,EddShrT1N10D5, & + EddShrT1N11D5,EddShrT1N12D5,EddShrT1N13D5,EddShrT1N14D5,EddShrT1N15D5,EddShrT1N16D5,EddShrT1N17D5,EddShrT1N18D5,EddShrT1N19D5,EddShrT1N20D5, & + EddShrT1N01D6,EddShrT1N02D6,EddShrT1N03D6,EddShrT1N04D6,EddShrT1N05D6,EddShrT1N06D6,EddShrT1N07D6,EddShrT1N08D6,EddShrT1N09D6,EddShrT1N10D6, & + EddShrT1N11D6,EddShrT1N12D6,EddShrT1N13D6,EddShrT1N14D6,EddShrT1N15D6,EddShrT1N16D6,EddShrT1N17D6,EddShrT1N18D6,EddShrT1N19D6,EddShrT1N20D6, & + EddShrT1N01D7,EddShrT1N02D7,EddShrT1N03D7,EddShrT1N04D7,EddShrT1N05D7,EddShrT1N06D7,EddShrT1N07D7,EddShrT1N08D7,EddShrT1N09D7,EddShrT1N10D7, & + EddShrT1N11D7,EddShrT1N12D7,EddShrT1N13D7,EddShrT1N14D7,EddShrT1N15D7,EddShrT1N16D7,EddShrT1N17D7,EddShrT1N18D7,EddShrT1N19D7,EddShrT1N20D7, & + EddShrT1N01D8,EddShrT1N02D8,EddShrT1N03D8,EddShrT1N04D8,EddShrT1N05D8,EddShrT1N06D8,EddShrT1N07D8,EddShrT1N08D8,EddShrT1N09D8,EddShrT1N10D8, & + EddShrT1N11D8,EddShrT1N12D8,EddShrT1N13D8,EddShrT1N14D8,EddShrT1N15D8,EddShrT1N16D8,EddShrT1N17D8,EddShrT1N18D8,EddShrT1N19D8,EddShrT1N20D8, & + EddShrT1N01D9,EddShrT1N02D9,EddShrT1N03D9,EddShrT1N04D9,EddShrT1N05D9,EddShrT1N06D9,EddShrT1N07D9,EddShrT1N08D9,EddShrT1N09D9,EddShrT1N10D9, & + EddShrT1N11D9,EddShrT1N12D9,EddShrT1N13D9,EddShrT1N14D9,EddShrT1N15D9,EddShrT1N16D9,EddShrT1N17D9,EddShrT1N18D9,EddShrT1N19D9,EddShrT1N20D9/), (/20,9/) ) +EddShrTND(:,:,2) = RESHAPE( & + (/EddShrT2N01D1,EddShrT2N02D1,EddShrT2N03D1,EddShrT2N04D1,EddShrT2N05D1,EddShrT2N06D1,EddShrT2N07D1,EddShrT2N08D1,EddShrT2N09D1,EddShrT2N10D1, & + EddShrT2N11D1,EddShrT2N12D1,EddShrT2N13D1,EddShrT2N14D1,EddShrT2N15D1,EddShrT2N16D1,EddShrT2N17D1,EddShrT2N18D1,EddShrT2N19D1,EddShrT2N20D1, & + EddShrT2N01D2,EddShrT2N02D2,EddShrT2N03D2,EddShrT2N04D2,EddShrT2N05D2,EddShrT2N06D2,EddShrT2N07D2,EddShrT2N08D2,EddShrT2N09D2,EddShrT2N10D2, & + EddShrT2N11D2,EddShrT2N12D2,EddShrT2N13D2,EddShrT2N14D2,EddShrT2N15D2,EddShrT2N16D2,EddShrT2N17D2,EddShrT2N18D2,EddShrT2N19D2,EddShrT2N20D2, & + EddShrT2N01D3,EddShrT2N02D3,EddShrT2N03D3,EddShrT2N04D3,EddShrT2N05D3,EddShrT2N06D3,EddShrT2N07D3,EddShrT2N08D3,EddShrT2N09D3,EddShrT2N10D3, & + EddShrT2N11D3,EddShrT2N12D3,EddShrT2N13D3,EddShrT2N14D3,EddShrT2N15D3,EddShrT2N16D3,EddShrT2N17D3,EddShrT2N18D3,EddShrT2N19D3,EddShrT2N20D3, & + EddShrT2N01D4,EddShrT2N02D4,EddShrT2N03D4,EddShrT2N04D4,EddShrT2N05D4,EddShrT2N06D4,EddShrT2N07D4,EddShrT2N08D4,EddShrT2N09D4,EddShrT2N10D4, & + EddShrT2N11D4,EddShrT2N12D4,EddShrT2N13D4,EddShrT2N14D4,EddShrT2N15D4,EddShrT2N16D4,EddShrT2N17D4,EddShrT2N18D4,EddShrT2N19D4,EddShrT2N20D4, & + EddShrT2N01D5,EddShrT2N02D5,EddShrT2N03D5,EddShrT2N04D5,EddShrT2N05D5,EddShrT2N06D5,EddShrT2N07D5,EddShrT2N08D5,EddShrT2N09D5,EddShrT2N10D5, & + EddShrT2N11D5,EddShrT2N12D5,EddShrT2N13D5,EddShrT2N14D5,EddShrT2N15D5,EddShrT2N16D5,EddShrT2N17D5,EddShrT2N18D5,EddShrT2N19D5,EddShrT2N20D5, & + EddShrT2N01D6,EddShrT2N02D6,EddShrT2N03D6,EddShrT2N04D6,EddShrT2N05D6,EddShrT2N06D6,EddShrT2N07D6,EddShrT2N08D6,EddShrT2N09D6,EddShrT2N10D6, & + EddShrT2N11D6,EddShrT2N12D6,EddShrT2N13D6,EddShrT2N14D6,EddShrT2N15D6,EddShrT2N16D6,EddShrT2N17D6,EddShrT2N18D6,EddShrT2N19D6,EddShrT2N20D6, & + EddShrT2N01D7,EddShrT2N02D7,EddShrT2N03D7,EddShrT2N04D7,EddShrT2N05D7,EddShrT2N06D7,EddShrT2N07D7,EddShrT2N08D7,EddShrT2N09D7,EddShrT2N10D7, & + EddShrT2N11D7,EddShrT2N12D7,EddShrT2N13D7,EddShrT2N14D7,EddShrT2N15D7,EddShrT2N16D7,EddShrT2N17D7,EddShrT2N18D7,EddShrT2N19D7,EddShrT2N20D7, & + EddShrT2N01D8,EddShrT2N02D8,EddShrT2N03D8,EddShrT2N04D8,EddShrT2N05D8,EddShrT2N06D8,EddShrT2N07D8,EddShrT2N08D8,EddShrT2N09D8,EddShrT2N10D8, & + EddShrT2N11D8,EddShrT2N12D8,EddShrT2N13D8,EddShrT2N14D8,EddShrT2N15D8,EddShrT2N16D8,EddShrT2N17D8,EddShrT2N18D8,EddShrT2N19D8,EddShrT2N20D8, & + EddShrT2N01D9,EddShrT2N02D9,EddShrT2N03D9,EddShrT2N04D9,EddShrT2N05D9,EddShrT2N06D9,EddShrT2N07D9,EddShrT2N08D9,EddShrT2N09D9,EddShrT2N10D9, & + EddShrT2N11D9,EddShrT2N12D9,EddShrT2N13D9,EddShrT2N14D9,EddShrT2N15D9,EddShrT2N16D9,EddShrT2N17D9,EddShrT2N18D9,EddShrT2N19D9,EddShrT2N20D9/), (/20,9/) ) +EddShrTND(:,:,3) = RESHAPE( & + (/EddShrT3N01D1,EddShrT3N02D1,EddShrT3N03D1,EddShrT3N04D1,EddShrT3N05D1,EddShrT3N06D1,EddShrT3N07D1,EddShrT3N08D1,EddShrT3N09D1,EddShrT3N10D1, & + EddShrT3N11D1,EddShrT3N12D1,EddShrT3N13D1,EddShrT3N14D1,EddShrT3N15D1,EddShrT3N16D1,EddShrT3N17D1,EddShrT3N18D1,EddShrT3N19D1,EddShrT3N20D1, & + EddShrT3N01D2,EddShrT3N02D2,EddShrT3N03D2,EddShrT3N04D2,EddShrT3N05D2,EddShrT3N06D2,EddShrT3N07D2,EddShrT3N08D2,EddShrT3N09D2,EddShrT3N10D2, & + EddShrT3N11D2,EddShrT3N12D2,EddShrT3N13D2,EddShrT3N14D2,EddShrT3N15D2,EddShrT3N16D2,EddShrT3N17D2,EddShrT3N18D2,EddShrT3N19D2,EddShrT3N20D2, & + EddShrT3N01D3,EddShrT3N02D3,EddShrT3N03D3,EddShrT3N04D3,EddShrT3N05D3,EddShrT3N06D3,EddShrT3N07D3,EddShrT3N08D3,EddShrT3N09D3,EddShrT3N10D3, & + EddShrT3N11D3,EddShrT3N12D3,EddShrT3N13D3,EddShrT3N14D3,EddShrT3N15D3,EddShrT3N16D3,EddShrT3N17D3,EddShrT3N18D3,EddShrT3N19D3,EddShrT3N20D3, & + EddShrT3N01D4,EddShrT3N02D4,EddShrT3N03D4,EddShrT3N04D4,EddShrT3N05D4,EddShrT3N06D4,EddShrT3N07D4,EddShrT3N08D4,EddShrT3N09D4,EddShrT3N10D4, & + EddShrT3N11D4,EddShrT3N12D4,EddShrT3N13D4,EddShrT3N14D4,EddShrT3N15D4,EddShrT3N16D4,EddShrT3N17D4,EddShrT3N18D4,EddShrT3N19D4,EddShrT3N20D4, & + EddShrT3N01D5,EddShrT3N02D5,EddShrT3N03D5,EddShrT3N04D5,EddShrT3N05D5,EddShrT3N06D5,EddShrT3N07D5,EddShrT3N08D5,EddShrT3N09D5,EddShrT3N10D5, & + EddShrT3N11D5,EddShrT3N12D5,EddShrT3N13D5,EddShrT3N14D5,EddShrT3N15D5,EddShrT3N16D5,EddShrT3N17D5,EddShrT3N18D5,EddShrT3N19D5,EddShrT3N20D5, & + EddShrT3N01D6,EddShrT3N02D6,EddShrT3N03D6,EddShrT3N04D6,EddShrT3N05D6,EddShrT3N06D6,EddShrT3N07D6,EddShrT3N08D6,EddShrT3N09D6,EddShrT3N10D6, & + EddShrT3N11D6,EddShrT3N12D6,EddShrT3N13D6,EddShrT3N14D6,EddShrT3N15D6,EddShrT3N16D6,EddShrT3N17D6,EddShrT3N18D6,EddShrT3N19D6,EddShrT3N20D6, & + EddShrT3N01D7,EddShrT3N02D7,EddShrT3N03D7,EddShrT3N04D7,EddShrT3N05D7,EddShrT3N06D7,EddShrT3N07D7,EddShrT3N08D7,EddShrT3N09D7,EddShrT3N10D7, & + EddShrT3N11D7,EddShrT3N12D7,EddShrT3N13D7,EddShrT3N14D7,EddShrT3N15D7,EddShrT3N16D7,EddShrT3N17D7,EddShrT3N18D7,EddShrT3N19D7,EddShrT3N20D7, & + EddShrT3N01D8,EddShrT3N02D8,EddShrT3N03D8,EddShrT3N04D8,EddShrT3N05D8,EddShrT3N06D8,EddShrT3N07D8,EddShrT3N08D8,EddShrT3N09D8,EddShrT3N10D8, & + EddShrT3N11D8,EddShrT3N12D8,EddShrT3N13D8,EddShrT3N14D8,EddShrT3N15D8,EddShrT3N16D8,EddShrT3N17D8,EddShrT3N18D8,EddShrT3N19D8,EddShrT3N20D8, & + EddShrT3N01D9,EddShrT3N02D9,EddShrT3N03D9,EddShrT3N04D9,EddShrT3N05D9,EddShrT3N06D9,EddShrT3N07D9,EddShrT3N08D9,EddShrT3N09D9,EddShrT3N10D9, & + EddShrT3N11D9,EddShrT3N12D9,EddShrT3N13D9,EddShrT3N14D9,EddShrT3N15D9,EddShrT3N16D9,EddShrT3N17D9,EddShrT3N18D9,EddShrT3N19D9,EddShrT3N20D9/), (/20,9/) ) +EddShrTND(:,:,4) = RESHAPE( & + (/EddShrT4N01D1,EddShrT4N02D1,EddShrT4N03D1,EddShrT4N04D1,EddShrT4N05D1,EddShrT4N06D1,EddShrT4N07D1,EddShrT4N08D1,EddShrT4N09D1,EddShrT4N10D1, & + EddShrT4N11D1,EddShrT4N12D1,EddShrT4N13D1,EddShrT4N14D1,EddShrT4N15D1,EddShrT4N16D1,EddShrT4N17D1,EddShrT4N18D1,EddShrT4N19D1,EddShrT4N20D1, & + EddShrT4N01D2,EddShrT4N02D2,EddShrT4N03D2,EddShrT4N04D2,EddShrT4N05D2,EddShrT4N06D2,EddShrT4N07D2,EddShrT4N08D2,EddShrT4N09D2,EddShrT4N10D2, & + EddShrT4N11D2,EddShrT4N12D2,EddShrT4N13D2,EddShrT4N14D2,EddShrT4N15D2,EddShrT4N16D2,EddShrT4N17D2,EddShrT4N18D2,EddShrT4N19D2,EddShrT4N20D2, & + EddShrT4N01D3,EddShrT4N02D3,EddShrT4N03D3,EddShrT4N04D3,EddShrT4N05D3,EddShrT4N06D3,EddShrT4N07D3,EddShrT4N08D3,EddShrT4N09D3,EddShrT4N10D3, & + EddShrT4N11D3,EddShrT4N12D3,EddShrT4N13D3,EddShrT4N14D3,EddShrT4N15D3,EddShrT4N16D3,EddShrT4N17D3,EddShrT4N18D3,EddShrT4N19D3,EddShrT4N20D3, & + EddShrT4N01D4,EddShrT4N02D4,EddShrT4N03D4,EddShrT4N04D4,EddShrT4N05D4,EddShrT4N06D4,EddShrT4N07D4,EddShrT4N08D4,EddShrT4N09D4,EddShrT4N10D4, & + EddShrT4N11D4,EddShrT4N12D4,EddShrT4N13D4,EddShrT4N14D4,EddShrT4N15D4,EddShrT4N16D4,EddShrT4N17D4,EddShrT4N18D4,EddShrT4N19D4,EddShrT4N20D4, & + EddShrT4N01D5,EddShrT4N02D5,EddShrT4N03D5,EddShrT4N04D5,EddShrT4N05D5,EddShrT4N06D5,EddShrT4N07D5,EddShrT4N08D5,EddShrT4N09D5,EddShrT4N10D5, & + EddShrT4N11D5,EddShrT4N12D5,EddShrT4N13D5,EddShrT4N14D5,EddShrT4N15D5,EddShrT4N16D5,EddShrT4N17D5,EddShrT4N18D5,EddShrT4N19D5,EddShrT4N20D5, & + EddShrT4N01D6,EddShrT4N02D6,EddShrT4N03D6,EddShrT4N04D6,EddShrT4N05D6,EddShrT4N06D6,EddShrT4N07D6,EddShrT4N08D6,EddShrT4N09D6,EddShrT4N10D6, & + EddShrT4N11D6,EddShrT4N12D6,EddShrT4N13D6,EddShrT4N14D6,EddShrT4N15D6,EddShrT4N16D6,EddShrT4N17D6,EddShrT4N18D6,EddShrT4N19D6,EddShrT4N20D6, & + EddShrT4N01D7,EddShrT4N02D7,EddShrT4N03D7,EddShrT4N04D7,EddShrT4N05D7,EddShrT4N06D7,EddShrT4N07D7,EddShrT4N08D7,EddShrT4N09D7,EddShrT4N10D7, & + EddShrT4N11D7,EddShrT4N12D7,EddShrT4N13D7,EddShrT4N14D7,EddShrT4N15D7,EddShrT4N16D7,EddShrT4N17D7,EddShrT4N18D7,EddShrT4N19D7,EddShrT4N20D7, & + EddShrT4N01D8,EddShrT4N02D8,EddShrT4N03D8,EddShrT4N04D8,EddShrT4N05D8,EddShrT4N06D8,EddShrT4N07D8,EddShrT4N08D8,EddShrT4N09D8,EddShrT4N10D8, & + EddShrT4N11D8,EddShrT4N12D8,EddShrT4N13D8,EddShrT4N14D8,EddShrT4N15D8,EddShrT4N16D8,EddShrT4N17D8,EddShrT4N18D8,EddShrT4N19D8,EddShrT4N20D8, & + EddShrT4N01D9,EddShrT4N02D9,EddShrT4N03D9,EddShrT4N04D9,EddShrT4N05D9,EddShrT4N06D9,EddShrT4N07D9,EddShrT4N08D9,EddShrT4N09D9,EddShrT4N10D9, & + EddShrT4N11D9,EddShrT4N12D9,EddShrT4N13D9,EddShrT4N14D9,EddShrT4N15D9,EddShrT4N16D9,EddShrT4N17D9,EddShrT4N18D9,EddShrT4N19D9,EddShrT4N20D9/), (/20,9/) ) + +EddShrTND(:,:,5) = RESHAPE( & + (/EddShrT5N01D1,EddShrT5N02D1,EddShrT5N03D1,EddShrT5N04D1,EddShrT5N05D1,EddShrT5N06D1,EddShrT5N07D1,EddShrT5N08D1,EddShrT5N09D1,EddShrT5N10D1, & + EddShrT5N11D1,EddShrT5N12D1,EddShrT5N13D1,EddShrT5N14D1,EddShrT5N15D1,EddShrT5N16D1,EddShrT5N17D1,EddShrT5N18D1,EddShrT5N19D1,EddShrT5N20D1, & + EddShrT5N01D2,EddShrT5N02D2,EddShrT5N03D2,EddShrT5N04D2,EddShrT5N05D2,EddShrT5N06D2,EddShrT5N07D2,EddShrT5N08D2,EddShrT5N09D2,EddShrT5N10D2, & + EddShrT5N11D2,EddShrT5N12D2,EddShrT5N13D2,EddShrT5N14D2,EddShrT5N15D2,EddShrT5N16D2,EddShrT5N17D2,EddShrT5N18D2,EddShrT5N19D2,EddShrT5N20D2, & + EddShrT5N01D3,EddShrT5N02D3,EddShrT5N03D3,EddShrT5N04D3,EddShrT5N05D3,EddShrT5N06D3,EddShrT5N07D3,EddShrT5N08D3,EddShrT5N09D3,EddShrT5N10D3, & + EddShrT5N11D3,EddShrT5N12D3,EddShrT5N13D3,EddShrT5N14D3,EddShrT5N15D3,EddShrT5N16D3,EddShrT5N17D3,EddShrT5N18D3,EddShrT5N19D3,EddShrT5N20D3, & + EddShrT5N01D4,EddShrT5N02D4,EddShrT5N03D4,EddShrT5N04D4,EddShrT5N05D4,EddShrT5N06D4,EddShrT5N07D4,EddShrT5N08D4,EddShrT5N09D4,EddShrT5N10D4, & + EddShrT5N11D4,EddShrT5N12D4,EddShrT5N13D4,EddShrT5N14D4,EddShrT5N15D4,EddShrT5N16D4,EddShrT5N17D4,EddShrT5N18D4,EddShrT5N19D4,EddShrT5N20D4, & + EddShrT5N01D5,EddShrT5N02D5,EddShrT5N03D5,EddShrT5N04D5,EddShrT5N05D5,EddShrT5N06D5,EddShrT5N07D5,EddShrT5N08D5,EddShrT5N09D5,EddShrT5N10D5, & + EddShrT5N11D5,EddShrT5N12D5,EddShrT5N13D5,EddShrT5N14D5,EddShrT5N15D5,EddShrT5N16D5,EddShrT5N17D5,EddShrT5N18D5,EddShrT5N19D5,EddShrT5N20D5, & + EddShrT5N01D6,EddShrT5N02D6,EddShrT5N03D6,EddShrT5N04D6,EddShrT5N05D6,EddShrT5N06D6,EddShrT5N07D6,EddShrT5N08D6,EddShrT5N09D6,EddShrT5N10D6, & + EddShrT5N11D6,EddShrT5N12D6,EddShrT5N13D6,EddShrT5N14D6,EddShrT5N15D6,EddShrT5N16D6,EddShrT5N17D6,EddShrT5N18D6,EddShrT5N19D6,EddShrT5N20D6, & + EddShrT5N01D7,EddShrT5N02D7,EddShrT5N03D7,EddShrT5N04D7,EddShrT5N05D7,EddShrT5N06D7,EddShrT5N07D7,EddShrT5N08D7,EddShrT5N09D7,EddShrT5N10D7, & + EddShrT5N11D7,EddShrT5N12D7,EddShrT5N13D7,EddShrT5N14D7,EddShrT5N15D7,EddShrT5N16D7,EddShrT5N17D7,EddShrT5N18D7,EddShrT5N19D7,EddShrT5N20D7, & + EddShrT5N01D8,EddShrT5N02D8,EddShrT5N03D8,EddShrT5N04D8,EddShrT5N05D8,EddShrT5N06D8,EddShrT5N07D8,EddShrT5N08D8,EddShrT5N09D8,EddShrT5N10D8, & + EddShrT5N11D8,EddShrT5N12D8,EddShrT5N13D8,EddShrT5N14D8,EddShrT5N15D8,EddShrT5N16D8,EddShrT5N17D8,EddShrT5N18D8,EddShrT5N19D8,EddShrT5N20D8, & + EddShrT5N01D9,EddShrT5N02D9,EddShrT5N03D9,EddShrT5N04D9,EddShrT5N05D9,EddShrT5N06D9,EddShrT5N07D9,EddShrT5N08D9,EddShrT5N09D9,EddShrT5N10D9, & + EddShrT5N11D9,EddShrT5N12D9,EddShrT5N13D9,EddShrT5N14D9,EddShrT5N15D9,EddShrT5N16D9,EddShrT5N17D9,EddShrT5N18D9,EddShrT5N19D9,EddShrT5N20D9/), (/20,9/) ) +EddShrTND(:,:,6) = RESHAPE( & + (/EddShrT6N01D1,EddShrT6N02D1,EddShrT6N03D1,EddShrT6N04D1,EddShrT6N05D1,EddShrT6N06D1,EddShrT6N07D1,EddShrT6N08D1,EddShrT6N09D1,EddShrT6N10D1, & + EddShrT6N11D1,EddShrT6N12D1,EddShrT6N13D1,EddShrT6N14D1,EddShrT6N15D1,EddShrT6N16D1,EddShrT6N17D1,EddShrT6N18D1,EddShrT6N19D1,EddShrT6N20D1, & + EddShrT6N01D2,EddShrT6N02D2,EddShrT6N03D2,EddShrT6N04D2,EddShrT6N05D2,EddShrT6N06D2,EddShrT6N07D2,EddShrT6N08D2,EddShrT6N09D2,EddShrT6N10D2, & + EddShrT6N11D2,EddShrT6N12D2,EddShrT6N13D2,EddShrT6N14D2,EddShrT6N15D2,EddShrT6N16D2,EddShrT6N17D2,EddShrT6N18D2,EddShrT6N19D2,EddShrT6N20D2, & + EddShrT6N01D3,EddShrT6N02D3,EddShrT6N03D3,EddShrT6N04D3,EddShrT6N05D3,EddShrT6N06D3,EddShrT6N07D3,EddShrT6N08D3,EddShrT6N09D3,EddShrT6N10D3, & + EddShrT6N11D3,EddShrT6N12D3,EddShrT6N13D3,EddShrT6N14D3,EddShrT6N15D3,EddShrT6N16D3,EddShrT6N17D3,EddShrT6N18D3,EddShrT6N19D3,EddShrT6N20D3, & + EddShrT6N01D4,EddShrT6N02D4,EddShrT6N03D4,EddShrT6N04D4,EddShrT6N05D4,EddShrT6N06D4,EddShrT6N07D4,EddShrT6N08D4,EddShrT6N09D4,EddShrT6N10D4, & + EddShrT6N11D4,EddShrT6N12D4,EddShrT6N13D4,EddShrT6N14D4,EddShrT6N15D4,EddShrT6N16D4,EddShrT6N17D4,EddShrT6N18D4,EddShrT6N19D4,EddShrT6N20D4, & + EddShrT6N01D5,EddShrT6N02D5,EddShrT6N03D5,EddShrT6N04D5,EddShrT6N05D5,EddShrT6N06D5,EddShrT6N07D5,EddShrT6N08D5,EddShrT6N09D5,EddShrT6N10D5, & + EddShrT6N11D5,EddShrT6N12D5,EddShrT6N13D5,EddShrT6N14D5,EddShrT6N15D5,EddShrT6N16D5,EddShrT6N17D5,EddShrT6N18D5,EddShrT6N19D5,EddShrT6N20D5, & + EddShrT6N01D6,EddShrT6N02D6,EddShrT6N03D6,EddShrT6N04D6,EddShrT6N05D6,EddShrT6N06D6,EddShrT6N07D6,EddShrT6N08D6,EddShrT6N09D6,EddShrT6N10D6, & + EddShrT6N11D6,EddShrT6N12D6,EddShrT6N13D6,EddShrT6N14D6,EddShrT6N15D6,EddShrT6N16D6,EddShrT6N17D6,EddShrT6N18D6,EddShrT6N19D6,EddShrT6N20D6, & + EddShrT6N01D7,EddShrT6N02D7,EddShrT6N03D7,EddShrT6N04D7,EddShrT6N05D7,EddShrT6N06D7,EddShrT6N07D7,EddShrT6N08D7,EddShrT6N09D7,EddShrT6N10D7, & + EddShrT6N11D7,EddShrT6N12D7,EddShrT6N13D7,EddShrT6N14D7,EddShrT6N15D7,EddShrT6N16D7,EddShrT6N17D7,EddShrT6N18D7,EddShrT6N19D7,EddShrT6N20D7, & + EddShrT6N01D8,EddShrT6N02D8,EddShrT6N03D8,EddShrT6N04D8,EddShrT6N05D8,EddShrT6N06D8,EddShrT6N07D8,EddShrT6N08D8,EddShrT6N09D8,EddShrT6N10D8, & + EddShrT6N11D8,EddShrT6N12D8,EddShrT6N13D8,EddShrT6N14D8,EddShrT6N15D8,EddShrT6N16D8,EddShrT6N17D8,EddShrT6N18D8,EddShrT6N19D8,EddShrT6N20D8, & + EddShrT6N01D9,EddShrT6N02D9,EddShrT6N03D9,EddShrT6N04D9,EddShrT6N05D9,EddShrT6N06D9,EddShrT6N07D9,EddShrT6N08D9,EddShrT6N09D9,EddShrT6N10D9, & + EddShrT6N11D9,EddShrT6N12D9,EddShrT6N13D9,EddShrT6N14D9,EddShrT6N15D9,EddShrT6N16D9,EddShrT6N17D9,EddShrT6N18D9,EddShrT6N19D9,EddShrT6N20D9/), (/20,9/) ) +EddShrTND(:,:,7) = RESHAPE( & + (/EddShrT7N01D1,EddShrT7N02D1,EddShrT7N03D1,EddShrT7N04D1,EddShrT7N05D1,EddShrT7N06D1,EddShrT7N07D1,EddShrT7N08D1,EddShrT7N09D1,EddShrT7N10D1, & + EddShrT7N11D1,EddShrT7N12D1,EddShrT7N13D1,EddShrT7N14D1,EddShrT7N15D1,EddShrT7N16D1,EddShrT7N17D1,EddShrT7N18D1,EddShrT7N19D1,EddShrT7N20D1, & + EddShrT7N01D2,EddShrT7N02D2,EddShrT7N03D2,EddShrT7N04D2,EddShrT7N05D2,EddShrT7N06D2,EddShrT7N07D2,EddShrT7N08D2,EddShrT7N09D2,EddShrT7N10D2, & + EddShrT7N11D2,EddShrT7N12D2,EddShrT7N13D2,EddShrT7N14D2,EddShrT7N15D2,EddShrT7N16D2,EddShrT7N17D2,EddShrT7N18D2,EddShrT7N19D2,EddShrT7N20D2, & + EddShrT7N01D3,EddShrT7N02D3,EddShrT7N03D3,EddShrT7N04D3,EddShrT7N05D3,EddShrT7N06D3,EddShrT7N07D3,EddShrT7N08D3,EddShrT7N09D3,EddShrT7N10D3, & + EddShrT7N11D3,EddShrT7N12D3,EddShrT7N13D3,EddShrT7N14D3,EddShrT7N15D3,EddShrT7N16D3,EddShrT7N17D3,EddShrT7N18D3,EddShrT7N19D3,EddShrT7N20D3, & + EddShrT7N01D4,EddShrT7N02D4,EddShrT7N03D4,EddShrT7N04D4,EddShrT7N05D4,EddShrT7N06D4,EddShrT7N07D4,EddShrT7N08D4,EddShrT7N09D4,EddShrT7N10D4, & + EddShrT7N11D4,EddShrT7N12D4,EddShrT7N13D4,EddShrT7N14D4,EddShrT7N15D4,EddShrT7N16D4,EddShrT7N17D4,EddShrT7N18D4,EddShrT7N19D4,EddShrT7N20D4, & + EddShrT7N01D5,EddShrT7N02D5,EddShrT7N03D5,EddShrT7N04D5,EddShrT7N05D5,EddShrT7N06D5,EddShrT7N07D5,EddShrT7N08D5,EddShrT7N09D5,EddShrT7N10D5, & + EddShrT7N11D5,EddShrT7N12D5,EddShrT7N13D5,EddShrT7N14D5,EddShrT7N15D5,EddShrT7N16D5,EddShrT7N17D5,EddShrT7N18D5,EddShrT7N19D5,EddShrT7N20D5, & + EddShrT7N01D6,EddShrT7N02D6,EddShrT7N03D6,EddShrT7N04D6,EddShrT7N05D6,EddShrT7N06D6,EddShrT7N07D6,EddShrT7N08D6,EddShrT7N09D6,EddShrT7N10D6, & + EddShrT7N11D6,EddShrT7N12D6,EddShrT7N13D6,EddShrT7N14D6,EddShrT7N15D6,EddShrT7N16D6,EddShrT7N17D6,EddShrT7N18D6,EddShrT7N19D6,EddShrT7N20D6, & + EddShrT7N01D7,EddShrT7N02D7,EddShrT7N03D7,EddShrT7N04D7,EddShrT7N05D7,EddShrT7N06D7,EddShrT7N07D7,EddShrT7N08D7,EddShrT7N09D7,EddShrT7N10D7, & + EddShrT7N11D7,EddShrT7N12D7,EddShrT7N13D7,EddShrT7N14D7,EddShrT7N15D7,EddShrT7N16D7,EddShrT7N17D7,EddShrT7N18D7,EddShrT7N19D7,EddShrT7N20D7, & + EddShrT7N01D8,EddShrT7N02D8,EddShrT7N03D8,EddShrT7N04D8,EddShrT7N05D8,EddShrT7N06D8,EddShrT7N07D8,EddShrT7N08D8,EddShrT7N09D8,EddShrT7N10D8, & + EddShrT7N11D8,EddShrT7N12D8,EddShrT7N13D8,EddShrT7N14D8,EddShrT7N15D8,EddShrT7N16D8,EddShrT7N17D8,EddShrT7N18D8,EddShrT7N19D8,EddShrT7N20D8, & + EddShrT7N01D9,EddShrT7N02D9,EddShrT7N03D9,EddShrT7N04D9,EddShrT7N05D9,EddShrT7N06D9,EddShrT7N07D9,EddShrT7N08D9,EddShrT7N09D9,EddShrT7N10D9, & + EddShrT7N11D9,EddShrT7N12D9,EddShrT7N13D9,EddShrT7N14D9,EddShrT7N15D9,EddShrT7N16D9,EddShrT7N17D9,EddShrT7N18D9,EddShrT7N19D9,EddShrT7N20D9/), (/20,9/) ) +EddShrTND(:,:,8) = RESHAPE( & + (/EddShrT8N01D1,EddShrT8N02D1,EddShrT8N03D1,EddShrT8N04D1,EddShrT8N05D1,EddShrT8N06D1,EddShrT8N07D1,EddShrT8N08D1,EddShrT8N09D1,EddShrT8N10D1, & + EddShrT8N11D1,EddShrT8N12D1,EddShrT8N13D1,EddShrT8N14D1,EddShrT8N15D1,EddShrT8N16D1,EddShrT8N17D1,EddShrT8N18D1,EddShrT8N19D1,EddShrT8N20D1, & + EddShrT8N01D2,EddShrT8N02D2,EddShrT8N03D2,EddShrT8N04D2,EddShrT8N05D2,EddShrT8N06D2,EddShrT8N07D2,EddShrT8N08D2,EddShrT8N09D2,EddShrT8N10D2, & + EddShrT8N11D2,EddShrT8N12D2,EddShrT8N13D2,EddShrT8N14D2,EddShrT8N15D2,EddShrT8N16D2,EddShrT8N17D2,EddShrT8N18D2,EddShrT8N19D2,EddShrT8N20D2, & + EddShrT8N01D3,EddShrT8N02D3,EddShrT8N03D3,EddShrT8N04D3,EddShrT8N05D3,EddShrT8N06D3,EddShrT8N07D3,EddShrT8N08D3,EddShrT8N09D3,EddShrT8N10D3, & + EddShrT8N11D3,EddShrT8N12D3,EddShrT8N13D3,EddShrT8N14D3,EddShrT8N15D3,EddShrT8N16D3,EddShrT8N17D3,EddShrT8N18D3,EddShrT8N19D3,EddShrT8N20D3, & + EddShrT8N01D4,EddShrT8N02D4,EddShrT8N03D4,EddShrT8N04D4,EddShrT8N05D4,EddShrT8N06D4,EddShrT8N07D4,EddShrT8N08D4,EddShrT8N09D4,EddShrT8N10D4, & + EddShrT8N11D4,EddShrT8N12D4,EddShrT8N13D4,EddShrT8N14D4,EddShrT8N15D4,EddShrT8N16D4,EddShrT8N17D4,EddShrT8N18D4,EddShrT8N19D4,EddShrT8N20D4, & + EddShrT8N01D5,EddShrT8N02D5,EddShrT8N03D5,EddShrT8N04D5,EddShrT8N05D5,EddShrT8N06D5,EddShrT8N07D5,EddShrT8N08D5,EddShrT8N09D5,EddShrT8N10D5, & + EddShrT8N11D5,EddShrT8N12D5,EddShrT8N13D5,EddShrT8N14D5,EddShrT8N15D5,EddShrT8N16D5,EddShrT8N17D5,EddShrT8N18D5,EddShrT8N19D5,EddShrT8N20D5, & + EddShrT8N01D6,EddShrT8N02D6,EddShrT8N03D6,EddShrT8N04D6,EddShrT8N05D6,EddShrT8N06D6,EddShrT8N07D6,EddShrT8N08D6,EddShrT8N09D6,EddShrT8N10D6, & + EddShrT8N11D6,EddShrT8N12D6,EddShrT8N13D6,EddShrT8N14D6,EddShrT8N15D6,EddShrT8N16D6,EddShrT8N17D6,EddShrT8N18D6,EddShrT8N19D6,EddShrT8N20D6, & + EddShrT8N01D7,EddShrT8N02D7,EddShrT8N03D7,EddShrT8N04D7,EddShrT8N05D7,EddShrT8N06D7,EddShrT8N07D7,EddShrT8N08D7,EddShrT8N09D7,EddShrT8N10D7, & + EddShrT8N11D7,EddShrT8N12D7,EddShrT8N13D7,EddShrT8N14D7,EddShrT8N15D7,EddShrT8N16D7,EddShrT8N17D7,EddShrT8N18D7,EddShrT8N19D7,EddShrT8N20D7, & + EddShrT8N01D8,EddShrT8N02D8,EddShrT8N03D8,EddShrT8N04D8,EddShrT8N05D8,EddShrT8N06D8,EddShrT8N07D8,EddShrT8N08D8,EddShrT8N09D8,EddShrT8N10D8, & + EddShrT8N11D8,EddShrT8N12D8,EddShrT8N13D8,EddShrT8N14D8,EddShrT8N15D8,EddShrT8N16D8,EddShrT8N17D8,EddShrT8N18D8,EddShrT8N19D8,EddShrT8N20D8, & + EddShrT8N01D9,EddShrT8N02D9,EddShrT8N03D9,EddShrT8N04D9,EddShrT8N05D9,EddShrT8N06D9,EddShrT8N07D9,EddShrT8N08D9,EddShrT8N09D9,EddShrT8N10D9, & + EddShrT8N11D9,EddShrT8N12D9,EddShrT8N13D9,EddShrT8N14D9,EddShrT8N15D9,EddShrT8N16D9,EddShrT8N17D9,EddShrT8N18D9,EddShrT8N19D9,EddShrT8N20D9/), (/20,9/) ) +EddShrTND(:,:,9) = RESHAPE( & + (/EddShrT9N01D1,EddShrT9N02D1,EddShrT9N03D1,EddShrT9N04D1,EddShrT9N05D1,EddShrT9N06D1,EddShrT9N07D1,EddShrT9N08D1,EddShrT9N09D1,EddShrT9N10D1, & + EddShrT9N11D1,EddShrT9N12D1,EddShrT9N13D1,EddShrT9N14D1,EddShrT9N15D1,EddShrT9N16D1,EddShrT9N17D1,EddShrT9N18D1,EddShrT9N19D1,EddShrT9N20D1, & + EddShrT9N01D2,EddShrT9N02D2,EddShrT9N03D2,EddShrT9N04D2,EddShrT9N05D2,EddShrT9N06D2,EddShrT9N07D2,EddShrT9N08D2,EddShrT9N09D2,EddShrT9N10D2, & + EddShrT9N11D2,EddShrT9N12D2,EddShrT9N13D2,EddShrT9N14D2,EddShrT9N15D2,EddShrT9N16D2,EddShrT9N17D2,EddShrT9N18D2,EddShrT9N19D2,EddShrT9N20D2, & + EddShrT9N01D3,EddShrT9N02D3,EddShrT9N03D3,EddShrT9N04D3,EddShrT9N05D3,EddShrT9N06D3,EddShrT9N07D3,EddShrT9N08D3,EddShrT9N09D3,EddShrT9N10D3, & + EddShrT9N11D3,EddShrT9N12D3,EddShrT9N13D3,EddShrT9N14D3,EddShrT9N15D3,EddShrT9N16D3,EddShrT9N17D3,EddShrT9N18D3,EddShrT9N19D3,EddShrT9N20D3, & + EddShrT9N01D4,EddShrT9N02D4,EddShrT9N03D4,EddShrT9N04D4,EddShrT9N05D4,EddShrT9N06D4,EddShrT9N07D4,EddShrT9N08D4,EddShrT9N09D4,EddShrT9N10D4, & + EddShrT9N11D4,EddShrT9N12D4,EddShrT9N13D4,EddShrT9N14D4,EddShrT9N15D4,EddShrT9N16D4,EddShrT9N17D4,EddShrT9N18D4,EddShrT9N19D4,EddShrT9N20D4, & + EddShrT9N01D5,EddShrT9N02D5,EddShrT9N03D5,EddShrT9N04D5,EddShrT9N05D5,EddShrT9N06D5,EddShrT9N07D5,EddShrT9N08D5,EddShrT9N09D5,EddShrT9N10D5, & + EddShrT9N11D5,EddShrT9N12D5,EddShrT9N13D5,EddShrT9N14D5,EddShrT9N15D5,EddShrT9N16D5,EddShrT9N17D5,EddShrT9N18D5,EddShrT9N19D5,EddShrT9N20D5, & + EddShrT9N01D6,EddShrT9N02D6,EddShrT9N03D6,EddShrT9N04D6,EddShrT9N05D6,EddShrT9N06D6,EddShrT9N07D6,EddShrT9N08D6,EddShrT9N09D6,EddShrT9N10D6, & + EddShrT9N11D6,EddShrT9N12D6,EddShrT9N13D6,EddShrT9N14D6,EddShrT9N15D6,EddShrT9N16D6,EddShrT9N17D6,EddShrT9N18D6,EddShrT9N19D6,EddShrT9N20D6, & + EddShrT9N01D7,EddShrT9N02D7,EddShrT9N03D7,EddShrT9N04D7,EddShrT9N05D7,EddShrT9N06D7,EddShrT9N07D7,EddShrT9N08D7,EddShrT9N09D7,EddShrT9N10D7, & + EddShrT9N11D7,EddShrT9N12D7,EddShrT9N13D7,EddShrT9N14D7,EddShrT9N15D7,EddShrT9N16D7,EddShrT9N17D7,EddShrT9N18D7,EddShrT9N19D7,EddShrT9N20D7, & + EddShrT9N01D8,EddShrT9N02D8,EddShrT9N03D8,EddShrT9N04D8,EddShrT9N05D8,EddShrT9N06D8,EddShrT9N07D8,EddShrT9N08D8,EddShrT9N09D8,EddShrT9N10D8, & + EddShrT9N11D8,EddShrT9N12D8,EddShrT9N13D8,EddShrT9N14D8,EddShrT9N15D8,EddShrT9N16D8,EddShrT9N17D8,EddShrT9N18D8,EddShrT9N19D8,EddShrT9N20D8, & + EddShrT9N01D9,EddShrT9N02D9,EddShrT9N03D9,EddShrT9N04D9,EddShrT9N05D9,EddShrT9N06D9,EddShrT9N07D9,EddShrT9N08D9,EddShrT9N09D9,EddShrT9N10D9, & + EddShrT9N11D9,EddShrT9N12D9,EddShrT9N13D9,EddShrT9N14D9,EddShrT9N15D9,EddShrT9N16D9,EddShrT9N17D9,EddShrT9N18D9,EddShrT9N19D9,EddShrT9N20D9/), (/20,9/) ) + if ( (farm%p%NumOuts == 0) ) then ! .or. .not. ( (farm%p%WrTxtOutFile) .or. (farm%p%WrBinOutFile) ) ) then return From 70895393a9ad05a1c7c53eefac4861c3bd09fa49 Mon Sep 17 00:00:00 2001 From: Ganesh Vijayakumar Date: Fri, 2 Jun 2017 08:58:55 -0600 Subject: [PATCH 024/386] Updating fast-farm to compile with cmake --- CMakeLists.txt | 8 ++++++ glue-codes/CMakeLists.txt | 5 ++++ glue-codes/fast-farm/CMakeLists.txt | 24 ++++++++-------- modules-local/awae/CMakeLists.txt | 34 +++++++++++++++++++++++ modules-local/wakedynamics/CMakeLists.txt | 34 +++++++++++++++++++++++ 5 files changed, 93 insertions(+), 12 deletions(-) create mode 100644 modules-local/awae/CMakeLists.txt create mode 100644 modules-local/wakedynamics/CMakeLists.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index c9f1b890cb..8181394399 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -34,6 +34,7 @@ option(USE_DLL_INTERFACE "Enable runtime loading of dynamic libraries" on) option(FPE_TRAP_ENABLED "Enable FPE trap in compiler options" off) option(ORCA_DLL_LOAD "Enable OrcaFlex Library Load" off) option(BUILD_FAST_CPP_API "Enable building FAST - C++ API" off) +option(BUILD_FAST_FARM "Enable building FAST-Farm glue code" off) # Setup Fortran Compiler options based on architecture/compiler set_fast_fortran() @@ -103,6 +104,13 @@ foreach(IDIR IN ITEMS ${FAST_MODULES_EXTERNAL}) add_subdirectory("${CMAKE_SOURCE_DIR}/modules-ext/${IDIR}") endforeach(IDIR IN ITEMS ${FAST_MODULES_EXTERNAL}) +if (BUILD_FAST_FARM) + add_subdirectory("${CMAKE_SOURCE_DIR}/modules-local/wakedynamics") + add_subdirectory("${CMAKE_SOURCE_DIR}/modules-local/awae") + set_registry_includes("modules-local" wakedynamics) + set_registry_includes("modules-local" awae) +endif() + option(BUILD_DOCUMENTATION "Build documentation." OFF) if(BUILD_DOCUMENTATION) add_subdirectory(docs) diff --git a/glue-codes/CMakeLists.txt b/glue-codes/CMakeLists.txt index d9b023f752..93c0aa1901 100644 --- a/glue-codes/CMakeLists.txt +++ b/glue-codes/CMakeLists.txt @@ -4,3 +4,8 @@ add_subdirectory(fast) if(BUILD_FAST_CPP_API) add_subdirectory(fast-cpp) endif() + +if(BUILD_FAST_FARM) + add_subdirectory(fast-farm) +endif() + diff --git a/glue-codes/fast-farm/CMakeLists.txt b/glue-codes/fast-farm/CMakeLists.txt index e001320455..ca30687339 100644 --- a/glue-codes/fast-farm/CMakeLists.txt +++ b/glue-codes/fast-farm/CMakeLists.txt @@ -15,26 +15,26 @@ # generate_f90_types(src/FASTWrapper_Registry.txt FASTWrapper_Types.f90) -generate_f90_types(src/FAST_Farm_Registry.txt FAST_Farm_Types.f90) -generate_f90_types(../../modules-local/awae/src/AWAE_Registry.txt AWAE_Types.f90) -generate_f90_types(../../modules-local/wakedynamics/src/WakeDynamics_Registry.txt WakeDynamics_Types.f90) +generate_f90_types(src/FAST_Farm_Registry.txt FAST_Farm_Types.f90 -noextrap) + +FIND_PACKAGE( OpenMP REQUIRED) +if(OPENMP_FOUND) + set(CMAKE_FORTRAN_FLAGS "${CMAKE_FORTRAN_FLAGS} ${OpenMP_FORTRAN_FLAGS}") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") +endif() add_executable(openfast-farm src/FAST_Farm_IO.f90 src/FAST_Farm_Subs.f90 src/FASTWrapper.f90 src/FAST_Farm.f90 - ../../modules-local/awae/src/AWAE.f90 - ../../modules-local/awae/src/AWAE_IO.f90 - ../../modules-local/wakedynamics/src/WakeDynamics.f90 - ../../modules-local/wakedynamics/src/WakeDynamics_IO.f90 # Autogenerated files - AWAE_Types.f90 - WakeDynamics_Types.f90 - FASTWrapper_Types.f90 - FAST_Farm_Types.f90) + FAST_Farm_Types.f90 + FASTWrapper_Types.f90) -target_link_libraries(openfast-farm openfast_postlib foamfastlib) +target_link_libraries(openfast-farm openfast_postlib openfast_prelib nwtclibs awaelib wdlib) install(TARGETS openfast-farm RUNTIME DESTINATION bin) diff --git a/modules-local/awae/CMakeLists.txt b/modules-local/awae/CMakeLists.txt new file mode 100644 index 0000000000..8a017f2872 --- /dev/null +++ b/modules-local/awae/CMakeLists.txt @@ -0,0 +1,34 @@ +# +# Copyright 2016 National Renewable Energy Laboratory +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +generate_f90_types(src/AWAE_Registry.txt AWAE_Types.f90) + +set(AWAE_LIBS_SOURCES + src/AWAE.f90 + src/AWAE_IO.f90 + + # Autogenerated files + AWAE_Types.f90 + ) + +add_library(awaelib ${AWAE_LIBS_SOURCES}) +target_link_libraries(awaelib nwtclibs) + +install(TARGETS awaelib + EXPORT "${CMAKE_PROJECT_NAME}Libraries" + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) diff --git a/modules-local/wakedynamics/CMakeLists.txt b/modules-local/wakedynamics/CMakeLists.txt new file mode 100644 index 0000000000..b133d56b1d --- /dev/null +++ b/modules-local/wakedynamics/CMakeLists.txt @@ -0,0 +1,34 @@ +# +# Copyright 2016 National Renewable Energy Laboratory +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +generate_f90_types(src/WakeDynamics_Registry.txt WakeDynamics_Types.f90) + +set(WD_LIBS_SOURCES + src/WakeDynamics.f90 + src/WakeDynamics_IO.f90 + + # Autogenerated files + WakeDynamics_Types.f90 + ) + +add_library(wdlib ${WD_LIBS_SOURCES}) +target_link_libraries(wdlib nwtclibs) + +install(TARGETS wdlib + EXPORT "${CMAKE_PROJECT_NAME}Libraries" + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) From 01b349eaee2cf264c6d50d4577c0db4e2cc0bcf0 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Wed, 7 Jun 2017 13:31:37 -0600 Subject: [PATCH 025/386] Fixed bug in summary file output statement where I was not indexing into FWrap array properly. --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index 27c5873232..70faf72470 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9811,7 +9811,7 @@ SUBROUTINE Farm_PrintSum( farm, WD_InputFileData, ErrStat, ErrMsg ) outStr = ' - ' end if - WRITE(UnSum,'(6X,I4,16X,A4,9X,3F10.3,5X,F10.5,8X,I4,10X,A)') I, outStr, farm%p%WT_Position(1,I), farm%p%WT_Position(2,I),farm%p%WT_Position(3,I), farm%p%DT/farm%FWrap%p%n_FAST_low, farm%FWrap%p%n_FAST_low, trim(farm%p%WT_FASTInFile(I)) + WRITE(UnSum,'(6X,I4,16X,A4,9X,3F10.3,5X,F10.5,8X,I4,10X,A)') I, outStr, farm%p%WT_Position(1,I), farm%p%WT_Position(2,I),farm%p%WT_Position(3,I), farm%p%DT/farm%FWrap(I)%p%n_FAST_low, farm%FWrap%p%n_FAST_low, trim(farm%p%WT_FASTInFile(I)) end do From 11d30bf26eeaa9c19a1dbbed0fec2ba0f16a53c6 Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Wed, 7 Jun 2017 13:32:31 -0600 Subject: [PATCH 026/386] More changes to prototype OpenMP code --- glue-codes/fast-farm/src/FAST_Farm.f90 | 16 ++++++++++++---- glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 18 ++++++++++-------- 2 files changed, 22 insertions(+), 12 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm.f90 b/glue-codes/fast-farm/src/FAST_Farm.f90 index c7575eace8..5a84ce32b0 100644 --- a/glue-codes/fast-farm/src/FAST_Farm.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm.f90 @@ -125,14 +125,22 @@ PROGRAM FAST_Farm ! ! this takes data from n_t_global and gets values at n_t_global + 1 t = n_t_global*farm%p%DT - !CALL FARM_UpdateStates(t, n_t_global, farm, ErrStat, ErrMsg) + +#ifdef PARALLEL_CODE + CALL FARM_UpdateStates(t, n_t_global, farm, ErrStat, ErrMsg) +#else CALL FARM_UpdateStatesSerial(t, n_t_global, farm, ErrStat, ErrMsg) - CALL CheckError( ErrStat, ErrMsg ) +#endif + CALL CheckError( ErrStat, ErrMsg ) t = (n_t_global+1)*farm%p%DT - !CALL FARM_CalcOutput(t, farm, ErrStat, ErrMsg) + +#ifdef PARALLEL_CODE + CALL FARM_CalcOutput(t, farm, ErrStat, ErrMsg) +#else CALL FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) - CALL CheckError( ErrStat, ErrMsg ) +#endif + CALL CheckError( ErrStat, ErrMsg ) CALL SimStatus( PrevSimTime, PrevClockTime, t, farm%p%TMax ) diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index 2a9694ba1a..a08602239b 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -1547,15 +1547,17 @@ subroutine FARM_UpdateStates(t, n, farm, ErrStat, ErrMsg) ! 3. CALL F_Increment !$OMP SECTION t3 = omp_get_wtime() + !$OMP PARALLEL DO DEFAULT(SHARED) DO nt = 1,farm%p%NumTurbines call FWrap_Increment( t, n, farm%FWrap(nt)%u, farm%FWrap(nt)%p, farm%FWrap(nt)%x, farm%FWrap(nt)%xd, farm%FWrap(nt)%z, & farm%FWrap(nt)%OtherSt, farm%FWrap(nt)%y, farm%FWrap(nt)%m, ErrStatF, ErrMsgF ) call SetErrStat(ErrStatF, ErrMsgF, ErrStatF, ErrMsgF, 'T'//trim(num2lstr(nt))//':FARM_UpdateStates') - t4 = omp_get_wtime() - write(*,*) ' Serial F_Increment took '//trim(num2lstr(t4-t3))//' seconds. Using thread #'//trim(num2lstr(omp_get_thread_num())) + write(*,*) ' FWrap_Increment for turbine #'//trim(num2lstr(nt))//' using thread #'//trim(num2lstr(omp_get_thread_num())) END DO - + !$OMP END PARALLEL DO + t4 = omp_get_wtime() + write(*,*) ' Parallel F_Increment(s) took '//trim(num2lstr(t4-t3))//' seconds.' ! if (ErrStat >= AbortErrLev) return @@ -1596,7 +1598,7 @@ subroutine FARM_UpdateStatesSerial(t, n, farm, ErrStat, ErrMsg) ErrStat = ErrID_None ErrMsg = "" - tm1 = omp_get_wtime() + ! tm1 = omp_get_wtime() !....................................................................................... @@ -1648,8 +1650,8 @@ subroutine FARM_UpdateStatesSerial(t, n, farm, ErrStat, ErrMsg) if (errStatAWAE >= AbortErrLev) return - tm2 = omp_get_wtime() - write(*,*) 'Total Farm_US-serial took '//trim(num2lstr(tm2-tm1))//' seconds.' + ! tm2 = omp_get_wtime() + ! write(*,*) 'Total Farm_US-serial took '//trim(num2lstr(tm2-tm1))//' seconds.' end subroutine FARM_UpdateStatesSerial @@ -1981,7 +1983,7 @@ subroutine FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) ErrStat = ErrID_None ErrMsg = "" - tm1 = omp_get_wtime() + ! tm1 = omp_get_wtime() !....................................................................................... ! calculate module outputs and perform some input-output solves (steps 1. and 2. and 3. can be done in parallel, @@ -2035,7 +2037,7 @@ subroutine FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) call Farm_WriteOutput(n, t, farm, ErrStat2, ErrMsg2) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - write(*,*) 'Total Farm_CO-serial took '//trim(num2lstr(omp_get_wtime()-tm1))//' seconds.' + ! write(*,*) 'Total Farm_CO-serial took '//trim(num2lstr(omp_get_wtime()-tm1))//' seconds.' end subroutine FARM_CalcOutputSerial !---------------------------------------------------------------------------------------------------------------------------------- From 4eefe6354f710265b4b5979c18f74766a108be9b Mon Sep 17 00:00:00 2001 From: Ganesh Vijayakumar Date: Tue, 13 Jun 2017 17:00:00 -0600 Subject: [PATCH 027/386] Implementing a filter for the inputs from the Supercontroller to Servodyn --- modules-local/fast-library/src/FAST_Subs.f90 | 4 +- .../servodyn/src/BladedInterface.f90 | 22 ++++---- modules-local/servodyn/src/ServoDyn.f90 | 54 ++++++++++++------- .../servodyn/src/ServoDyn_Registry.txt | 4 ++ 4 files changed, 55 insertions(+), 29 deletions(-) diff --git a/modules-local/fast-library/src/FAST_Subs.f90 b/modules-local/fast-library/src/FAST_Subs.f90 index 68b1dfea39..b64c8dd825 100644 --- a/modules-local/fast-library/src/FAST_Subs.f90 +++ b/modules-local/fast-library/src/FAST_Subs.f90 @@ -6300,7 +6300,7 @@ SUBROUTINE FAST_CreateCheckpoint_T(t_initial, n_t_global, NumTurbines, Turbine, Turbine%SrvD%p%DLL_InFile = DLLFileName Turbine%SrvD%m%dll_data%avrSWAP(50) = REAL( LEN_TRIM(DLLFileName) ) +1 ! No. of characters in the "INFILE" argument (-) (we add one for the C NULL CHARACTER) Turbine%SrvD%m%dll_data%avrSWAP( 1) = -8 - CALL CallBladedDLL(Turbine%SrvD%Input(1), Turbine%SrvD%p%DLL_Trgt, Turbine%SrvD%m%dll_data, Turbine%SrvD%p, ErrStat2, ErrMsg2) + CALL CallBladedDLL(Turbine%SrvD%Input(1), Turbine%SrvD%xd(STATE_CURR)%ScInFilter, Turbine%SrvD%p%DLL_Trgt, Turbine%SrvD%m%dll_data, Turbine%SrvD%p, ErrStat2, ErrMsg2) CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) ! put values back: @@ -6498,7 +6498,7 @@ SUBROUTINE FAST_RestoreFromCheckpoint_T(t_initial, n_t_global, NumTurbines, Turb Turbine%SrvD%p%DLL_InFile = DLLFileName Turbine%SrvD%m%dll_data%avrSWAP(50) = REAL( LEN_TRIM(DLLFileName) ) +1 ! No. of characters in the "INFILE" argument (-) (we add one for the C NULL CHARACTER) Turbine%SrvD%m%dll_data%avrSWAP( 1) = -9 - CALL CallBladedDLL(Turbine%SrvD%Input(1), Turbine%SrvD%p%DLL_Trgt, Turbine%SrvD%m%dll_data, Turbine%SrvD%p, ErrStat2, ErrMsg2) + CALL CallBladedDLL(Turbine%SrvD%Input(1), Turbine%SrvD%xd(STATE_CURR)%ScInFilter, Turbine%SrvD%p%DLL_Trgt, Turbine%SrvD%m%dll_data, Turbine%SrvD%p, ErrStat2, ErrMsg2) CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) ! put values back: Turbine%SrvD%p%DLL_InFile = FileName diff --git a/modules-local/servodyn/src/BladedInterface.f90 b/modules-local/servodyn/src/BladedInterface.f90 index 878520c450..611945348b 100644 --- a/modules-local/servodyn/src/BladedInterface.f90 +++ b/modules-local/servodyn/src/BladedInterface.f90 @@ -97,10 +97,11 @@ END SUBROUTINE DISCON CONTAINS !================================================================================================================================== !> This SUBROUTINE is used to call the Bladed-style DLL. -SUBROUTINE CallBladedDLL ( u, DLL, dll_data, p, ErrStat, ErrMsg ) +SUBROUTINE CallBladedDLL ( u, scInFilter, DLL, dll_data, p, ErrStat, ErrMsg ) ! Passed Variables: TYPE(SrvD_InputType), INTENT(IN ) :: u ! System inputs + REAL(SiKi), INTENT(IN ) :: scInFilter (*) ! Filtered input from Supercontroller to ServoDyn TYPE(DLL_Type), INTENT(IN ) :: DLL ! The DLL to be called. TYPE(BladedDLLType), INTENT(INOUT) :: dll_data ! data type containing the avrSWAP, accINFILE, and avcOUTNAME arrays TYPE(SrvD_ParameterType), INTENT(IN ) :: p ! Parameters @@ -138,7 +139,7 @@ SUBROUTINE CallBladedDLL ( u, DLL, dll_data, p, ErrStat, ErrMsg ) ! if we're statically loading the library (i.e., OpenFOAM), we can just call DISCON(); ! I'll leave some options for whether the supercontroller is being used #ifdef LOAD_SUPERCONTROLLER - CALL DISCON( dll_data%avrSWAP, u%SuperController, dll_data%SCoutput, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) + CALL DISCON( dll_data%avrSWAP, scInFilter, dll_data%SCoutput, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) #else CALL DISCON( dll_data%avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) #endif @@ -148,7 +149,7 @@ SUBROUTINE CallBladedDLL ( u, DLL, dll_data, p, ErrStat, ErrMsg ) IF ( ALLOCATED(dll_data%SCoutput) ) THEN ! Call the DLL (first associate the address from the procedure in the DLL with the subroutine): CALL C_F_PROCPOINTER( DLL%ProcAddr(1), DLL_SC_Subroutine) - CALL DLL_SC_Subroutine ( dll_data%avrSWAP, u%SuperController, dll_data%SCoutput, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) + CALL DLL_SC_Subroutine ( dll_data%avrSWAP, scInFilter, dll_data%SCoutput, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) ELSE @@ -180,11 +181,12 @@ SUBROUTINE CallBladedDLL ( u, DLL, dll_data, p, ErrStat, ErrMsg ) END SUBROUTINE CallBladedDLL !================================================================================================================================== !> This routine initializes variables used in the Bladed DLL interface. -SUBROUTINE BladedInterface_Init(u,p,m,y,InputFileData, ErrStat, ErrMsg) +SUBROUTINE BladedInterface_Init(u,p,m,xd,y,InputFileData, ErrStat, ErrMsg) TYPE(SrvD_InputType), INTENT(INOUT) :: u !< An initial guess for the input; input mesh must be defined TYPE(SrvD_ParameterType), INTENT(INOUT) :: p !< Parameters TYPE(SrvD_MiscVarType), INTENT(INOUT) :: m !< Initial misc (optimization) variables + TYPE(SrvD_DiscreteStateType), INTENT(IN ) :: xd !< Discrete states TYPE(SrvD_OutputType), INTENT(INOUT) :: y !< Initial system outputs (outputs are not calculated; !! only the output mesh is initialized) TYPE(SrvD_InputFile), INTENT(INOUT) :: InputFileData !< Data stored in the module's input file @@ -305,7 +307,7 @@ SUBROUTINE BladedInterface_Init(u,p,m,y,InputFileData, ErrStat, ErrMsg) !CALL Fill_avrSWAP( 0_IntKi, t, u, p, LEN(ErrMsg), m%dll_data ) ! Status flag set as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation (-) - !CALL CallBladedDLL(p%DLL_Trgt, m%dll_data, ErrStat2, ErrMsg2) + !CALL CallBladedDLL(u, xd%ScInFilter, p%DLL_Trgt, m%dll_data, ErrStat2, ErrMsg2) ! CALL CheckError(ErrStat2,ErrMsg2) ! IF ( ErrStat >= AbortErrLev ) RETURN ! @@ -344,11 +346,12 @@ END SUBROUTINE CheckError END SUBROUTINE BladedInterface_Init !================================================================================================================================== !> This routine calls the DLL for the final time (if it was previously called), and frees the dynamic library. -SUBROUTINE BladedInterface_End(u, p, m, ErrStat, ErrMsg) +SUBROUTINE BladedInterface_End(u, p, m, xd, ErrStat, ErrMsg) TYPE(SrvD_InputType), INTENT(IN ) :: u !< System inputs TYPE(SrvD_ParameterType), INTENT(INOUT) :: p !< Parameters TYPE(SrvD_MiscVarType), INTENT(INOUT) :: m !< misc (optimization) variables + TYPE(SrvD_DiscreteStateType), INTENT(IN ) :: xd !< Discrete states INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None @@ -362,7 +365,7 @@ SUBROUTINE BladedInterface_End(u, p, m, ErrStat, ErrMsg) m%dll_data%avrSWAP( 1) = -1.0 ! Status flag set as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation (-) !CALL Fill_avrSWAP( -1_IntKi, -10.0_DbKi, u, p, LEN(ErrMsg), m%dll_data ) - CALL CallBladedDLL(u, p%DLL_Trgt, m%dll_data, p, ErrStat, ErrMsg) + CALL CallBladedDLL(u, xd%ScInFilter, p%DLL_Trgt, m%dll_data, p, ErrStat, ErrMsg) END IF end if @@ -376,12 +379,13 @@ END SUBROUTINE BladedInterface_End !================================================================================================================================== !> This routine sets the AVRswap array, calls the routine from the BladedDLL, and sets the outputs from the call to be used as !! necessary in the main ServoDyn CalcOutput routine. -SUBROUTINE BladedInterface_CalcOutput(t, u, p, m, ErrStat, ErrMsg) +SUBROUTINE BladedInterface_CalcOutput(t, u, p, m, xd, ErrStat, ErrMsg) REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds TYPE(SrvD_InputType), INTENT(IN ) :: u !< Inputs at t TYPE(SrvD_ParameterType), INTENT(IN ) :: p !< Parameters TYPE(SrvD_MiscVarType), INTENT(INOUT) :: m !< misc (optimization) variables + TYPE(SrvD_DiscreteStateType), INTENT(IN ) :: xd !< Discrete states at t INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None @@ -406,7 +410,7 @@ SUBROUTINE BladedInterface_CalcOutput(t, u, p, m, ErrStat, ErrMsg) ! Call the Bladed-style DLL controller: - CALL CallBladedDLL(u, p%DLL_Trgt, m%dll_data, p, ErrStat, ErrMsg) + CALL CallBladedDLL(u, xd%ScInFilter, p%DLL_Trgt, m%dll_data, p, ErrStat, ErrMsg) IF ( ErrStat >= AbortErrLev ) RETURN #ifdef DEBUG_BLADED_INTERFACE diff --git a/modules-local/servodyn/src/ServoDyn.f90 b/modules-local/servodyn/src/ServoDyn.f90 index 2417847960..192de85eee 100644 --- a/modules-local/servodyn/src/ServoDyn.f90 +++ b/modules-local/servodyn/src/ServoDyn.f90 @@ -326,6 +326,14 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO CALL CheckError( ErrStat2, ErrMsg2 ) IF (ErrStat >= AbortErrLev) RETURN u%SuperController = 0.0_SiKi + + p%ScInAlpha = exp( -TwoPi*p%DT*InputFileData%ScInCutoff ) + if (InputFileData%ScInCutOff < EPSILON( InputFileData%ScInCutOff )) CALL CheckError( ErrID_Fatal, 'ScInCutoff must be greater than 0.') + CALL AllocAry( xd%ScInFilter, InitInp%NumSC2Ctrl, 'xd%ScInFilter', ErrStat2, ErrMsg2 ) + CALL CheckError( ErrStat2, ErrMsg2 ) + IF (ErrStat >= AbortErrLev) RETURN + xd%ScInFilter = 0.0_ReKi + END IF @@ -470,7 +478,7 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO p%AirDens = InitInp%AirDens p%AvgWindSpeed = InitInp%AvgWindSpeed - CALL BladedInterface_Init(u, p, m, y, InputFileData, ErrStat2, ErrMsg2 ) + CALL BladedInterface_Init(u, p, m, xd, y, InputFileData, ErrStat2, ErrMsg2 ) CALL CheckError( ErrStat2, ErrMsg2 ) IF (ErrStat >= AbortErrLev) RETURN @@ -655,7 +663,7 @@ SUBROUTINE SrvD_End( u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMsg ) ! Place any last minute operations or calculations here: IF ( p%UseBladedInterface ) THEN - CALL BladedInterface_End(u, p, m, ErrStat, ErrMsg ) + CALL BladedInterface_End(u, p, m, xd, ErrStat, ErrMsg ) END IF IF (p%CompNTMD) THEN @@ -802,28 +810,27 @@ SUBROUTINE SrvD_UpdateStates( t, n, Inputs, InputTimes, p, x, xd, z, OtherState, END IF - ! Get appropriate value of input for the filter in discrete states - ! this works only for the DLL at this point, so we're going to move it there>>>>>>>>>>>>>>> + CALL SrvD_CopyInput( Inputs(1), u_interp, MESH_NEWCOPY, ErrStat2, ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + IF (ErrStat >= AbortErrLev) THEN + CALL Cleanup() + RETURN + END IF - ! - !CALL SrvD_UpdateDiscState( t, u_interp, p, x, xd, z, OtherState, ErrStat2, ErrMsg2 ) - ! CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - !<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< + CALL SrvD_Input_ExtrapInterp( Inputs, InputTimes, u_interp, t, ErrStat2, ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + + CALL SrvD_UpdateDiscState( t, u_interp, p, x, xd, z, OtherState, m, ErrStat2, ErrMsg2 ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) !............................................................................................................................... ! get inputs at t+dt: !............................................................................................................................... t_next = t+p%dt - - CALL SrvD_CopyInput( Inputs(1), u_interp, MESH_NEWCOPY, ErrStat2, ErrMsg2 ) - CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) - IF (ErrStat >= AbortErrLev) THEN - CALL Cleanup() - RETURN - END IF - + CALL SrvD_Input_ExtrapInterp( Inputs, InputTimes, u_interp, t_next, ErrStat2, ErrMsg2 ) - CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) + !............................................................................................................................... ! update remaining states to values at t+dt: @@ -930,7 +937,7 @@ SUBROUTINE SrvD_CalcOutput( t, u, p, x, xd, z, OtherState, y, m, ErrStat, ErrMsg ELSE m%dll_data%PrevBlPitch(1:p%NumBl) = m%dll_data%BlPitchCom ! used for linear ramp of delayed signal m%LastTimeCalled = t - CALL BladedInterface_CalcOutput( t, u, p, m, ErrStat2, ErrMsg2 ) + CALL BladedInterface_CalcOutput( t, u, p, m, xd, ErrStat2, ErrMsg2 ) CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName ) END IF @@ -1065,6 +1072,9 @@ SUBROUTINE SrvD_UpdateDiscState( t, u, p, x, xd, z, OtherState, m, ErrStat, ErrM ErrMsg = "" + ! Filter the inputs from the Supercontroller to ServoDyn + xd%ScInFilter = p%ScInAlpha * xd%ScInFilter + (1.0_SiKi - p%ScInAlpha) * u%SuperController + !xd%BlPitchFilter = p%BlAlpha * xd%BlPitchFilter + (1.0_ReKi - p%BlAlpha) * u%BlPitch !if ( p%PCMode == ControlMode_DLL ) then @@ -2212,6 +2222,14 @@ SUBROUTINE ReadPrimaryFile( InputFile, InputFileData, OutFileRoot, UnEc, ErrStat END DO + !---------------------- SUPERCONTROLLER ------------- + CALL ReadCom( UnIn, InputFile, 'Section Header: Supercontroller', ErrStat2, ErrMsg2, UnEc ) + CALL CheckError( ErrStat2, ErrMsg2 ) + IF ( ErrStat >= AbortErrLev ) RETURN + + CALL ReadVar( UnIn, InputFile, InputFileData%ScInCutoff, "ScInCutoff", "Cuttoff frequency for low-pass filter on Supercontroller Inputs (Hz)", ErrStat2, ErrMsg2, UnEc) + CALL CheckError( ErrStat2, ErrMsg2 ) + IF ( ErrStat >= AbortErrLev ) RETURN !---------------------- OUTPUT -------------------------------------------------- CALL ReadCom( UnIn, InputFile, 'Section Header: Output', ErrStat2, ErrMsg2, UnEc ) diff --git a/modules-local/servodyn/src/ServoDyn_Registry.txt b/modules-local/servodyn/src/ServoDyn_Registry.txt index 5e38f70350..e602695a86 100644 --- a/modules-local/servodyn/src/ServoDyn_Registry.txt +++ b/modules-local/servodyn/src/ServoDyn_Registry.txt @@ -121,6 +121,7 @@ typedef ^ SrvD_InputFile LOGICAL CompNTMD - - - "Compute nacelle tuned mass damp typedef ^ SrvD_InputFile CHARACTER(1024) NTMDfile - - - "File for nacelle tuned mass damper (quoted string)" - typedef ^ SrvD_InputFile LOGICAL CompTTMD - - - "Compute tower tuned mass damper {true/false}" - typedef ^ SrvD_InputFile CHARACTER(1024) TTMDfile - - - "File for tower tuned mass damper (quoted string)" - +typedef ^ SrvD_InputFile SiKi ScInCutOff - - - "Cuttoff frequency for low-pass filter on Supercontroller inputs" Hz # ..... Data for using Bladed DLLs ....................................................................................................... typedef ^ BladedDLLType SiKi avrSWAP {:} - - "The swap array: used to pass data to and from the DLL controller" "see Bladed DLL documentation" @@ -143,6 +144,8 @@ typedef ^ ContinuousStateType TMD_ContinuousStateType TTMD - - - "TMD module sta #typedef ^ DiscreteStateType ReKi BlPitchFilter {:} - - "blade pitch filter" - typedef ^ DiscreteStateType TMD_DiscreteStateType NTMD - - - "TMD module states - nacelle" - typedef ^ DiscreteStateType TMD_DiscreteStateType TTMD - - - "TMD module states - tower" - +typedef ^ DiscreteStateType SiKi ScInFilter {:} - - "Filtered inputs from supercontroller" - + # Define constraint states here: typedef ^ ConstraintStateType ReKi DummyConstrState - - - "Remove this variable if you have constraint states" - @@ -277,6 +280,7 @@ typedef ^ ParameterType TMD_ParameterType NTMD - - - "TMD module parameters - na typedef ^ ParameterType TMD_ParameterType TTMD - - - "TMD module parameters - tower" - typedef ^ ParameterType ReKi AvgWindSpeed - - - "average wind speed for the simulation" m/s typedef ^ ParameterType ReKi AirDens - - - "air density" kg/m^3 +typedef ^ ParameterType SiKi ScInAlpha - - - "Low pass filter cutoff parameter for Supercontroller inputs to ServoDyn" - # ..... Inputs .................................................................................................................... # Define inputs that are contained on the mesh here: From 93efe04b1f7c746829724b369c7b924115e5d1c4 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Wed, 14 Jun 2017 16:33:29 -0600 Subject: [PATCH 028/386] Fixed write outputs for multiple turbines, plus a few other minor fixes Added compiler directives for all OpenMP calls Moved the initial AWAE_UpdateStates call from FARM_InitialCO to AWAE_Init per the FAST.Farm plan --- glue-codes/fast-farm/src/FAST_Farm_IO.f90 | 227 ++++++++++++++++-- .../fast-farm/src/FAST_Farm_Registry.txt | 1 + glue-codes/fast-farm/src/FAST_Farm_Subs.f90 | 13 +- modules-local/awae/src/AWAE.f90 | 20 +- 4 files changed, 228 insertions(+), 33 deletions(-) diff --git a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 index 70faf72470..8125ea84a1 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_IO.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_IO.f90 @@ -9900,7 +9900,6 @@ SUBROUTINE Farm_InitOutput( farm, ErrStat, ErrMsg ) INTEGER(IntKi) :: indxLast ! The index of the last value to be written to an array INTEGER(IntKi) :: indxNext ! The index of the next value to be written to an array INTEGER(IntKi) :: NumOuts ! number of channels to be written to the output file(s) - INTEGER(IntKi) :: temp(20,9) WkDfVxTND(:,:,1) = RESHAPE( & @@ -11143,7 +11142,6 @@ SUBROUTINE SetOutParam(OutList, farm, ErrStat, ErrMsg ) LOGICAL :: InvalidOutput(0:MaxOutPts) ! This array determines if the output channel is valid for this configuration CHARACTER(ChanLenFF) :: OutListTmp ! A string to temporarily hold OutList(I) CHARACTER(*), PARAMETER :: RoutineName = "SetOutParam" - INTEGER :: nTurbOut ! min (p%NumTurbines,9), for output handling CHARACTER(OutStrLenM1) :: ValidParamAry(9423) ! This lists the names of the allowed parameters, which must be sorted alphabetically INTEGER(IntKi) :: ParamIndxAry (9423) ! This lists the index into AllOuts(:) of the allowed parameters ValidParamAry(:) CHARACTER(ChanLenFF), :: ParamUnitsAry(9423) ! This lists the units corresponding to the allowed parameters @@ -14708,35 +14706,174 @@ SUBROUTINE SetOutParam(OutList, farm, ErrStat, ErrMsg ) ! ..... Developer must add checking for invalid inputs here: ..... - nTurbOut = min(farm%p%NumTurbines,9) ! We only support output for the first 9 turbines, even if the farm has more than 9 - + ! Check Output radii and make sure they are >= 0 and <= Nr-1 : NOTE: This was actually already done during the input file read. do i = 1,farm%p%NOutRadii if ( (farm%p%OutRadii(i) < 0) .or. (farm%p%OutRadii(i) >= farm%AWAE%p%NumRadii) ) then - InvalidOutput( CtTN (i,: ) ) = .true. + InvalidOutput( CtTN (i, :) ) = .true. InvalidOutput( WkDfVxTND(i,:,1) ) = .true. InvalidOutput( WkDfVrTND(i,:,1) ) = .true. InvalidOutput( EddVisTND(i,:,1) ) = .true. InvalidOutput( EddAmbTND(i,:,1) ) = .true. InvalidOutput( EddShrTND(i,:,1) ) = .true. + InvalidOutput( WkDfVxTND(i,:,2) ) = .true. + InvalidOutput( WkDfVrTND(i,:,2) ) = .true. + InvalidOutput( EddVisTND(i,:,2) ) = .true. + InvalidOutput( EddAmbTND(i,:,2) ) = .true. + InvalidOutput( EddShrTND(i,:,2) ) = .true. + InvalidOutput( WkDfVxTND(i,:,3) ) = .true. + InvalidOutput( WkDfVrTND(i,:,3) ) = .true. + InvalidOutput( EddVisTND(i,:,3) ) = .true. + InvalidOutput( EddAmbTND(i,:,3) ) = .true. + InvalidOutput( EddShrTND(i,:,3) ) = .true. + InvalidOutput( WkDfVxTND(i,:,4) ) = .true. + InvalidOutput( WkDfVrTND(i,:,4) ) = .true. + InvalidOutput( EddVisTND(i,:,4) ) = .true. + InvalidOutput( EddAmbTND(i,:,4) ) = .true. + InvalidOutput( EddShrTND(i,:,4) ) = .true. + InvalidOutput( WkDfVxTND(i,:,5) ) = .true. + InvalidOutput( WkDfVrTND(i,:,5) ) = .true. + InvalidOutput( EddVisTND(i,:,5) ) = .true. + InvalidOutput( EddAmbTND(i,:,5) ) = .true. + InvalidOutput( EddShrTND(i,:,5) ) = .true. + InvalidOutput( WkDfVxTND(i,:,6) ) = .true. + InvalidOutput( WkDfVrTND(i,:,6) ) = .true. + InvalidOutput( EddVisTND(i,:,6) ) = .true. + InvalidOutput( EddAmbTND(i,:,6) ) = .true. + InvalidOutput( EddShrTND(i,:,6) ) = .true. + InvalidOutput( WkDfVxTND(i,:,7) ) = .true. + InvalidOutput( WkDfVrTND(i,:,7) ) = .true. + InvalidOutput( EddVisTND(i,:,7) ) = .true. + InvalidOutput( EddAmbTND(i,:,7) ) = .true. + InvalidOutput( EddShrTND(i,:,7) ) = .true. + InvalidOutput( WkDfVxTND(i,:,8) ) = .true. + InvalidOutput( WkDfVrTND(i,:,8) ) = .true. + InvalidOutput( EddVisTND(i,:,8) ) = .true. + InvalidOutput( EddAmbTND(i,:,8) ) = .true. + InvalidOutput( EddShrTND(i,:,8) ) = .true. + InvalidOutput( WkDfVxTND(i,:,9) ) = .true. + InvalidOutput( WkDfVrTND(i,:,9) ) = .true. + InvalidOutput( EddVisTND(i,:,9) ) = .true. + InvalidOutput( EddAmbTND(i,:,9) ) = .true. + InvalidOutput( EddShrTND(i,:,9) ) = .true. end if end do - DO i = farm%p%NOutRadii+1,9 ! Invalid tower nodes + DO i = farm%p%NOutRadii+1,20 - InvalidOutput( CtTN (i,: ) ) = .true. + InvalidOutput( CtTN (i, :) ) = .true. InvalidOutput( WkDfVxTND(i,:,1) ) = .true. InvalidOutput( WkDfVrTND(i,:,1) ) = .true. InvalidOutput( EddVisTND(i,:,1) ) = .true. InvalidOutput( EddAmbTND(i,:,1) ) = .true. InvalidOutput( EddShrTND(i,:,1) ) = .true. + InvalidOutput( WkDfVxTND(i,:,2) ) = .true. + InvalidOutput( WkDfVrTND(i,:,2) ) = .true. + InvalidOutput( EddVisTND(i,:,2) ) = .true. + InvalidOutput( EddAmbTND(i,:,2) ) = .true. + InvalidOutput( EddShrTND(i,:,2) ) = .true. + InvalidOutput( WkDfVxTND(i,:,3) ) = .true. + InvalidOutput( WkDfVrTND(i,:,3) ) = .true. + InvalidOutput( EddVisTND(i,:,3) ) = .true. + InvalidOutput( EddAmbTND(i,:,3) ) = .true. + InvalidOutput( EddShrTND(i,:,3) ) = .true. + InvalidOutput( WkDfVxTND(i,:,4) ) = .true. + InvalidOutput( WkDfVrTND(i,:,4) ) = .true. + InvalidOutput( EddVisTND(i,:,4) ) = .true. + InvalidOutput( EddAmbTND(i,:,4) ) = .true. + InvalidOutput( EddShrTND(i,:,4) ) = .true. + InvalidOutput( WkDfVxTND(i,:,5) ) = .true. + InvalidOutput( WkDfVrTND(i,:,5) ) = .true. + InvalidOutput( EddVisTND(i,:,5) ) = .true. + InvalidOutput( EddAmbTND(i,:,5) ) = .true. + InvalidOutput( EddShrTND(i,:,5) ) = .true. + InvalidOutput( WkDfVxTND(i,:,6) ) = .true. + InvalidOutput( WkDfVrTND(i,:,6) ) = .true. + InvalidOutput( EddVisTND(i,:,6) ) = .true. + InvalidOutput( EddAmbTND(i,:,6) ) = .true. + InvalidOutput( EddShrTND(i,:,6) ) = .true. + InvalidOutput( WkDfVxTND(i,:,7) ) = .true. + InvalidOutput( WkDfVrTND(i,:,7) ) = .true. + InvalidOutput( EddVisTND(i,:,7) ) = .true. + InvalidOutput( EddAmbTND(i,:,7) ) = .true. + InvalidOutput( EddShrTND(i,:,7) ) = .true. + InvalidOutput( WkDfVxTND(i,:,8) ) = .true. + InvalidOutput( WkDfVrTND(i,:,8) ) = .true. + InvalidOutput( EddVisTND(i,:,8) ) = .true. + InvalidOutput( EddAmbTND(i,:,8) ) = .true. + InvalidOutput( EddShrTND(i,:,8) ) = .true. + InvalidOutput( WkDfVxTND(i,:,9) ) = .true. + InvalidOutput( WkDfVrTND(i,:,9) ) = .true. + InvalidOutput( EddVisTND(i,:,9) ) = .true. + InvalidOutput( EddAmbTND(i,:,9) ) = .true. + InvalidOutput( EddShrTND(i,:,9) ) = .true. END DO - do i = nTurbOut+1,9 + DO i = farm%p%NOutDist+1,9 + + InvalidOutput( WkAxsXTD ( i,:) ) = .true. + InvalidOutput( WkAxsYTD ( i,:) ) = .true. + InvalidOutput( WkAxsZTD ( i,:) ) = .true. + InvalidOutput( WkPosXTD ( i,:) ) = .true. + InvalidOutput( WkPosYTD ( i,:) ) = .true. + InvalidOutput( WkPosZTD ( i,:) ) = .true. + InvalidOutput( WkVelXTD ( i,:) ) = .true. + InvalidOutput( WkVelYTD ( i,:) ) = .true. + InvalidOutput( WkVelZTD ( i,:) ) = .true. + InvalidOutput( WkDiamTD ( i,:) ) = .true. + InvalidOutput( WkDfVxTND(:,i,1) ) = .true. + InvalidOutput( WkDfVrTND(:,i,1) ) = .true. + InvalidOutput( EddVisTND(:,i,1) ) = .true. + InvalidOutput( EddAmbTND(:,i,1) ) = .true. + InvalidOutput( EddShrTND(:,i,1) ) = .true. + InvalidOutput( WkDfVxTND(:,i,2) ) = .true. + InvalidOutput( WkDfVrTND(:,i,2) ) = .true. + InvalidOutput( EddVisTND(:,i,2) ) = .true. + InvalidOutput( EddAmbTND(:,i,2) ) = .true. + InvalidOutput( EddShrTND(:,i,2) ) = .true. + InvalidOutput( WkDfVxTND(:,i,3) ) = .true. + InvalidOutput( WkDfVrTND(:,i,3) ) = .true. + InvalidOutput( EddVisTND(:,i,3) ) = .true. + InvalidOutput( EddAmbTND(:,i,3) ) = .true. + InvalidOutput( EddShrTND(:,i,3) ) = .true. + InvalidOutput( WkDfVxTND(:,i,4) ) = .true. + InvalidOutput( WkDfVrTND(:,i,4) ) = .true. + InvalidOutput( EddVisTND(:,i,4) ) = .true. + InvalidOutput( EddAmbTND(:,i,4) ) = .true. + InvalidOutput( EddShrTND(:,i,4) ) = .true. + InvalidOutput( WkDfVxTND(:,i,5) ) = .true. + InvalidOutput( WkDfVrTND(:,i,5) ) = .true. + InvalidOutput( EddVisTND(:,i,5) ) = .true. + InvalidOutput( EddAmbTND(:,i,5) ) = .true. + InvalidOutput( EddShrTND(:,i,5) ) = .true. + InvalidOutput( WkDfVxTND(:,i,6) ) = .true. + InvalidOutput( WkDfVrTND(:,i,6) ) = .true. + InvalidOutput( EddVisTND(:,i,6) ) = .true. + InvalidOutput( EddAmbTND(:,i,6) ) = .true. + InvalidOutput( EddShrTND(:,i,6) ) = .true. + InvalidOutput( WkDfVxTND(:,i,7) ) = .true. + InvalidOutput( WkDfVrTND(:,i,7) ) = .true. + InvalidOutput( EddVisTND(:,i,7) ) = .true. + InvalidOutput( EddAmbTND(:,i,7) ) = .true. + InvalidOutput( EddShrTND(:,i,7) ) = .true. + InvalidOutput( WkDfVxTND(:,i,8) ) = .true. + InvalidOutput( WkDfVrTND(:,i,8) ) = .true. + InvalidOutput( EddVisTND(:,i,8) ) = .true. + InvalidOutput( EddAmbTND(:,i,8) ) = .true. + InvalidOutput( EddShrTND(:,i,8) ) = .true. + InvalidOutput( WkDfVxTND(:,i,9) ) = .true. + InvalidOutput( WkDfVrTND(:,i,9) ) = .true. + InvalidOutput( EddVisTND(:,i,9) ) = .true. + InvalidOutput( EddAmbTND(:,i,9) ) = .true. + InvalidOutput( EddShrTND(:,i,9) ) = .true. + + END DO + + do i = farm%p%NOutTurb+1,9 InvalidOutput( RtAxsXT (i) ) = .true. InvalidOutput( RtAxsYT (i) ) = .true. @@ -14749,24 +14886,62 @@ SUBROUTINE SetOutParam(OutList, farm, ErrStat, ErrMsg ) InvalidOutput( TIAmbT (i) ) = .true. InvalidOutput( RtVAmbT (i) ) = .true. InvalidOutput( RtVRelT (i) ) = .true. - InvalidOutput( CtTN (:,i) ) = .true. - InvalidOutput( WkAxsXTD (:,i) ) = .true. - InvalidOutput( WkAxsYTD (:,i) ) = .true. - InvalidOutput( WkAxsZTD (:,i) ) = .true. - InvalidOutput( WkPosXTD (:,i) ) = .true. - InvalidOutput( WkPosYTD (:,i) ) = .true. - InvalidOutput( WkPosZTD (:,i) ) = .true. - InvalidOutput( WkVelXTD (:,i) ) = .true. - InvalidOutput( WkVelYTD (:,i) ) = .true. - InvalidOutput( WkVelZTD (:,i) ) = .true. - InvalidOutput( WkDiamTD(:,i) ) = .true. - - ! TODO: Once the following arrays support NumTurbines > 1, then add them back into this section - !InvalidOutput( WkDfVxTND(i,:,1) ) = .true. - !InvalidOutput( WkDfVrTND(i,:,1) ) = .true. - !InvalidOutput( EddVisTND(i,:,1) ) = .true. - !InvalidOutput( EddAmbTND(i,:,1) ) = .true. - !InvalidOutput( EddShrTND(i,:,1) ) = .true. + InvalidOutput( CtTN (:, i) ) = .true. + InvalidOutput( WkAxsXTD ( :,i) ) = .true. + InvalidOutput( WkAxsYTD ( :,i) ) = .true. + InvalidOutput( WkAxsZTD ( :,i) ) = .true. + InvalidOutput( WkPosXTD ( :,i) ) = .true. + InvalidOutput( WkPosYTD ( :,i) ) = .true. + InvalidOutput( WkPosZTD ( :,i) ) = .true. + InvalidOutput( WkVelXTD ( :,i) ) = .true. + InvalidOutput( WkVelYTD ( :,i) ) = .true. + InvalidOutput( WkVelZTD ( :,i) ) = .true. + InvalidOutput( WkDiamTD ( :,i) ) = .true. + InvalidOutput( WkDfVxTND(:,1,i) ) = .true. + InvalidOutput( WkDfVrTND(:,1,i) ) = .true. + InvalidOutput( EddVisTND(:,1,i) ) = .true. + InvalidOutput( EddAmbTND(:,1,i) ) = .true. + InvalidOutput( EddShrTND(:,1,i) ) = .true. + InvalidOutput( WkDfVxTND(:,2,i) ) = .true. + InvalidOutput( WkDfVrTND(:,2,i) ) = .true. + InvalidOutput( EddVisTND(:,2,i) ) = .true. + InvalidOutput( EddAmbTND(:,2,i) ) = .true. + InvalidOutput( EddShrTND(:,2,i) ) = .true. + InvalidOutput( WkDfVxTND(:,3,i) ) = .true. + InvalidOutput( WkDfVrTND(:,3,i) ) = .true. + InvalidOutput( EddVisTND(:,3,i) ) = .true. + InvalidOutput( EddAmbTND(:,3,i) ) = .true. + InvalidOutput( EddShrTND(:,3,i) ) = .true. + InvalidOutput( WkDfVxTND(:,4,i) ) = .true. + InvalidOutput( WkDfVrTND(:,4,i) ) = .true. + InvalidOutput( EddVisTND(:,4,i) ) = .true. + InvalidOutput( EddAmbTND(:,4,i) ) = .true. + InvalidOutput( EddShrTND(:,4,i) ) = .true. + InvalidOutput( WkDfVxTND(:,5,i) ) = .true. + InvalidOutput( WkDfVrTND(:,5,i) ) = .true. + InvalidOutput( EddVisTND(:,5,i) ) = .true. + InvalidOutput( EddAmbTND(:,5,i) ) = .true. + InvalidOutput( EddShrTND(:,5,i) ) = .true. + InvalidOutput( WkDfVxTND(:,6,i) ) = .true. + InvalidOutput( WkDfVrTND(:,6,i) ) = .true. + InvalidOutput( EddVisTND(:,6,i) ) = .true. + InvalidOutput( EddAmbTND(:,6,i) ) = .true. + InvalidOutput( EddShrTND(:,6,i) ) = .true. + InvalidOutput( WkDfVxTND(:,7,i) ) = .true. + InvalidOutput( WkDfVrTND(:,7,i) ) = .true. + InvalidOutput( EddVisTND(:,7,i) ) = .true. + InvalidOutput( EddAmbTND(:,7,i) ) = .true. + InvalidOutput( EddShrTND(:,7,i) ) = .true. + InvalidOutput( WkDfVxTND(:,8,i) ) = .true. + InvalidOutput( WkDfVrTND(:,8,i) ) = .true. + InvalidOutput( EddVisTND(:,8,i) ) = .true. + InvalidOutput( EddAmbTND(:,8,i) ) = .true. + InvalidOutput( EddShrTND(:,8,i) ) = .true. + InvalidOutput( WkDfVxTND(:,9,i) ) = .true. + InvalidOutput( WkDfVrTND(:,9,i) ) = .true. + InvalidOutput( EddVisTND(:,9,i) ) = .true. + InvalidOutput( EddAmbTND(:,9,i) ) = .true. + InvalidOutput( EddShrTND(:,9,i) ) = .true. end do diff --git a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt index 9c8037d7f0..242178689e 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Registry.txt +++ b/glue-codes/fast-farm/src/FAST_Farm_Registry.txt @@ -45,6 +45,7 @@ typedef ^ ParameterType CHARACTER(20) OutFmt - typedef ^ ParameterType CHARACTER(20) OutFmt_t - - - "Format used for time channel in text tabular output; resulting field should be 10 characters" - typedef ^ ParameterType IntKi FmtWidth - - - "width of the time OutFmt specifier" - typedef ^ ParameterType IntKi TChanLen - - - "width of the time channel" - +typedef ^ ParameterType IntKi NOutTurb - - - "Number of turbines for write output [1 to 9]" typedef ^ ParameterType IntKi NOutRadii - - - "Number of radial nodes for wake output for an individual rotor [0 to 20]" - typedef ^ ParameterType IntKi OutRadii {:} - - "List of radial nodes for wake output for an individual rotor [1 to NOutRadii]" - typedef ^ ParameterType IntKi NOutDist - - - "Number of downstream distances for wake output for an individual rotor [0 to 9]" - diff --git a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 index a08602239b..5351588836 100644 --- a/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 +++ b/glue-codes/fast-farm/src/FAST_Farm_Subs.f90 @@ -32,7 +32,9 @@ MODULE FAST_Farm_Subs USE FAST_Farm_IO USE FAST_Subs USE FASTWrapper +#ifdef PARALLEL_CODE USE OMP_LIB +#endif IMPLICIT NONE @@ -204,7 +206,7 @@ SUBROUTINE Farm_Initialize( farm, InputFile, ErrStat, ErrMsg ) END IF - + farm%p%NOutTurb = min(farm%p%NumTurbines,9) ! We only support output for the first 9 turbines, even if the farm has more than 9 farm%p%n_high_low = NINT( farm%p%dt / farm%p%dt_high ) @@ -1387,8 +1389,6 @@ subroutine FARM_InitialCO(farm, ErrStat, ErrMsg) !-------------------- ! 1b. CALL AWAE_CO - call AWAE_UpdateStates( 0.0_DbKi, -1, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & - farm%AWAE%OtherSt, farm%AWAE%m, errStat, errMsg ) call AWAE_CalcOutput( 0.0_DbKi, farm%AWAE%u, farm%AWAE%p, farm%AWAE%x, farm%AWAE%xd, farm%AWAE%z, & farm%AWAE%OtherSt, farm%AWAE%y, farm%AWAE%m, ErrStat2, ErrMsg2 ) call SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) @@ -1486,6 +1486,7 @@ subroutine FARM_InitialCO(farm, ErrStat, ErrMsg) end subroutine FARM_InitialCO +#ifdef PARALLEL_CODE !---------------------------------------------------------------------------------------------------------------------------------- !> This routine updates states each time increment. !! The update states algorithm: \n @@ -1581,6 +1582,7 @@ subroutine FARM_UpdateStates(t, n, farm, ErrStat, ErrMsg) if (ErrStat >= AbortErrLev) return end subroutine FARM_UpdateStates +#endif subroutine FARM_UpdateStatesSerial(t, n, farm, ErrStat, ErrMsg) REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds @@ -1682,7 +1684,7 @@ subroutine Farm_WriteOutput(n, t, farm, ErrStat, ErrMsg) ! Define the output channel specifying the current simulation time: farm%m%AllOuts( Time) = REAL( t, ReKi ) - do nt = 1, farm%p%NumTurbines + do nt = 1, farm%p%NOutTurb !....................................................................................... ! Super controller Outputs @@ -1862,6 +1864,7 @@ subroutine Farm_WriteOutput(n, t, farm, ErrStat, ErrMsg) end if end subroutine Farm_WriteOutput +#ifdef PARALLEL_CODE !---------------------------------------------------------------------------------------------------------------------------------- !> This routine calculates outputs at each time increment and solves for the inputs at the next step. !! The calculate output algorithm: \n @@ -1968,6 +1971,8 @@ subroutine FARM_CalcOutput(t, farm, ErrStat, ErrMsg) write(*,*) 'Total Farm_CO took '//trim(num2lstr(t6-tm1))//' seconds.' end subroutine FARM_CalcOutput +#endif + subroutine FARM_CalcOutputSerial(t, farm, ErrStat, ErrMsg) REAL(DbKi), INTENT(IN ) :: t !< Current simulation time in seconds type(All_FastFarm_Data), INTENT(INOUT) :: farm !< FAST.Farm data diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index e357516232..966d3f0673 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -27,7 +27,9 @@ module AWAE use NWTC_Library use AWAE_Types use AWAE_IO - use OMP_LIB +#ifdef PARALLEL_CODE + use OMP_LIB +#endif implicit none @@ -48,11 +50,14 @@ module AWAE public :: AWAE_TEST_Init_BadData public :: AWAE_TEST_Init_GoodData public :: AWAE_TEST_CalcOutput +#ifdef PARALLEL_CODE public :: AWAE_TEST_ExtractSlice public :: AWAE_TEST_LowResGridCalcs - +#endif + contains +#ifdef PARALLEL_CODE subroutine ExtractSliceOMP( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) @@ -109,6 +114,7 @@ subroutine ExtractSliceOMP( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) !$OMP END PARALLEL DO end subroutine ExtractSliceOMP +#endif subroutine ExtractSlice( sliceType, s, s0, szs, sz1, sz2, ds, V, slice) @@ -442,6 +448,7 @@ subroutine LowResGridCalcOutput(n, u, p, y, m, errStat, errMsg) end subroutine LowResGridCalcOutput +#ifdef PARALLEL_CODE !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine !! @@ -663,6 +670,7 @@ subroutine LowResGridCalcOutputOMP(n, u, p, y, Vdist_low, Vamb_low, m, errStat, end do end subroutine LowResGridCalcOutputOMP +#endif !---------------------------------------------------------------------------------------------------------------------------------- !> This subroutine !! @@ -1135,6 +1143,11 @@ subroutine AWAE_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO m%ny_wind = 0.0_ReKi m%nz_wind = 0.0_ReKi + + ! Read-in the ambient wind data for the initial calculate output + + call AWAE_UpdateStates( 0.0_DbKi, -1, u, p, x, xd, z, OtherState, m, errStat, errMsg ) + call Cleanup() contains @@ -1529,6 +1542,7 @@ subroutine AWAE_TEST_Init_GoodData(errStat, errMsg) end subroutine AWAE_TEST_Init_GoodData +#ifdef PARALLEL_CODE subroutine AWAE_TEST_LowResGridCalcs(errStat, errMsg) integer(IntKi), intent(out) :: errStat !< Error status @@ -1646,7 +1660,7 @@ subroutine AWAE_TEST_ExtractSlice(errStat, errMsg) end do end do end subroutine AWAE_TEST_ExtractSlice - +#endif subroutine AWAE_TEST_CalcOutput(errStat, errMsg) From 8030b5a6fdddc62b69d8dd6ccf8f3146ecf362d0 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Wed, 14 Jun 2017 16:55:12 -0600 Subject: [PATCH 029/386] Temporarily commented out the new SC section of the ServoDyn input file This should be uncommented once the supercontroller has been implemented and the input files have been updated. --- modules-local/servodyn/src/ServoDyn.f90 | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/modules-local/servodyn/src/ServoDyn.f90 b/modules-local/servodyn/src/ServoDyn.f90 index 192de85eee..c0537e84e4 100644 --- a/modules-local/servodyn/src/ServoDyn.f90 +++ b/modules-local/servodyn/src/ServoDyn.f90 @@ -2222,14 +2222,14 @@ SUBROUTINE ReadPrimaryFile( InputFile, InputFileData, OutFileRoot, UnEc, ErrStat END DO - !---------------------- SUPERCONTROLLER ------------- - CALL ReadCom( UnIn, InputFile, 'Section Header: Supercontroller', ErrStat2, ErrMsg2, UnEc ) - CALL CheckError( ErrStat2, ErrMsg2 ) - IF ( ErrStat >= AbortErrLev ) RETURN - - CALL ReadVar( UnIn, InputFile, InputFileData%ScInCutoff, "ScInCutoff", "Cuttoff frequency for low-pass filter on Supercontroller Inputs (Hz)", ErrStat2, ErrMsg2, UnEc) - CALL CheckError( ErrStat2, ErrMsg2 ) - IF ( ErrStat >= AbortErrLev ) RETURN + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED !---------------------- SUPERCONTROLLER ------------- + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED CALL ReadCom( UnIn, InputFile, 'Section Header: Supercontroller', ErrStat2, ErrMsg2, UnEc ) + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED CALL CheckError( ErrStat2, ErrMsg2 ) + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED IF ( ErrStat >= AbortErrLev ) RETURN + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED CALL ReadVar( UnIn, InputFile, InputFileData%ScInCutoff, "ScInCutoff", "Cuttoff frequency for low-pass filter on Supercontroller Inputs (Hz)", ErrStat2, ErrMsg2, UnEc) + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED CALL CheckError( ErrStat2, ErrMsg2 ) + !TODO: UNCOMMENT THIS ONCE THE SUPERCONTROLLER HAS BEEN IMPLEMENTED AND THE INPUT FILES HAVE BEEN UPDATED IF ( ErrStat >= AbortErrLev ) RETURN !---------------------- OUTPUT -------------------------------------------------- CALL ReadCom( UnIn, InputFile, 'Section Header: Output', ErrStat2, ErrMsg2, UnEc ) From 489ae1cfe8eac76b47b2e3eca9732b9b9c99d6dd Mon Sep 17 00:00:00 2001 From: Ganesh Vijayakumar Date: Thu, 15 Jun 2017 17:14:03 -0600 Subject: [PATCH 030/386] Check that the supercontroller is used before applying the filter --- modules-local/servodyn/src/ServoDyn.f90 | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/modules-local/servodyn/src/ServoDyn.f90 b/modules-local/servodyn/src/ServoDyn.f90 index 192de85eee..b8496e9de2 100644 --- a/modules-local/servodyn/src/ServoDyn.f90 +++ b/modules-local/servodyn/src/ServoDyn.f90 @@ -1072,8 +1072,10 @@ SUBROUTINE SrvD_UpdateDiscState( t, u, p, x, xd, z, OtherState, m, ErrStat, ErrM ErrMsg = "" - ! Filter the inputs from the Supercontroller to ServoDyn - xd%ScInFilter = p%ScInAlpha * xd%ScInFilter + (1.0_SiKi - p%ScInAlpha) * u%SuperController + if( allocated(u%SuperController) ) then + ! Filter the inputs from the Supercontroller to ServoDyn + xd%ScInFilter = p%ScInAlpha * xd%ScInFilter + (1.0_SiKi - p%ScInAlpha) * u%SuperController + end if !xd%BlPitchFilter = p%BlAlpha * xd%BlPitchFilter + (1.0_ReKi - p%BlAlpha) * u%BlPitch From cdc3c67014624e5c803fc6b89d6df498fd257647 Mon Sep 17 00:00:00 2001 From: Jason Jonkman Date: Thu, 15 Jun 2017 21:17:22 -0600 Subject: [PATCH 031/386] Fixed indexing bug in AWAE's HighResGridCalcOutput routine This bug resulted in incorrect results for multiple turbines. The bug was also fixed in the FAST.Farm plan. --- modules-local/awae/src/AWAE.f90 | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/modules-local/awae/src/AWAE.f90 b/modules-local/awae/src/AWAE.f90 index 966d3f0673..9877f72acc 100644 --- a/modules-local/awae/src/AWAE.f90 +++ b/modules-local/awae/src/AWAE.f90 @@ -747,7 +747,7 @@ subroutine HighResGridCalcOutput(n, u, p, y, m, errStat, errMsg) do nt2 = 1,p%NumTurbines if (nt /= nt2) then - x_end_plane = dot_product(u%xhat_plane(:,0,nt2), (p%Grid_high(:,nXYZ_high,nt2) - u%p_plane(:,0,nt2)) ) + x_end_plane = dot_product(u%xhat_plane(:,0,nt2), (p%Grid_high(:,nXYZ_high,nt) - u%p_plane(:,0,nt2)) ) do np = 0, maxPln !p%NumPlanes-2 @@ -756,7 +756,7 @@ subroutine HighResGridCalcOutput(n, u, p, y, m, errStat, errMsg) ! Construct the endcaps of the current wake plane volume x_start_plane = x_end_plane - x_end_plane = dot_product(u%xhat_plane(:,np+1,nt2), (p%Grid_high(:,nXYZ_high,nt2) - u%p_plane(:,np+1,nt2)) ) + x_end_plane = dot_product(u%xhat_plane(:,np+1,nt2), (p%Grid_high(:,nXYZ_high,nt) - u%p_plane(:,np+1,nt2)) ) ! test if the point is within the endcaps of the wake volume if ( ( x_start_plane >= 0.0_ReKi ) .and. ( x_end_plane < 0.0_ReKi ) ) then @@ -770,7 +770,7 @@ subroutine HighResGridCalcOutput(n, u, p, y, m, errStat, errMsg) p_tmp_plane = delta*m%pvec_ce(:,np,nt2) + deltad*m%pvec_cs(:,np,nt2) + ( delta*m%r_e(np,nt2) + deltad*m%r_s(np,nt2) )* tmp_vec / TwoNorm(tmp_vec) end if - r_vec_plane = p%Grid_high(:,nXYZ_high,nt2) - p_tmp_plane + r_vec_plane = p%Grid_high(:,nXYZ_high,nt) - p_tmp_plane r_tmp_plane = TwoNorm( r_vec_plane ) ! test if the point is within radial finite-difference grid From 1a2b253e9f58d1b71e33bcf008e536c7e54e6eb5 Mon Sep 17 00:00:00 2001 From: Ganesh Vijayakumar Date: Fri, 16 Jun 2017 23:56:16 -0600 Subject: [PATCH 032/386] Moving supercontroller data into a separate class stored as an object within the OpenFAST - C++ API The previous OpenFAST - C++ interface stores the states of the supercontroller within a separate supercontroller class with no control over the data. This does not conform to the FASTv8 interface because the supercontroller class cannot correct the supercontroller state once updateStates is called. Hence the OpenFAST - C++ API needs to store all the super controller states along with a duplicate copy for the prediction at the next time and pass it to the supercontroller functions everytime. Finally, when we are sure that enough corrections have been made, the states have to be updated to the next time step. Hence this commit does the following: 1. Move all existing supercontroller states storage into a separate Supercontroller class, create extra storage to store the predicted states at the next time step. 2. Change updateStates and calcOutputs to pass the states into the function. Any simulation with a supercontroller now needs to only supply a dynamic library with two functions: 1. void sc_updateStates(int nTurbines, int nInputsGlob, std::vector & sc_inputsGlob, int nInputsTurbine, std::vector & sc_inputsTurbine, int nGlobStates, std::vector & globStates_n, std::vector & globStates_np1, int nTurbineStates, std::vector & turbineStates_n, std::vector & turbineStates_np1); sc_updateStates_t * sc_updateStates; 2. void sc_calcOutputs(int nTurbines, int nInputsGlob, std::vector & sc_inputsGlob, int nInputsTurbine, std::vector & sc_inputsTurbine, int nGlobStates, std::vector & globStates, int nTurbineStates, std::vector & turbineStates, int nOutputsGlob, std::vector & sc_outputsGlob, int nOutputsTurbine, std::vector & sc_outputsTurbine); --- glue-codes/fast-cpp/CMakeLists.txt | 7 +- glue-codes/fast-cpp/src/FAST_Prog.cpp | 8 +- glue-codes/fast-cpp/src/OpenFAST.H | 26 +- glue-codes/fast-cpp/src/OpenFAST.cpp | 166 +++++---- glue-codes/fast-cpp/src/SC.H | 73 ++++ glue-codes/fast-cpp/src/SC.cpp | 319 ++++++++++++++++++ glue-codes/fast-cpp/src/SC.h | 39 --- .../fast-library/src/FAST_Library.f90 | 9 +- modules-local/fast-library/src/FAST_Library.h | 2 +- .../fast-library/src/FAST_Registry.txt | 1 + modules-local/fast-library/src/FAST_Subs.f90 | 10 +- modules-local/servodyn/src/ServoDyn.f90 | 4 +- .../servodyn/src/ServoDyn_Registry.txt | 2 + 13 files changed, 518 insertions(+), 148 deletions(-) create mode 100644 glue-codes/fast-cpp/src/SC.H create mode 100644 glue-codes/fast-cpp/src/SC.cpp delete mode 100644 glue-codes/fast-cpp/src/SC.h diff --git a/glue-codes/fast-cpp/CMakeLists.txt b/glue-codes/fast-cpp/CMakeLists.txt index 0c01e257fe..2bcd514fc7 100644 --- a/glue-codes/fast-cpp/CMakeLists.txt +++ b/glue-codes/fast-cpp/CMakeLists.txt @@ -21,15 +21,16 @@ find_package(MPI REQUIRED) find_package(HDF5 REQUIRED COMPONENTS C HL) find_package(YAMLCPP REQUIRED) +message("HDF5_INCLUDES" ${HDF5_INCLUDE_DIR}) include_directories(${YAML_INCLUDES}) -include_directories(${HDF5_INCLUDES}) +include_directories(${HDF5_INCLUDE_DIR}) include_directories(${CMAKE_SOURCE_DIR}/modules-local/fast-library/src/) include_directories(${CMAKE_BINARY_DIR}/modules-local/openfoam/) include_directories(${CMAKE_BINARY_DIR}/modules-local/supercontroller/) include_directories(${MPI_INCLUDE_PATH}) add_library(openfastcpplib - src/OpenFAST.cpp) + src/OpenFAST.cpp src/SC.cpp) target_link_libraries(openfastcpplib openfastlib ${HDF5_C_LIBRARIES} @@ -64,7 +65,7 @@ install(TARGETS openfastcpplib LIBRARY DESTINATION lib) install(FILES - src/OpenFAST.H src/SC.h + src/OpenFAST.H src/SC.H DESTINATION include) install(TARGETS openfastcpp diff --git a/glue-codes/fast-cpp/src/FAST_Prog.cpp b/glue-codes/fast-cpp/src/FAST_Prog.cpp index 2b6b79394d..44998337ac 100644 --- a/glue-codes/fast-cpp/src/FAST_Prog.cpp +++ b/glue-codes/fast-cpp/src/FAST_Prog.cpp @@ -67,8 +67,12 @@ void readInputFile(fast::fastInputs & fi, std::string cInterfaceInputFile, doubl if(cDriverInp["superController"]) { fi.scStatus = cDriverInp["superController"].as(); fi.scLibFile = cDriverInp["scLibFile"].as(); - fi.numScInputs = cDriverInp["numScInputs"].as(); - fi.numScOutputs = cDriverInp["numScOutputs"].as(); + fi.numScInputsGlob = cDriverInp["numScInputsGlob"].as(); + fi.numScOutputsGlob = cDriverInp["numScOutputsGlob"].as(); + fi.numScInputsTurbine = cDriverInp["numScInputsTurbine"].as(); + fi.numScOutputsTurbine = cDriverInp["numScOutputsTurbine"].as(); + fi.numScGlobStates = cDriverInp["numScGlobStates"].as(); + fi.numScTurbineStates = cDriverInp["numScTurbineStates"].as(); } fi.globTurbineData.resize(fi.nTurbinesGlob); diff --git a/glue-codes/fast-cpp/src/OpenFAST.H b/glue-codes/fast-cpp/src/OpenFAST.H index e9a605cc43..7b6abb7da0 100644 --- a/glue-codes/fast-cpp/src/OpenFAST.H +++ b/glue-codes/fast-cpp/src/OpenFAST.H @@ -19,7 +19,8 @@ #define MPICH_SKIP_MPICXX #endif #include "mpi.h" -#include "SC.h" +#include "SuperController_Types.h" +#include "SC.H" namespace fast { @@ -65,8 +66,9 @@ class fastInputs { bool scStatus; std::string scLibFile; - int numScInputs, numScOutputs; - + int numScInputsTurbine, numScOutputsTurbine; + int numScInputsGlob, numScOutputsGlob; + int numScGlobStates, numScTurbineStates; std::vector globTurbineData; // Constructor @@ -106,10 +108,14 @@ class OpenFAST { std::vector numForcePtsTwr; std::vector numVelPtsBlade; std::vector numVelPtsTwr; - int numScOutputs; // # outputs from the supercontroller == # inputs to the controller == NumSC2Ctrl - int numScInputs; // # inputs to the supercontroller == # outputs from the controller == NumCtrl2SC - std::vector scOutputsGlob; // # outputs from the supercontroller for all turbines - std::vector scInputsGlob; // # inputs to the supercontroller for all turbines + int numScOutputsTurbine; // # outputs from the supercontroller == # inputs to the controller == NumSC2Ctrl + int numScInputsTurbine; // # inputs to the supercontroller == # outputs from the controller == NumCtrl2SC + int numScOutputsGlob; // # outputs from the supercontroller == # inputs to glob == NumSC2Ctrl + int numScInputsGlob; // # inputs to the supercontroller == # outputs from glob == NumCtrl2SC + std::vector scOutputsTurbine; // # outputs from the supercontroller for turbines + std::vector scInputsTurbine; // # inputs to the supercontroller from turbines + std::vector scOutputsGlob; // # outputs from the supercontroller for glob + std::vector scInputsGlob; // # inputs to the supercontroller from glob std::vector > > forceNodeVel; // Velocity at force nodes - Store temporarily to interpolate to the velocity nodes std::vector > velNodeData; // Position and velocity data at the velocity (aerodyn) nodes - (nTurbines, nTimesteps * nPoints * 6) @@ -118,8 +124,8 @@ class OpenFAST { std::vector cDriver_Input_from_FAST; std::vector cDriver_Output_to_FAST; - std::vector cDriverSC_Input_from_FAST; - std::vector cDriverSC_Output_to_FAST; + std::vector scInputsTurbine_from_FAST; + std::vector scOutputsTurbine_to_FAST; // Turbine Number is DIFFERENT from TurbID. Turbine Number simply runs from 0:n-1 locally and globally. std::map turbineMapGlobToProc; // Mapping global turbine number to processor number @@ -137,7 +143,7 @@ class OpenFAST { create_sc_t * create_SuperController; typedef void destroy_sc_t(SuperController *); destroy_sc_t * destroy_SuperController; - SuperController * sc; + SuperController sc; int fastMPIGroupSize; MPI_Group fastMPIGroup; diff --git a/glue-codes/fast-cpp/src/OpenFAST.cpp b/glue-codes/fast-cpp/src/OpenFAST.cpp index 2e18fa845a..96bbbce9e2 100644 --- a/glue-codes/fast-cpp/src/OpenFAST.cpp +++ b/glue-codes/fast-cpp/src/OpenFAST.cpp @@ -11,8 +11,8 @@ tMax(0.0), dtFAST(0.0), scStatus(false), scLibFile(""), -numScInputs(0), -numScOutputs(0) +numScInputsTurbine(0), +numScOutputsTurbine(0) { //Nothing to do here } @@ -44,7 +44,7 @@ void fast::OpenFAST::init() { for (int iTurb=0; iTurb < nTurbinesProc; iTurb++) { /* note that this will set nt_global inside the FAST library */ - FAST_OpFM_Restart(&iTurb, CheckpointFileRoot[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &ntStart, &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &cDriverSC_Input_from_FAST[iTurb], &cDriverSC_Output_to_FAST[iTurb], &ErrStat, ErrMsg); + FAST_OpFM_Restart(&iTurb, CheckpointFileRoot[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &ntStart, &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &scInputsTurbine_from_FAST[iTurb], &scOutputsTurbine_to_FAST[iTurb], &ErrStat, ErrMsg); checkError(ErrStat, ErrMsg); nt_global = ntStart; @@ -57,17 +57,21 @@ void fast::OpenFAST::init() { if (nTurbinesProc > 0) velNodeDataFile = openVelocityDataFile(false); if(scStatus) { - sc->readRestartFile(nt_global); + sc.readRestartFile(nt_global); } break ; case fast::init: - // this calls the Init() routines of each module + if(scStatus) { + sc.init(nTurbinesGlob); + sc.calcOutputs(scInputsGlob, scInputsTurbine, scOutputsGlob, scOutputsTurbine); + } + // this calls the Init() routines of each module for (int iTurb=0; iTurb < nTurbinesProc; iTurb++) { - FAST_OpFM_Init(&iTurb, &tMax, FASTInputFileName[iTurb].data(), &TurbID[iTurb], &numScOutputs, &numScInputs, &numForcePtsBlade[iTurb], &numForcePtsTwr[iTurb], TurbineBasePos[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &cDriverSC_Input_from_FAST[iTurb], &cDriverSC_Output_to_FAST[iTurb], &ErrStat, ErrMsg); + FAST_OpFM_Init(&iTurb, &tMax, FASTInputFileName[iTurb].data(), &TurbID[iTurb], &numScOutputsTurbine, &numScInputsTurbine, scOutputsTurbine.data(), &numForcePtsBlade[iTurb], &numForcePtsTwr[iTurb], TurbineBasePos[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &scInputsTurbine_from_FAST[iTurb], &scOutputsTurbine_to_FAST[iTurb], &ErrStat, ErrMsg); checkError(ErrStat, ErrMsg); timeZero = true; @@ -91,8 +95,13 @@ void fast::OpenFAST::init() { case fast::restartDriverInitFAST: + if(scStatus) { + sc.init(nTurbinesGlob); + sc.calcOutputs(scInputsGlob, scInputsTurbine, scOutputsGlob, scOutputsTurbine); + } + for (int iTurb=0; iTurb < nTurbinesProc; iTurb++) { - FAST_OpFM_Init(&iTurb, &tMax, FASTInputFileName[iTurb].data(), &TurbID[iTurb], &numScOutputs, &numScInputs, &numForcePtsBlade[iTurb], &numForcePtsTwr[iTurb], TurbineBasePos[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &cDriverSC_Input_from_FAST[iTurb], &cDriverSC_Output_to_FAST[iTurb], &ErrStat, ErrMsg); + FAST_OpFM_Init(&iTurb, &tMax, FASTInputFileName[iTurb].data(), &TurbID[iTurb], &numScOutputsTurbine, &numScInputsTurbine, scOutputsTurbine.data(), &numForcePtsBlade[iTurb], &numForcePtsTwr[iTurb], TurbineBasePos[iTurb].data(), &AbortErrLev, &dtFAST, &numBlades[iTurb], &numVelPtsBlade[iTurb], &cDriver_Input_from_FAST[iTurb], &cDriver_Output_to_FAST[iTurb], &scInputsTurbine_from_FAST[iTurb], &scOutputsTurbine_to_FAST[iTurb], &ErrStat, ErrMsg); checkError(ErrStat, ErrMsg); timeZero = true; @@ -152,9 +161,7 @@ void fast::OpenFAST::solution0() { if(scStatus) { - sc->init(nTurbinesGlob, numScInputs, numScOutputs); - - sc->calcOutputs(scOutputsGlob); + sc.calcOutputs(scInputsGlob, scInputsTurbine, scOutputsGlob, scOutputsTurbine); fillScOutputsLoc(); } @@ -181,8 +188,8 @@ void fast::OpenFAST::step() { ********************************* */ if(scStatus) { - sc->calcOutputs(scOutputsGlob); - fillScOutputsLoc(); + sc.calcOutputs(scInputsGlob, scInputsTurbine, scOutputsGlob, scOutputsTurbine); + fillScOutputsLoc(); } for (int iTurb=0; iTurb < nTurbinesProc; iTurb++) { @@ -223,7 +230,8 @@ void fast::OpenFAST::step() { } if(scStatus) { - sc->updateStates(scInputsGlob); // Go from 'n' to 'n+1' based on input at previous time step + sc.updateStates(scInputsGlob, scInputsTurbine); // Predict state at 'n+1' based on inputs + sc.advanceStates(); // Advance states from 'n' to 'n+1' fillScInputsGlob(); // Update inputs to super controller for 'n+1' } @@ -238,7 +246,7 @@ void fast::OpenFAST::step() { } if(scStatus) { if (fastMPIRank == 0) { - sc->writeRestartFile(nt_global); + sc.writeRestartFile(nt_global); } } } @@ -252,8 +260,8 @@ void fast::OpenFAST::stepNoWrite() { ********************************* */ if(scStatus) { - sc->calcOutputs(scOutputsGlob); - fillScOutputsLoc(); + sc.calcOutputs(scInputsGlob, scInputsTurbine, scOutputsGlob, scOutputsTurbine); + fillScOutputsLoc(); } for (int iTurb=0; iTurb < nTurbinesProc; iTurb++) { @@ -269,7 +277,7 @@ void fast::OpenFAST::stepNoWrite() { } if(scStatus) { - sc->updateStates(scInputsGlob); // Go from 'n' to 'n+1' based on input at previous time step + sc.updateStates(scInputsTurbine, scInputsGlob); // Go from 'n' to 'n+1' based on input at previous time step fillScInputsGlob(); // Update inputs to super controller for 'n+1' } @@ -711,8 +719,8 @@ void fast::OpenFAST::allocateMemory() { cDriver_Input_from_FAST.resize(nTurbinesProc) ; cDriver_Output_to_FAST.resize(nTurbinesProc) ; - cDriverSC_Input_from_FAST.resize(nTurbinesProc) ; - cDriverSC_Output_to_FAST.resize(nTurbinesProc) ; + scInputsTurbine_from_FAST.resize(nTurbinesProc) ; + scOutputsTurbine_to_FAST.resize(nTurbinesProc) ; } @@ -745,15 +753,8 @@ void fast::OpenFAST::end() { MPI_Group_free(&worldMPIGroup); if(scStatus) { - - destroy_SuperController(sc) ; - - if(scLibHandle != NULL) { - // close the library - std::cout << "Closing library...\n"; - dlclose(scLibHandle); - } - + sc.end(); + } } @@ -911,57 +912,54 @@ void fast::OpenFAST::loadSuperController(const fast::fastInputs & fi) { if(fi.scStatus) { scStatus = fi.scStatus; - scLibFile = fi.scLibFile; - - // open the library - scLibHandle = dlopen(scLibFile.c_str(), RTLD_LAZY); - if (!scLibHandle) { - std::cerr << "Cannot open library: " << dlerror() << '\n'; - } - - create_SuperController = (create_sc_t*) dlsym(scLibHandle, "create_sc"); - // reset errors - dlerror(); - const char *dlsym_error = dlerror(); - if (dlsym_error) { - std::cerr << "Cannot load symbol 'create_sc': " << dlsym_error << '\n'; - dlclose(scLibHandle); - } - - destroy_SuperController = (destroy_sc_t*) dlsym(scLibHandle, "destroy_sc"); - // reset errors - dlerror(); - const char *dlsym_error_us = dlerror(); - if (dlsym_error_us) { - std::cerr << "Cannot load symbol 'destroy_sc': " << dlsym_error_us << '\n'; - dlclose(scLibHandle); - } - - sc = create_SuperController() ; - - numScInputs = fi.numScInputs; - numScOutputs = fi.numScOutputs; - if ( (numScInputs > 0) && (numScOutputs > 0)) { - scOutputsGlob.resize(nTurbinesGlob*numScOutputs) ; - scInputsGlob.resize(nTurbinesGlob*numScInputs) ; - for (int iTurb=0; iTurb < nTurbinesGlob; iTurb++) { - for(int iInput=0; iInput < numScInputs; iInput++) { - scInputsGlob[iTurb*numScInputs + iInput] = 0.0 ; // Initialize to zero - } - for(int iOutput=0; iOutput < numScOutputs; iOutput++) { - scOutputsGlob[iTurb*numScOutputs + iOutput] = 0.0 ; // Initialize to zero - } - } + numScInputsTurbine = fi.numScInputsTurbine; + numScOutputsTurbine = fi.numScOutputsTurbine; + numScInputsGlob = fi.numScInputsGlob; + numScOutputsGlob = fi.numScOutputsGlob; + + if ( (numScInputsTurbine > 0) && (numScOutputsTurbine > 0) ) { + + scOutputsTurbine.resize(nTurbinesGlob*numScOutputsTurbine) ; + scInputsTurbine.resize(nTurbinesGlob*numScInputsTurbine) ; + for (int iTurb=0; iTurb < nTurbinesGlob; iTurb++) { + for(int iInput=0; iInput < numScInputsTurbine; iInput++) { + scInputsTurbine[iTurb*numScInputsTurbine + iInput] = 0.0 ; // Initialize to zero + } + for(int iOutput=0; iOutput < numScOutputsTurbine; iOutput++) { + scOutputsTurbine[iTurb*numScOutputsTurbine + iOutput] = 0.0 ; // Initialize to zero + } + } + if (numScInputsGlob < 1) { + throw std::runtime_error("Supercontroller: numScInputsGlob should be atleast 1. Simulation time is always a global input to the supercontroller"); + } + scOutputsGlob.resize(numScOutputsGlob) ; + scInputsGlob.resize(numScInputsGlob) ; + for(int iInput=0; iInput < numScInputsGlob; iInput++) + scInputsGlob[iInput] = 0.0 ; // Initialize to zero + for(int iOutput=0; iOutput < numScOutputsGlob; iOutput++) + scOutputsGlob[iOutput] = 0.0 ; // Initialize to zero + + scInData sci ; + sci.nInputsTurbine = numScInputsTurbine ; + sci.nOutputsTurbine = numScOutputsTurbine ; + sci.nInputsGlob = numScInputsGlob ; + sci.nOutputsGlob = numScOutputsGlob ; + sci.nGlobStates = fi.numScGlobStates ; + sci.nTurbineStates = fi.numScTurbineStates ; + sci.scLibFile = fi.scLibFile ; + sc.load(sci); } else { - std::cerr << "Make sure numScInputs and numScOutputs are greater than zero" << std::endl; + std::cerr << "Make sure numScInputsTurbine and numScOutputsTurbine are greater than zero" << std::endl; } } else { scStatus = false; - numScInputs = 0; - numScOutputs = 0; + numScInputsGlob = 0; + numScOutputsGlob = 0; + numScInputsTurbine = 0; + numScOutputsTurbine = 0; } } @@ -972,19 +970,19 @@ void fast::OpenFAST::fillScInputsGlob() { // Fills the global array containing inputs to the supercontroller from all turbines for(int iTurb=0; iTurb < nTurbinesGlob; iTurb++) { - for(int iInput=0; iInput < numScInputs; iInput++) { - scInputsGlob[iTurb*numScInputs + iInput] = 0.0; // Initialize to zero + for(int iInput=0; iInput < numScInputsTurbine; iInput++) { + scInputsTurbine[iTurb*numScInputsTurbine + iInput] = 0.0; // Initialize to zero } } for(int iTurb=0; iTurb < nTurbinesProc; iTurb++) { - for(int iInput=0; iInput < numScInputs; iInput++) { - scInputsGlob[turbineMapProcToGlob[iTurb]*numScInputs + iInput] = cDriverSC_Input_from_FAST[iTurb].toSC[iInput] ; + for(int iInput=0; iInput < numScInputsTurbine; iInput++) { + scInputsTurbine[turbineMapProcToGlob[iTurb]*numScInputsTurbine + iInput] = scInputsTurbine_from_FAST[iTurb].toSC[iInput] ; } } if (MPI_COMM_NULL != fastMPIComm) { - MPI_Allreduce(MPI_IN_PLACE, scInputsGlob.data(), numScInputs*nTurbinesGlob, MPI_DOUBLE, MPI_SUM, fastMPIComm) ; + MPI_Allreduce(MPI_IN_PLACE, scInputsTurbine.data(), numScInputsTurbine*nTurbinesGlob, MPI_DOUBLE, MPI_SUM, fastMPIComm) ; } } @@ -995,20 +993,10 @@ void fast::OpenFAST::fillScOutputsLoc() { // Fills the local array containing outputs from the supercontroller to each turbine for(int iTurb=0; iTurb < nTurbinesProc; iTurb++) { - for(int iOutput=0; iOutput < numScOutputs; iOutput++) { - cDriverSC_Output_to_FAST[iTurb].fromSC[iOutput] = scOutputsGlob[turbineMapProcToGlob[iTurb]*numScOutputs + iOutput] ; + for(int iOutput=0; iOutput < numScOutputsTurbine; iOutput++) { + scOutputsTurbine_to_FAST[iTurb].fromSC[iOutput] = scOutputsTurbine[turbineMapProcToGlob[iTurb]*numScOutputsTurbine + iOutput] ; } } } - - - - - - - - - - diff --git a/glue-codes/fast-cpp/src/SC.H b/glue-codes/fast-cpp/src/SC.H new file mode 100644 index 0000000000..90c50db1c7 --- /dev/null +++ b/glue-codes/fast-cpp/src/SC.H @@ -0,0 +1,73 @@ +#include +#include +#include +#include "yaml-cpp/yaml.h" +#include "hdf5.h" +#include "dlfcn.h" + +class scInData { + +public: + int nInputsTurbine; + int nOutputsTurbine; + int nInputsGlob; + int nOutputsGlob; + int nGlobStates; + int nTurbineStates; + std::string scLibFile; + +}; + +class SuperController { + + private: + + int nTurbines; + int nInputsTurbine; + int nOutputsTurbine; + int nInputsGlob; + int nOutputsGlob; + + int nGlobStates; // Global states like time + std::vector globStates; + std::vector globStates_np1; + + int nTurbineStates; // States for each turbine + std::vector turbineStates ; + std::vector turbineStates_np1 ; + + double d2R = 0.01745329251 ; //Degrees to Radians + + //Supercontroller stuff + std::string scLibFile; + // Dynamic load stuff copied from 'C++ dlopen mini HOWTO' on tldp.org + void *scLibHandle ; + typedef void sc_updateStates_t(int nTurbines, int nInputsGlob, std::vector & sc_inputsGlob, int nInputsTurbine, std::vector & sc_inputsTurbine, int nGlobStates, std::vector & globStates_n, std::vector & globStates_np1, int nTurbineStates, std::vector & turbineStates_n, std::vector & turbineStates_np1); + sc_updateStates_t * sc_updateStates; + typedef void sc_calcOutputs_t(int nTurbines, int nInputsGlob, std::vector & sc_inputsGlob, int nInputsTurbine, std::vector & sc_inputsTurbine, int nGlobStates, std::vector & globStates, int nTurbineStates, std::vector & turbineStates, int nOutputsGlob, std::vector & sc_outputsGlob, int nOutputsTurbine, std::vector & sc_outputsTurbine); + sc_calcOutputs_t * sc_calcOutputs; + + + public: + + SuperController(); + + ~SuperController() ; + + void init(int nTurbinesGlob); + + void load(scInData sci); + + void calcOutputs(std::vector & sc_inputsGlob, std::vector & sc_inputsTurbine, std::vector & sc_outputsGlob, std::vector & sc_outputsTurbine) ; + + void updateStates(std::vector & sc_inputsGlob, std::vector & sc_inputsTurbine) ; //Make a prediction for 'n+1' based on 'n' + + void advanceStates() ; //Advance states to time step 'n+1' + + int writeRestartFile(int n_t_global); + + int readRestartFile(int n_t_global); + + void end() {} ; +}; + diff --git a/glue-codes/fast-cpp/src/SC.cpp b/glue-codes/fast-cpp/src/SC.cpp new file mode 100644 index 0000000000..8fad8501c2 --- /dev/null +++ b/glue-codes/fast-cpp/src/SC.cpp @@ -0,0 +1,319 @@ +#include "SC.h" + +SuperController::SuperController(): +nInputsTurbine(0), +nOutputsTurbine(0), +nInputsGlob(0), +nOutputsGlob(0), +nGlobStates(0), +nTurbineStates(0) +{ + +} + +SuperController::~SuperController() { + + + if(scLibHandle != NULL) { + // close the library + std::cout << "Closing SC library..." << std::endl; + dlclose(scLibHandle); + } + +} + +void SuperController::load(scInData sci) { + + nInputsTurbine = sci.nInputsTurbine; + nOutputsTurbine = sci.nOutputsTurbine; + nInputsGlob = sci.nInputsGlob; + nOutputsGlob = sci.nOutputsGlob; + nGlobStates = sci.nGlobStates; + nTurbineStates = sci.nTurbineStates; + scLibFile = sci.scLibFile; + + + if (nInputsGlob < 0) + std::cerr << "Supercontroller: nInputsGlob has to be greater than zero" << std::endl ; + + if (nOutputsGlob < 0) + std::cerr << "Supercontroller: nOutputsGlob is less than zero." << std::endl ; + + if (nGlobStates < 0) + std::cerr << "Supercontroller: nGlobStates has to be greater than zero" << std::endl ; + + if (nTurbineStates < 0) + std::cerr << "Supercontroller: nTurbineStates has to be greater than zero" << std::endl ; + + // open the library + scLibHandle = dlopen(scLibFile.c_str(), RTLD_LAZY); + if (!scLibHandle) { + std::cerr << "Cannot open library: " << dlerror() << '\n'; + } + + sc_updateStates = (sc_updateStates_t*) dlsym(scLibHandle, "sc_updateStates"); + // reset errors + const char *dlsym_error_us = dlerror(); + if (dlsym_error_us) { + std::cerr << "Cannot load symbol 'sc_updateStates': " << dlsym_error_us << '\n'; + dlclose(scLibHandle); + } + + sc_calcOutputs = (sc_calcOutputs_t*) dlsym(scLibHandle, "sc_calcOutputs"); + // reset errors + const char *dlsym_error_co = dlerror(); + if (dlsym_error_co) { + std::cerr << "Cannot load symbol 'sc_calcOutputs': " << dlsym_error_co << '\n'; + dlclose(scLibHandle); + } + +} + +void SuperController::init(int nTurbinesGlob) { + + nTurbines = nTurbinesGlob; + + globStates.resize(nGlobStates); + globStates_np1.resize(nGlobStates); + + turbineStates.resize(nTurbines*nTurbineStates); + turbineStates_np1.resize(nTurbines*nTurbineStates); + + // Initialize the turbine states at time zero - Not sure how to do this. May be call calcOut? + +} + +void SuperController::calcOutputs(std::vector & sc_inputsGlob, std::vector & sc_inputsTurbine, std::vector & sc_outputsGlob, std::vector & sc_outputsTurbine) { + + sc_calcOutputs(nTurbines, nInputsGlob, sc_inputsGlob, nInputsTurbine, sc_inputsTurbine, nGlobStates, globStates, nTurbineStates, turbineStates, nOutputsGlob, sc_outputsGlob, nOutputsTurbine, sc_outputsTurbine); + +} + +void SuperController::advanceStates() { + + for(int iState=0; iState & sc_inputsGlob, std::vector & sc_inputsTurbine) { + + + // Meaning of scInputs + // 0 - Time + // 1 - GenTorque + + // Meaning of scOutputs + // 0 - Minimum Blade pitch + + + // Turbine 0 + /* Vary PC_MinPit as a function of time: */ + /* 0-20s: 0 degrees */ + /* 20-40s: 1.5 degrees */ + /* 40-60s: 3 degrees */ + + // Turbine 1 + /* Vary PC_MinPit as a function of time: */ + /* 0-20s: 0.5 degrees */ + /* 20-40s: 1 degrees */ + /* 40-60s: 2.5 degrees */ + + sc_updateStates(nTurbines, nInputsGlob, sc_inputsGlob, nInputsTurbine, sc_inputsTurbine, nGlobStates, globStates, globStates_np1, nTurbineStates, turbineStates, turbineStates_np1) ; + +/* //Copy inputs into states first */ + + } + +int SuperController::readRestartFile(int n_t_global) { + + hid_t restartFile = H5Fopen(("sc" + std::to_string(n_t_global) + ".chkp.h5").c_str(), H5F_ACC_RDWR, H5P_DEFAULT); + + { + hid_t attr = H5Aopen(restartFile, "nTurbines", H5P_DEFAULT); + herr_t ret = H5Aread(attr, H5T_NATIVE_INT, &nTurbines) ; + H5Aclose(attr); + + attr = H5Aopen(restartFile, "nInputsTurbine", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nInputsTurbine) ; + H5Aclose(attr); + + attr = H5Aopen(restartFile, "nOutputsTurbine", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nOutputsTurbine) ; + H5Aclose(attr); + + attr = H5Aopen(restartFile, "nInputsGlob", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nInputsGlob) ; + H5Aclose(attr); + + attr = H5Aopen(restartFile, "nOutputsGlob", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nOutputsGlob) ; + H5Aclose(attr); + + attr = H5Aopen(restartFile, "nGlobStates", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nGlobStates) ; + H5Aclose(attr); + + globStates.resize(nGlobStates); + globStates_np1.resize(nGlobStates); + + attr = H5Aopen(restartFile, "nTurbineStates", H5P_DEFAULT); + ret = H5Aread(attr, H5T_NATIVE_INT, &nTurbineStates) ; + H5Aclose(attr); + + turbineStates.resize(nTurbines*nTurbineStates); + turbineStates_np1.resize(nTurbines*nTurbineStates); + +#ifdef DEBUG + std::cout << "nTurbines = " << nTurbines << std::endl ; + std::cout << "nInputsTurbine = " << nInputsTurbine << std::endl ; + std::cout << "nOutputsTurbine = " << nOutputsTurbine << std::endl ; + std::cout << "nInputsGlob = " << nInputsGlob << std::endl ; + std::cout << "nOutputsGlob = " << nOutputsGlob << std::endl ; + std::cout << "nGlobStates = " << nGlobStates << std::endl ; + std::cout << "nTurbineStates = " << nTurbineStates << std::endl ; +#endif + + } + + if (nGlobStates > 0) { + hid_t dataSet = H5Dopen2(restartFile, "/globStates", H5P_DEFAULT); + herr_t status = H5Dread(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, globStates.data()); + status = H5Dclose(dataSet); + + dataSet = H5Dopen2(restartFile, "/globStates_np1", H5P_DEFAULT); + status = H5Dread(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, globStates_np1.data()); + status = H5Dclose(dataSet); + } + + if (nTurbineStates > 0) { + hid_t dataSet = H5Dopen2(restartFile, "turbineStates", H5P_DEFAULT); + herr_t status = H5Dread(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, turbineStates.data()); + status = H5Dclose(dataSet); + + dataSet = H5Dopen2(restartFile, "turbineStates_np1", H5P_DEFAULT); + status = H5Dread(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, turbineStates_np1.data()); + status = H5Dclose(dataSet); + } + +#ifdef DEBUG + for(int iTurb=0; iTurb < nTurbines; iTurb++) { + for(int i=0; i < nTurbineStates; i++) { + std::cout << "iTurb = " << iTurb << ", i = " << i << ", " ; + std::cout << turbineStates[iTurb*nTurbineStates + i] << std::endl ; + } + } +#endif + herr_t status = H5Fclose(restartFile); + +} + + +int SuperController::writeRestartFile(int n_t_global) { + + /* // HDF5 stuff to write states to restart file or read back from it */ + + hid_t restartFile = H5Fcreate(("sc" + std::to_string(n_t_global) + ".chkp.h5").c_str(), H5F_ACC_TRUNC, H5P_DEFAULT, H5P_DEFAULT); + + { + hsize_t dims[1]; + dims[0] = 1; + hid_t dataSpace = H5Screate_simple(1, dims, NULL); + hid_t attr = H5Acreate2(restartFile, "nTurbines", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + herr_t status = H5Awrite(attr, H5T_NATIVE_INT, &nTurbines); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nInputsTurbine", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nInputsTurbine); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nOutputsTurbine", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nOutputsTurbine); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nInputsGlob", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nInputsGlob); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nOutputsGlob", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nOutputsGlob); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nGlobStates", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nGlobStates); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + attr = H5Acreate2(restartFile, "nTurbineStates", H5T_NATIVE_INT, dataSpace, H5P_DEFAULT, H5P_DEFAULT) ; + status = H5Awrite(attr, H5T_NATIVE_INT, &nTurbineStates); + status = H5Aclose(attr); + status = H5Sclose(dataSpace); + + } + + if (nGlobStates > 0) { + hsize_t dims[1]; + dims[0] = nGlobStates; + hid_t dataSpace = H5Screate_simple(1, dims, NULL); + hid_t dataSet = H5Dcreate2(restartFile, "/globStates", H5T_NATIVE_DOUBLE, dataSpace, H5P_DEFAULT, H5P_DEFAULT, H5P_DEFAULT); + herr_t status = H5Dwrite(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, globStates.data()); + + status = H5Dclose(dataSet); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(1, dims, NULL); + dataSet = H5Dcreate2(restartFile, "/globStates_np1", H5T_NATIVE_DOUBLE, dataSpace, H5P_DEFAULT, H5P_DEFAULT, H5P_DEFAULT); + status = H5Dwrite(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, globStates_np1.data()); + + status = H5Dclose(dataSet); + status = H5Sclose(dataSpace); + + + } + + if (nTurbineStates > 0) { + + hsize_t dims[2]; + dims[0] = nTurbines; + dims[1] = nTurbineStates; + + hid_t dataSpace = H5Screate_simple(2, dims, NULL); + hid_t dataSet = H5Dcreate2(restartFile, "turbineStates", H5T_NATIVE_DOUBLE, dataSpace, H5P_DEFAULT, H5P_DEFAULT, H5P_DEFAULT); + herr_t status = H5Dwrite(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, turbineStates.data()); + + status = H5Dclose(dataSet); + status = H5Sclose(dataSpace); + + dataSpace = H5Screate_simple(2, dims, NULL); + dataSet = H5Dcreate2(restartFile, "turbineStates_np1", H5T_NATIVE_DOUBLE, dataSpace, H5P_DEFAULT, H5P_DEFAULT, H5P_DEFAULT); + status = H5Dwrite(dataSet, H5T_NATIVE_DOUBLE, H5S_ALL, H5S_ALL, H5P_DEFAULT, turbineStates_np1.data()); + + status = H5Dclose(dataSet); + status = H5Sclose(dataSpace); + } + + herr_t status = H5Fclose(restartFile); + + return 0; + +} + + diff --git a/glue-codes/fast-cpp/src/SC.h b/glue-codes/fast-cpp/src/SC.h deleted file mode 100644 index 423d0b78a4..0000000000 --- a/glue-codes/fast-cpp/src/SC.h +++ /dev/null @@ -1,39 +0,0 @@ - -#include "SuperController_Types.h" -#include -#include -#include "hdf5.h" -#include - -class SuperController { - - private: - - int nTurbines; - int nScInputs; - int nScOutputs; - - int nGlobStates; // Global states like time - double * globStates; - - int nTurbineStates; // States for each turbine - double ** turbineStates ; - - double d2R = 0.01745329251 ; //Degrees to Radians - - public: - - SuperController(); - - virtual ~SuperController() ; - - virtual void init(int n, int numScInputs, int numScOutputs); - - virtual void calcOutputs(std::vector & scOutputsGlob) ; - - virtual void updateStates(std::vector & scInputsGlob) ; - - virtual int writeRestartFile(int n_t_global); - - virtual int readRestartFile(int n_t_global); -}; diff --git a/modules-local/fast-library/src/FAST_Library.f90 b/modules-local/fast-library/src/FAST_Library.f90 index 5fbaa7959f..186d04c42d 100644 --- a/modules-local/fast-library/src/FAST_Library.f90 +++ b/modules-local/fast-library/src/FAST_Library.f90 @@ -422,7 +422,7 @@ subroutine FAST_Restart(iTurb, CheckpointRootName_c, AbortErrLev_c, NumOuts_c, d end subroutine FAST_Restart !================================================================================================================================== -subroutine FAST_OpFM_Init(iTurb, TMax, InputFileName_c, TurbID, NumSC2Ctrl, NumCtrl2SC, NumActForcePtsBlade, NumActForcePtsTower, TurbPosn, AbortErrLev_c, dt_c, NumBl_c, NumBlElem_c, & +subroutine FAST_OpFM_Init(iTurb, TMax, InputFileName_c, TurbID, NumSC2Ctrl, NumCtrl2SC, InitSCOutputsTurbine, NumActForcePtsBlade, NumActForcePtsTower, TurbPosn, AbortErrLev_c, dt_c, NumBl_c, NumBlElem_c, & OpFM_Input_from_FAST, OpFM_Output_to_FAST, SC_Input_from_FAST, SC_Output_to_FAST, ErrStat_c, ErrMsg_c) BIND (C, NAME='FAST_OpFM_Init') !DEC$ ATTRIBUTES DLLEXPORT::FAST_OpFM_Init IMPLICIT NONE @@ -435,6 +435,7 @@ subroutine FAST_OpFM_Init(iTurb, TMax, InputFileName_c, TurbID, NumSC2Ctrl, NumC INTEGER(C_INT), INTENT(IN ) :: TurbID ! Need not be same as iTurb INTEGER(C_INT), INTENT(IN ) :: NumSC2Ctrl ! Supercontroller outputs = controller inputs INTEGER(C_INT), INTENT(IN ) :: NumCtrl2SC ! controller outputs = Supercontroller inputs + REAL(C_FLOAT), INTENT(IN ) :: InitScOutputsTurbine (:) ! Initial Supercontroller outputs = controller inputs INTEGER(C_INT), INTENT(IN ) :: NumActForcePtsBlade ! number of actuator line force points in blade INTEGER(C_INT), INTENT(IN ) :: NumActForcePtsTower ! number of actuator line force points in tower REAL(C_FLOAT), INTENT(IN ) :: TurbPosn(3) @@ -470,6 +471,12 @@ subroutine FAST_OpFM_Init(iTurb, TMax, InputFileName_c, TurbID, NumSC2Ctrl, NumC ExternInitData%SensorType = SensorType_None ExternInitData%NumCtrl2SC = NumCtrl2SC ExternInitData%NumSC2Ctrl = NumSC2Ctrl + if ( (NumSC2Ctrl .gt. 0) .and. (NumCtrl2SC .gt. 0) ) then + CALL AllocAry( ExternInitData%InitScOutputsTurbine, NumSC2Ctrl, 'ExternInitData%InitScOutputsTurbine', ErrStat, ErrMsg) + do i=1,NumSC2Ctrl + ExternInitData%InitScOutputsTurbine(i) = InitScOutputsTurbine(i) + end do + end if ExternInitData%NumActForcePtsBlade = NumActForcePtsBlade ExternInitData%NumActForcePtsTower = NumActForcePtsTower diff --git a/modules-local/fast-library/src/FAST_Library.h b/modules-local/fast-library/src/FAST_Library.h index 645e07f102..2f456cacb7 100644 --- a/modules-local/fast-library/src/FAST_Library.h +++ b/modules-local/fast-library/src/FAST_Library.h @@ -12,7 +12,7 @@ EXTERNAL_ROUTINE void FAST_AllocateTurbines(int * iTurb, int *ErrStat, char *Err EXTERNAL_ROUTINE void FAST_OpFM_Restart(int * iTurb, const char *CheckpointRootName, int *AbortErrLev, double * dt, int * NumBl, int * NumBlElem, int * n_t_global, OpFM_InputType_t* OpFM_Input, OpFM_OutputType_t* OpFM_Output, SC_InputType_t* SC_Input, SC_OutputType_t* SC_Output, int *ErrStat, char *ErrMsg); -EXTERNAL_ROUTINE void FAST_OpFM_Init(int * iTurb, double *TMax, const char *InputFileName, int * TurbineID, int * NumSC2Ctrl, int * NumCtrl2SC, int * NumActForcePtsBlade, int * NumActForcePtsTower, float * TurbinePosition, +EXTERNAL_ROUTINE void FAST_OpFM_Init(int * iTurb, double *TMax, const char *InputFileName, int * TurbineID, int * NumSC2Ctrl, int * NumCtrl2SC, double * initSCInputsTurbine, int * NumActForcePtsBlade, int * NumActForcePtsTower, float * TurbinePosition, int *AbortErrLev, double * dt, int * NumBl, int * NumBlElem, OpFM_InputType_t* OpFM_Input, OpFM_OutputType_t* OpFM_Output, SC_InputType_t* SC_Input, SC_OutputType_t* SC_Output, int *ErrStat, char *ErrMsg); EXTERNAL_ROUTINE void FAST_OpFM_Solution0(int * iTurb, int *ErrStat, char *ErrMsg); diff --git a/modules-local/fast-library/src/FAST_Registry.txt b/modules-local/fast-library/src/FAST_Registry.txt index ca0ca7f214..59ff51d5ff 100644 --- a/modules-local/fast-library/src/FAST_Registry.txt +++ b/modules-local/fast-library/src/FAST_Registry.txt @@ -483,6 +483,7 @@ typedef ^ FAST_ExternInitType IntKi TurbineID - 0 - "ID number for turbine (used typedef ^ FAST_ExternInitType ReKi TurbinePos {3} - - "Initial position of turbine base (origin used in future for graphics)" m typedef ^ FAST_ExternInitType IntKi NumSC2Ctrl - - - "number of controller inputs [from supercontroller]" - typedef ^ FAST_ExternInitType IntKi NumCtrl2SC - - - "number of controller outputs [to supercontroller]" - +typedef ^ FAST_ExternInitType ReKi InitScOutputsTurbine {:} - - "Initial inputs to the controller [from the supercontroller]" - typedef ^ FAST_ExternInitType logical FarmIntegration - .false. - "whether this is called from FAST.Farm (or another program that doesn't want FAST to call all of the init stuff first)" - typedef ^ FAST_ExternInitType IntKi windGrid_n 4 - - "number of grid points in the x, y, z, and t directions for IfW" - typedef ^ FAST_ExternInitType ReKi windGrid_delta 4 - - "size between 2 consecutive grid points in each grid direction for IfW" "m,m,m,s" diff --git a/modules-local/fast-library/src/FAST_Subs.f90 b/modules-local/fast-library/src/FAST_Subs.f90 index b64c8dd825..4219271520 100644 --- a/modules-local/fast-library/src/FAST_Subs.f90 +++ b/modules-local/fast-library/src/FAST_Subs.f90 @@ -684,7 +684,15 @@ SUBROUTINE FAST_InitializeAll( t_initial, p_FAST, y_FAST, m_FAST, ED, BD, SrvD, IF ( PRESENT(ExternInitData) ) THEN InitInData_SrvD%NumSC2Ctrl = ExternInitData%NumSC2Ctrl - InitInData_SrvD%NumCtrl2SC = ExternInitData%NumCtrl2SC + InitInData_SrvD%NumCtrl2SC = ExternInitData%NumCtrl2SC + IF ( (InitInData_SrvD%NumSC2Ctrl .gt. 0) .and. (InitInData_SrvD%NumSC2Ctrl .gt. 0)) THEN + CALL AllocAry( InitInData_SrvD%InitScOutputsTurbine, InitInData_SrvD%NumSC2Ctrl, 'InitInData_SrvD%InitScOutputsTurbine', ErrStat2, ErrMsg2) + CALL SetErrStat(ErrStat2,ErrMsg2,ErrStat,ErrMsg,RoutineName) + do i=1,InitInData_SrvD%NumSC2Ctrl + InitInData_SrvD%InitScOutputsTurbine(i) = ExternInitData%InitScOutputsTurbine(i) + end do + + END IF ELSE InitInData_SrvD%NumSC2Ctrl = 0 InitInData_SrvD%NumCtrl2SC = 0 diff --git a/modules-local/servodyn/src/ServoDyn.f90 b/modules-local/servodyn/src/ServoDyn.f90 index b8496e9de2..409c8fba7f 100644 --- a/modules-local/servodyn/src/ServoDyn.f90 +++ b/modules-local/servodyn/src/ServoDyn.f90 @@ -325,14 +325,14 @@ SUBROUTINE SrvD_Init( InitInp, u, p, x, xd, z, OtherState, y, m, Interval, InitO CALL AllocAry( u%SuperController, InitInp%NumSC2Ctrl, 'u%SuperController', ErrStat2, ErrMsg2 ) CALL CheckError( ErrStat2, ErrMsg2 ) IF (ErrStat >= AbortErrLev) RETURN - u%SuperController = 0.0_SiKi + u%SuperController = InitInp%InitScOutputsTurbine p%ScInAlpha = exp( -TwoPi*p%DT*InputFileData%ScInCutoff ) if (InputFileData%ScInCutOff < EPSILON( InputFileData%ScInCutOff )) CALL CheckError( ErrID_Fatal, 'ScInCutoff must be greater than 0.') CALL AllocAry( xd%ScInFilter, InitInp%NumSC2Ctrl, 'xd%ScInFilter', ErrStat2, ErrMsg2 ) CALL CheckError( ErrStat2, ErrMsg2 ) IF (ErrStat >= AbortErrLev) RETURN - xd%ScInFilter = 0.0_ReKi + xd%ScInFilter = InitInp%InitScOutputsTurbine END IF diff --git a/modules-local/servodyn/src/ServoDyn_Registry.txt b/modules-local/servodyn/src/ServoDyn_Registry.txt index e602695a86..a1068320ac 100644 --- a/modules-local/servodyn/src/ServoDyn_Registry.txt +++ b/modules-local/servodyn/src/ServoDyn_Registry.txt @@ -29,6 +29,8 @@ typedef ^ InitInputType ReKi AvgWindSpeed - - - "average wind speed for the simu typedef ^ InitInputType ReKi AirDens - - - "air density" kg/m^3 typedef ^ InitInputType IntKi NumSC2Ctrl - - - "number of controller inputs [from supercontroller]" - typedef ^ InitInputType IntKi NumCtrl2SC - - - "number of controller outputs [to supercontroller]" - +typedef ^ InitInputType ReKi InitScOutputsTurbine {:} - - "Initial inputs to the controller [from the supercontroller]" - + # Define outputs from the initialization routine here: typedef ^ InitOutputType CHARACTER(ChanLen) WriteOutputHdr {:} - - "Names of the output-to-file channels" - From e555f6725ba4e13b8033c30370aeb9360448b00a Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Mon, 19 Jun 2017 10:27:25 -0600 Subject: [PATCH 033/386] Added IfW_4Dext.txt and related Custom Build steps --- vs-build/FAST-farm/FAST-Farm.sln | 27 ++------------------------- vs-build/FASTlib/FASTlib.vfproj | 17 +++++++++++++++++ 2 files changed, 19 insertions(+), 25 deletions(-) diff --git a/vs-build/FAST-farm/FAST-Farm.sln b/vs-build/FAST-farm/FAST-Farm.sln index cf226a22c4..cb1ec30714 100644 --- a/vs-build/FAST-farm/FAST-Farm.sln +++ b/vs-build/FAST-farm/FAST-Farm.sln @@ -1,17 +1,15 @@  Microsoft Visual Studio Solution File, Format Version 12.00 -# Visual Studio 14 -VisualStudioVersion = 14.0.25420.1 +# Visual Studio 2013 +VisualStudioVersion = 12.0.40629.0 MinimumVisualStudioVersion = 10.0.40219.1 Project("{6989167D-11E4-40FE-8C1A-2192A86A7E90}") = "FASTlib", "..\FASTlib\FASTlib.vfproj", "{1A440C5B-CBA6-47D9-9CC2-C1CBA8C00BF9}" ProjectSection(ProjectDependencies) = postProject {BF86702A-CB17-4050-8AE9-078CDC5910D3} = {BF86702A-CB17-4050-8AE9-078CDC5910D3} - {A3802474-D03F-422B-B8FF-F5636DC25BF2} = {A3802474-D03F-422B-B8FF-F5636DC25BF2} EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "MAP_dll", "..\MAPlib\MAP_dll.vcxproj", "{BF86702A-CB17-4050-8AE9-078CDC5910D3}" ProjectSection(ProjectDependencies) = postProject - {A3802474-D03F-422B-B8FF-F5636DC25BF2} = {A3802474-D03F-422B-B8FF-F5636DC25BF2} {DA16A3A6-3297-4628-9E46-C6FA0E3C4D16} = {DA16A3A6-3297-4628-9E46-C6FA0E3C4D16} EndProjectSection EndProject @@ -23,11 +21,6 @@ Project("{6989167D-11E4-40FE-8C1A-2192A86A7E90}") = "FAST-Farm", "FAST-Farm.vfpr {1A440C5B-CBA6-47D9-9CC2-C1CBA8C00BF9} = {1A440C5B-CBA6-47D9-9CC2-C1CBA8C00BF9} EndProjectSection EndProject -Project("{6989167D-11E4-40FE-8C1A-2192A86A7E90}") = "FAST-Types", "..\FAST-Types\FAST-Types.vfproj", "{A3802474-D03F-422B-B8FF-F5636DC25BF2}" - ProjectSection(ProjectDependencies) = postProject - {DA16A3A6-3297-4628-9E46-C6FA0E3C4D16} = {DA16A3A6-3297-4628-9E46-C6FA0E3C4D16} - EndProjectSection -EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug_Matlab|Win32 = Debug_Matlab|Win32 @@ -104,22 +97,6 @@ Global {F47C7C94-2A7F-4CBE-B834-1BC7DD3FE692}.Release|Win32.Build.0 = Release|Win32 {F47C7C94-2A7F-4CBE-B834-1BC7DD3FE692}.Release|x64.ActiveCfg = Release|x64 {F47C7C94-2A7F-4CBE-B834-1BC7DD3FE692}.Release|x64.Build.0 = Release|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug_Matlab|Win32.ActiveCfg = Debug_Matlab|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug_Matlab|Win32.Build.0 = Debug_Matlab|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug_Matlab|x64.ActiveCfg = Debug_Matlab|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug_Matlab|x64.Build.0 = Debug_Matlab|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug|Win32.ActiveCfg = Debug|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug|Win32.Build.0 = Debug|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug|x64.ActiveCfg = Debug|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Debug|x64.Build.0 = Debug|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release_Matlab|Win32.ActiveCfg = Release_Matlab|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release_Matlab|Win32.Build.0 = Release_Matlab|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release_Matlab|x64.ActiveCfg = Release_Matlab|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release_Matlab|x64.Build.0 = Release_Matlab|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release|Win32.ActiveCfg = Release|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release|Win32.Build.0 = Release|Win32 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release|x64.ActiveCfg = Release|x64 - {A3802474-D03F-422B-B8FF-F5636DC25BF2}.Release|x64.Build.0 = Release|x64 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE diff --git a/vs-build/FASTlib/FASTlib.vfproj b/vs-build/FASTlib/FASTlib.vfproj index 521f16457f..dcfae6d38a 100644 --- a/vs-build/FASTlib/FASTlib.vfproj +++ b/vs-build/FASTlib/FASTlib.vfproj @@ -550,6 +550,23 @@ + + + + + + + + + + + + + + + + + From 5b02df119ff75d4c13f221da761875ad85aae2ee Mon Sep 17 00:00:00 2001 From: Greg Hayman Date: Mon, 19 Jun 2017 10:27:54 -0600 Subject: [PATCH 034/386] Added OutListParameters.xlsx for FAST.Farm --- .../fast-farm/src/OutListParameters.xlsx | Bin 0 -> 334668 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 glue-codes/fast-farm/src/OutListParameters.xlsx diff --git a/glue-codes/fast-farm/src/OutListParameters.xlsx b/glue-codes/fast-farm/src/OutListParameters.xlsx new file mode 100644 index 0000000000000000000000000000000000000000..ac3b980b7624a99909909acc856d6ca9948cb335 GIT binary patch literal 334668 zcmeEv2|Sc*`@fD;I;FHzmZ?S zz%l_-a_A|ODFOo5e-{v#FEIT#LoKMSgSo8(h!#<3Oq;MmbUEjhlp#( zmn6iI=+~?)6%7)V47dGReSD2a*4C3>)}nkvf~w4DH%Q*Xf2l-2ci!hU>+fJ66lzDj zu0ZY>7m;7Nk^G4CUb z6YDjq!Y}TRFn2MzPKN!}{ku>*ciNpWuFlSlGQt5$i`vp7iC$snY!Cg;-WwoOT_vEI z;BR-9wCAD7yZH+$S!-K#9_8c<&fK;_&~sU%)vHU=dL)JiCRs9>QTn%gs(G?rHVFU~ zmn$f+k8fut9F~{v0-o#vHr`BNXF|@ITieTR;C)Z-$ba!R9I$ks8wGoT9hptpnW|O8 zY_i=s{r=;WJv&pD9g=#pf(%OVeYj#PopxF9;x02nA+5eZ)3AbEclr=W!c=Z=M)K-y zahputac5kj!;gskZMxj@^aAV>KM50kVudxt<J~zyE{DsluC!pO}~5s#W*ENbQqVD|vfnx{$ljGmRcK#*0KnU8sv(9o#f%ug})7 z`QRL(WB%z2dp=naj-t!&ZGZ((B~D+G4kS_qC5ZzfjdkUiMp? zn=fn#KlQXbEnlrF@^Yo_$!?RkSt5rZL++9b8n=QvfhWnpE?FWleTs{F-;(a(d?~e1-Fjio5k8LUS@d8>;{A zKV#JjdfL%35o4%8EX|wxXo!uozbk{E1dT9Hb z2QRJW>n(}$lPsHknj2>Kpba1QqP}vIJqj0MAB~qeCgYpG^iJlReWE*d!gIgC=`QgC zb!xba>mDjxnyHGf!Ra^Wn*W&%n}sjmW{YIpdc3}^Vu6kCXOTJHUhc<8hhNxTN9}%kR&%v!>S<#a zUH9;X@>!wCIYkfOeF@xNTp51ZCM4y^+GiUg+ZQ}w8PPMkYA=w@`d7CP=e_KTh=@LR5CXn>c}4Kf^MdCe7qNO&F8q1GCkde!)>(~+Tx4@Z zH?jyMR16WhIQN=9m*!8W?ByWr?A=}AT_HM_+;cq*HC0V{U4)z{5Q5r(L^3roZtV>< zG%~BHm66gMwe*C%q%u`8=) zNRuF>R833<*PWVCO%PEQt%pL9sYyxhTyp!(;$lmGQaHp|UDef|-QGl2_7Bt0bnoaW ze2DOO}QzLYnIcf>cW(xX<@XJ;E$V6yWD2yAk}MXGoo4`oW|=xBB&Qg z2Gk=J#(SVC-qBHcm?p=Cz02{`FT=3Bm&t*Q&AAwW4uXDsbR!)!Jf5BhH|Mz2roNBxlq&c(%q3_ ziCsl&vTf2F_=@fxgsD3;UrFS?kPBRsUQPsRFBfh&XuUVBZ5Q*f55cW*LG>$R)vToG zpuGyV&5sX$EwcBD1cq~gZh(F^@9lB6A-kV2N|5b*@n&RSKhCB6WQG7jN$+3aqr-Z9U{k z-%7tv`r8bbrAjs<#8H4{<6l1(tfQp>!tRd|}Q{q}V6exfOZe1kX7R zsEv)mb5SWS_3!NxZx|s{tw?WPAlb2$9%IeaTuxU;M6)})Z6gyW0*;|{W#qI#G_4cS zI1#ycpc3wDr5#@@r9A&y$)~r{J+Ngod!==yUdXQQM25LvtcqW-8C9;H5K?hgx!hLL zV(OQNS^miWvhTS}i4cl;g#G2b-d|6EvRU>(83y;*{<1FbS5%IJ zU#uO_mwoo;dY6q(A|BDNTKvuZp_IfBAVT#y-GWcfWu|581R=s%;+4-{#L%nhUJI zLNZAx#6DFbMM%)u06TcT{1Uya?D$Rg4Eo!)1IScntEMgYB9c^rIFkiIyVfenOx45(QMK9qb{$j zYnDb$9gAF5Lkl9Lc+&}G=$D*;L~lrvkEE3Uj9W#)-+Lh#_qjw4xqsr%5La*aK>-aH94l8wKILL%Xt?D$;od= zuipU~?x7BvLp{c3)_67(a+nx!3Xn$y8xHt)IexP7 z{KHZFeB-I|+4Gku3l#59mRxnqRv_Y`Gk8w}QDBcwms9Y*v?;-Uv{w21a6x&=spTfy zrwE`KhVzz^U*;w#4=)s4^(RyyLe4E|+N?q=qf4cKj<0#|*baYE=t1=q z@j_-bTQdlq^<^sOtpioRtQ!@YqW?#NDQX^)N+ciNZh?==B(d7o-WO>(Tm?nA+>VVa z>nkzQd7*y|!>Bx*ex$c{M$~2XH^wVDb)NcvK#gf@E0wujta`4UeX$FUJw@~0RLvu` zQILG3#_OclZ#D5$P)}PH!5f4wM~l-@QWYnJjMZ5j_RK4E`~}e&7$kRlrH#{q|5y_CS7hpg|(3J>b`1(uhnFozgENbR>QFUNoa0N`>HI|24}x=?)n@4ls4(> z8`@B*&Z7F=h%a(7OoA>V+kcj-3KrVq(EOf|LkORp7TTV1B@lcl-LU7vyo&o7t1EAV zEQF!8CYwC;5y1+n^`3cR#tf6}SQU@{AKqVo5WoJA`&#Eh?+<@xWV*NV=e8^+HqnGm zMmpn9GB3o6(gZ7IQ$W)x&)HjD1Y3mC!;2A1VJdXN=)>Ihs^exQ-Ew51V>44hr)1j@ zekhD0>6LtZ6K>2Bqw!MN>YEY+EUP*K6^y#aG8t7JbQsB<;(vqe{L z5vVYNz_{$%5T<>lcT_F5EDiiRMZ@4Ow-(+B&9{?flWUrKTBjmhO4w`Sn1%YjAoH#_ z(;<0p5i26UYqb1FOdcww=l_WT`P z38%7GqZj3gRpNy79RR};K{))f=U8vEx=~$B4ne$?7DIv{-X7j*D78x zM|W4D572!uxiSivQixUW%tp9e-Vc|(tKfyw-jv<)wU@UGi7<%bp2VnAUG#6|{f~#b z^e*aV`%Bg_MI&=rq5!aRW!!_s(y-gp^c|@1LLWe8ie_whp*%4I^r3H0xyd1B0i67G(01q+@4?+$s9e}>Wy@qvCoX=l{ty)bzTh(8aIeE(%S z^5~^?$qe+V?CBVdyKx-l9$;$j{qr8`^2bA-iWWe;d0HkK{cve(?&~kuR===`IkeFF z#q^vfCjIr`sXyr{Y_U;c9w7HVb+R9rBzq<{3?a0iifI_36>Ko)8+DaWlU3oWYF9?W zsVyIa5?6nfG=CRg#UBk$dJsYZ*520qaB;I`P`ZN%*t}2IeKH$KO8lbZlUaSkK<(db ze*j47-lH6MLB9F^MEbFp_<$w>4pt)&B`*$?*V{^DW z0Ij_$@Mv^e7>!;u%SV&jNkEo!pI4Kx1u0NgZee%B1kvu|k$I|4s6gD7*fUhB-o75t@=xvy(~ zW*0naw!#AB0y{Y9f|hXP+tpP)%;eb$iuOQBC{Y)7AdvhJd9p!+xOCBD!m^)#QbM{N z4U+viQ*xLNmyX`D_5AsVY+F_Q!U4ptZlE_#i(5^cJlSl4Q+aMXzIf@P;fsdKyBXsloxDGDu76F-)n&woSEZ%im(A5m z)|soLb|YTe!@+;KpUVnM9pOePZHe}s`F>(W>Rwx_0`5sFJaS)Pmnp5X^p({6#oB5q zB3x_;C9qzuy>f}V-a+zJ?MA0zKIBzEvpYA*Xv2a4a;db+!>i3v!)wvBIpE&@<3I~A(1zzQRMI#!Mm-nJS2*1B&T#qG}@})*yNS8cX+MFb?wZ5vLU9J=-jMQL*z zN+uf?82Z=vERQK}o#S2fvky^+WylP;hhfiG=c$khC=-wY^TNUj>Re(@-{7cZrmZ?@ z?$0N{n;22o8W6Y)5uO+(P2|mgE>3?`azQu!&!}qvxJMufo?x2*;1CnTMuY52-Ql=I zCywJD=-S7*|w;LekzA7#!74tu74G z`+U}${(GxxgP+px@QbAgi~3@m(o5biSp7|e^oBWmvF5x1qI%GFvjS znX=cj)NIfEm(4#JVqi0W9bPks2AAb0c%$6{MjK*M-&*kIeczDa_M6pqC@xY9t0k0D ze7{S+^mm{SzGd*W=$$?BbE%f`e76)0N!2hbeCX`x`m|N2aNigHV+)>a8cJVKkC#s=a@TQ@a_^Rv4=gSp<)X9;Xj_F0~0ty&O@R3;sM(Rv< zV_6i|83j>Cr@`1~7?>2CFQ}Ye(56_vS3Jx)m?s{%UPkN7N{8UTCEIzWdp-a7Ja^1R z5-+18D**u@og3U$%_94?Km3vu%R7tjQyPWu&HmbUWSJMA1!T@i(IOQu-XeKSFJm;4 z03bL^`F>(E-(aKBlt-VYfMXc|g22e5f*>%bUI@CY3Px%*pHBMYbJsAc?cFHJ2|NLG zI>A*t)k7};2vjT|9Rho$p&^+Zo_`8h;wXR=zDSdt)TL-tZE3;Tq&6$D*rQ&O2U|d% zXTdgGfZsa3rNt%}oifKThOY7Z`mR|s77?nZ+X6ThhKQoMKKip>*XQg0XhI=rn zdg0mW#Z$w5uXMnb7O7Ipj^ayz8}-hzqb^v4(xM6waHr|ZKH6;HUyxmtP>tD*^NVw6 z6&rl1NWSTcp_Rfj!hIiGVUa;Gl4gyc6#@rd4C#%nI9&2Nay-yMH>D`SZ2fUC(C7Dy zd-H}{?4DzE7)%Lh$vvLzwtqmhLyYoIkJWvHq2h+YPIA)&a#RN>%( zUMM@@!wl34#h^<`2^!+STDcnrO%uQTVFXzbkmPQPJRf%WXZv5iQ~1CW@hxQj$~#xp?i(iO%)<&<%U{;+&T$qA!M9T!n12@#qQ_wD#z(|2r?1;gHdH zbPaQ7^ptcUol#s?apdMqO6&xxp>l}JHN;R59sc3ShrHc?)dZ;_Q|!N*TeDSPQZE>Y~MM^m_{64d{9hP0-?MJRNwZB~ff~G@RG^ z_}6N9VKXO*kb!+|2%UmVk&3Ub0(Vpry?Xo9GJ+HUgJmiJYdvfZyA8qY8r-UP29Gy= z0UQx0BN#?4HAw#Z5bf*m@zr=?yFDQ$Y7c zmp6y&;|9!fncwM6&oTD%AhkHn#sQ1wwdJ}2Z6VE`nnJlhhypL%e*ELN38Z}hCV&p= zmsL>ydF1BBz-slYDx)s*NpOH@GU*221b~^Hsn6&ls#;)y<&v7RTap@JM+JEzAJBk* zc~#)omVkPyf|W9QNYzzQtWG9{+vyM0E8u)&>9mnJ)g3J2`+}T9!21o(?79we(9J|q z5~K=QUcn9N&QsxB10I)j5tzuCz&jfRWb~Vj?RVh9$|9w zxv&6K-*xV&E~wJuN3o98WxzUYOO}jt9gkaqb%20%z@g(@2VF=C=PN1==;PYiaq7b& z2hhj4KhejWPtG=LVEmSmE6O<2cQqNspikVfct#Q0{to|)7y_G>^=OH>7cC5>h&gIAkQj9<16TkBn} z9#ub6coXFE{c&8J3+^(OI~O$d3U-{c05%yhek}Or?TGJN;4J<59l3M#=e;l=9lUuP zVnEGub*s96xERi%!@iIWrrPsSu32D7)=&4>3%{eXsfO- zE_iNSzb-f40suKcle2lfXRAVlcqlguMG5luKwLg<3J>N->zf65o8URs@jP#flmh#r zT)p`?JoHA2B@XGT_GWqp06F#KxtHdOzIH#- zOYEZ~be;(qP?H?CnW{|=E9vF+(eXLY0(`G|CB-ri7La1uHHL-ri|Btq4A-d%FpGpB zIoh3)etHB-#td3FblaU0fIC{rliV>$p$!bco=r#$=g@%#&uJZ58u7>YZTFbKnTx|c z4tE5l$8xVTBmpX9Hni|KGri3&+(4JSvX@CYX8P)Ov%~=AO6e)mY~~06#{Ts+ z{Q^<+l5MU=1F4ChsD`}jXRqVjT7}D%@y)ZoTEUAQNdwK{*J3^!$zS+CU@_g${{xN# z;B0Ede+E#NduCYob9e}=L%MU%0Jc@be$uv1x)^|OHbGBI1(IWV#GPRpZXi3F*ytzV ztZP2qXi4;xe9e7XGJr|HdY>lUNh0u-iHa!d!a4)){n0V1w*s)~ox2_*OW9KZzwF$6 zRG1uWb3f6gi#Cs%2m1*yg_C234+xj+92C=CmMgUzZICzVmG(;Nmx}>_;eXI8omDaE zl}^YV`=7AS|2y4AnQh1XVLk^2FE39`I5@J-f(#@je1N zJg1790T~BM({Ao_rXY|$s##?W_z`FLb6b}+|kZ^fkI+<{p z%sUl`PB8uUpRw?!=&;*}Qn-rOE;_^#^ap~@_Vx)zg!F~%?h&8;TJ8b7uycGP49@TIW4C5w_W1aqenj~ zDTSrsj_i+6!e(Au;ngFv^X;tA5XK?nqp3x((2x>exnzTAhU#Kpxep&+RV3`0S?CF}2xXP?w|aqclE1?r4GAkkcBmk5^&7u(xid!!2!?KDw-H zW|qc}LOetD5p5|Ai4E%-wTSupuu&IhT$pL*!00f~y53Y9bgAR5StrVqs%T2r7sN)^b=H50TY%%`16mRffp%ketMDd+(CU zDl62--yy-&5&7)DPQwa|dBp&Vv-3pFtstF3QIJ-*2NyZI4;oVW?lmn03wN&uw9ad1r<)okK#4-{QWj}^dRYy}tF_SClwT60Lr z$oE%aZ?EF036Vn>W&Ryg-M+17AocZ0GmYy4Q|p4tL;CDEf0LnTu)TXJJbQo}Fll~A z?i>|N_bZ~M zNp1g|+`J4Nl-rSlVQ`^DF0}x|YODwTnFNw1mw?g){-!*VlY`+jYI5r%AqaMLI1R+9 zj@0DTCWa%J9i(nLhSkxm=KyBXnk#D{C^QFx%|KCbc7n8`c7YbAWBJ822esds2uWoV zIZ2UpGz4pd-;K?P1*%8`Rkre~cmY)w@T!;rRkDF9tzwSWJD4tvjM?}?H*D#C$xE{- zc-3cSA1fsdbsU9NQ_Y&6_-*raww5eWXlV0`eyBQ4vLep$5ccm3@GHM2F$WjytH@}- zw||#@y&Yp8CN_@3feC}U9Bm)6)=_5iaa}`BYs5Zm&KOEwijE#`X~XmpLTD26u}vFU zJVW&%PC9};0dF3)i23>;%t%z7w#jI$YU=Hy6|ZtpQu5(C{O7phxsnfOx8fVG`tA30 zYH|1z`$P-ur24?@(|t*>WT8USN54?N1~JD|*u6RqKB_OxBBfP#0IENp5##q(#d=($ zQ}DE;5(Rwqc!7omfF^|-C(zVw9ffI0;{;l(U6ffYcDz9I2Y{v?Gftqnmp6&E*o_lt zglYh2{^JFj6aX~$aRUtn0FC*1oIopz!?5G%4A4G!S^@WQb$f>=J;6j22Bvjya|ZCp z;m)wd8uQR<2c{JPNcJPd1@Yio?w7`caP zx-hhQDXe~Mj5i6QQ5Xb%wweHlCd3z~u=()T1~DS8bSNSl8J2B+t!O7lVW-YX${5!C z|95B`a6^8Tb@&`-4*{$0peH2s*~pQh#cx_4nIY+B6sqR=ZZ}cxZh+j#FcQFGKxo^B zR%*Ek#Y$;5AfyTv+@!v-nLE#FV_WgO+Ny(zP@xGgrHlYk=?nd2`L(*LZPaua zl{43`%|1I_fz;PH-(APV_B(`FX=)#9_BnohnjgwrwD}hrz6o*Ggis8)Z)7VSYyDwUNlF;Y$A^*fS zxDFrDDj>tTkAb9I$_WZSY!GEZ2%aOQ?s|P@Iwz&0{X%ygiNKfF`>J^<%qx)*(t?wY z-q^FI;}2K9I8b6J9`#j$?ZVW7SE{5T3`}32H(smantbupN@s$e)j`Aw%DI%^oFB8yPkp6_ubJ`>xLQ)O6dLcb(Yfh?k(_vPT#-K z@t+u&oUJEdB_?WqU9e7&l)ik(*j{7mH-G=_+HOI*rlcI+jRL1tB_8m6A3zK(@W`IC zo&2Uo{)FL~<);jnzMq9=`dpiHD(-HaNBEt@*$yx7XUFeOKz^ReRbL5CHfu?8+~eec z#oILpw>0?0RhKH16-ri1(MuIxV_U!8n_;8PUOWV6`x#NxvICi=biBa4A;C2vX+ z6`aadSN+hDoxgi?aCx=UppM7TQ4%)IaSz!pW#}1>rla!e3e{Egq@T>Nf2qTEM7D!U z-gGY?eyPKB)Pi?~FpCu2Az-kRlaZf+dv;kO%Wjg2w` zIiGCHFghEP@k!CNdyO?o_A5jwh zn1Qq1Yd!k`f&q;Tly99Ag1ShJJPb}kr%!71B;cxUJF4yWO^ST`)Vr za@l&wZk!wmLCqtfSp;WIP9qcepKTkV5Kb)JmBvzi=9G|kDIkP zzA??LsH30`sOj-~$o-z{$V*MC+@@krR)`*sp&zJGLpqwAk2!PFHRcRSqrBtX9_F@( z5IFHBs4M_x>B)NMR|5vu=s2w)l`YeJAzhx&nUJG$jrz2FdLmGU8 z(sK59@C)fg)YseVW9h;6h>laup#=U8N7qBfwZ?aTMuAR4O=+YalBP?R1!#R7W>G)y zLFk?|_*`Pyh+-L{hsug`Cw21Ik5;gJJ>1jrYk7D0fY2iGyi#(PJ0n% z*p54)H%a(7m_>b!veWwTG8KleWX>>;oSj_uxSZ6fm_u&io6so15xwPwG|p>W;D}iW zfa6%)xWJK61%PAS_`q>QqAb8FYh2*Kc>&;v#*Yge$Lvn(#4H>aIE>Z-;7BkX2RJM} zt+E0nUms~1yK)O!?kVdlJGDG5$<2QcZ8@qDZ{Hyf4g`u>*?zT~z%rOPGsZBF-sNi| zZp#Fcj2N~1i^Hi1repCrzq-<2qoPS?jKey!Sz{&s%FTG3Un;8i{#$tvt36T z;(DoZbdKJnB_6FeFn&u6xM@$5eA@H-YPQ zOME5W4{jc#f7Wk3Ur@s_9}GW0AqJS#4c+#DKNjWyAK;i_;7RJXt0NzvT2k3PC=6p% z{1#Y$%#LXriFwT8MVHtcp^_TRzW5Tuu2URU)Y(V$DCB!L=7*jVsE&vB!)v_&+%^ON{68O@En69Px z44|8cGo#IA@H=iN>oKs~iML3cQ{0Z^F9kqo>0Z<|M2rc9ky6UHc9-ZoRUp_nBz;(h z>yJU%vb7>W#!Mx!rKPQmpP9I}OL%EBJ{sanrt~Edx_g42Cu)Ai^vFpKm3o7YvYUTL zF5(xV_dgVj20fb$Mkj;Ofr;#i2cxLoU{up^Xs2yZHjNjfCf%3#&=;d}3JLhQf*-SO z>kAU9XvDq9-3(s--)|)t45Rg)0Ps^8z^6a+;4=EsvS`lA=GKBz6z3-2LBd$One+$# zKl%f_?CxP8yQ@3S>~8*S=rbTG{q)rTZBqId83J^CKeQ(?IT9u(nCH-O;t=#*cQaZc zWI5DK&OIPsCUYE8HYjoS{s81{SXA5TFC#G^sXbyWUvbV!;!sq{mjJ9+pp+Vs^gOZ1Y;Ds@YM zBeRlm9GOkB(`a%seZkN_?(kuv7V}*`lDihV2E!(Eh7Cvgjy%8f9&mo@FaF_9TkrX4 zvuH&h!5s~=%4$ss9%o+}S{%&6%#>a04L7QM@6-X`T6S zz&XVvvHeqsjhC|E_ryoSOW#{S<34zsOy!UDIPd>BT|IGP(}eT#Y#M10V^P-klhGmH z;rLEyy(ggG9l73fhG5h!5`qo9r#2RUjX(Vc2?EFsgGdBUW4T`ar%3Hxat5HjlhHxh zx*;65zU{!JIhOUFp#GaOuFg)sgvWuG)S%C7Tks*z#`x}9f4(c%!r$aOU88xM z^WVhd6FiyX=H_#|sURemfb6CNv12%iTN?>NGpixU9x@XHV>B}5G}$C52FA=&Mlw5~ zBzAWs1<4{uV&IG*5SmL3(qu9GNpNORIGWXo197@>NH$Fl*+a|0z_=MfAWmDJGw-G0 z{~q`^9AnmNgH9bKd!>NQ1JBb~xp}ehyz?{~FUe zy4phzWRGI4t~*y!KDh6pYY#oG`WdYKxwS`9$F+#B1KF^FwM|8gu;j0`hn80OQI`ew zjMpCDBs6^Wp@pj{)Ump*qj>q)bTMcoL~O*OLQ(ZmxdE1IQ8W-{| zI6Oel)K+>^on_6k$?fu%>QKqXOilmkRJG(R!DHr}@o6rNcDff0Prk!2YO`>u@9R zH~7yDp3O3fUZ)UAa9Tp0Z(zDNV9b|!R87vG%3DFlkZDtTR(7!Z+RNP!iC$8dr$ za=3f92-W(eN(v`PDmLJSDLDVXcZo*i?eJtp`N5ONaKLdEM ztjG-gZh`&P&S1HXSv-Q|e`J2pO9fz1&3Lt?tUCC)etS_Yco%qJ3tp7q?tz!iFpfC+|rE#_y+10)7bRwO1$;#@w!4E^9tf04_%D zD*DLt_*CCGn{npxe9EtUIQtI|>s~$#PszL&R^!Xq%|mxZFotLCf4EiAwk$Prq0%XD^51hZhhh#A`TuwkFO{uKrqQk^nmB2=|O zG&>9f^F1ZA5_5xnr-@_k8bg!I3y2{kRFDT6ptj;E=plk$Ah1>Q{M{-=oT`(>1_Lyy*OARy z`6Bb)a%e7O`R?2`-*4BP%Zcd7D<=uSuL1ra<2Dwi$M5rjFtbMV5Bn&nk+UhMx|x}0 z_;E-d62?-3&HJfS*@u=sN?kP?FLWq)1?sM;i?!|;+HD=G0pCRbt%H9G4ktLRtaBjj zHAC>g0l;)@7a&|9I02G>MV*v9zj2+!++Ysu4=pE*xdWygIbLjxRjzJ+d|xgA!0&m= z&qxlk90WpkNX*;w8#EWRkS-cIl#4iwPso=ZWOUzV|2)v`OSck{7Ot>OXxFz#`JF;O z54omVpLX-dd~d%4`HxL|Oh(695+2r*(eY$-Jj~u7@aR7g9e2qjPwDA?%yc{5z>9k& zzod+KA_9Z4-rMhtH3U+JhssIhdG>BMc(L@#x&^LgdjkxWZbR!h(}3Q*RB};j!yl3O zQ%Z&ib-#zl{*YuShhjWn%|F>4jBaE25H8}RTQ}AK>p$R4`!ZhJ=$r0MY*nn2;YALc z$9hq(OR)(uoh_~~>CF$9O&`id{I>#r!kAlG$EEQSg)DbOnqns};+@?_{7DY*hYVp& zb+ulY)QO7W#c6>+dUlWFWzF|LCGP*mE z0|{|5*EiO!)F0vZX<&R=&dqi8uZ~|+A-*aO4(GjX0K_h1yL1LqULEhVqhkyY`+0v- z?Y}_n>UF=VY^tza%w&q1)W{R!H5Ne}O+M5x<#aPn_ZF7Suj-l+M8@p+B4XuFZ} zgu@&ggSPX$x>OPndy`I}zmZ|;pM8`!DB(C_N1eg{)=b?mUHODlHeb_(lL^|vZ&VEB z15T!H8bM>5NHio2A0$DmUpxKZan2>hRn$%gyH7wf<W(heq2sgMIyvR+#bYiy58bL~7fov>1lHUk`Y z|D$(W`d;hRou;VR`QkIu@atMKJ+=?~NNHCnUVdN4=o|121HJm`+N^aeh8=;g0sp*8 zcL0NL9{1n}fWh6Dk9TkUzUx zY>IojZ>$#pC04ef__H7K#tfH!W%}yLC|Sc&M}e=Qv`^@EFwMxuP7cn$8-@}U{|5eb zVh1p`H^khu`1mGS+M3+Vi0xy(tf7IBfna};8<+}L)`9NsZZqe+6IUF(**lYFZi;I> zQYTB>ZL&&fVTCDXfraV8$`Njr7TQ+dOf%z7QPQA;X}c?{tNpLdx?klFw`Z)x*Uyvy|D{*}Y9EW895DW* z+W&okpD^b3d9fqIYxAoGQ&IX0cnnuun_$=yl#a!MQmm$dpBlF4q_c$qB3wK+0%U^y z<*oo&-riwKS*(FL-^YRrolLdvi@F03_BCV~o5(0FaEsH&_Yx%Eql)av`QiYBLbRp6 zz^RC&e&?~RT@bcsY;NQvlZ}JPCdeeRwAWUF*L0opUg9I==ZDNl80#espJG)C_|WQ; z25ii6)4vq(6UN+QJd$HTR@2zRaJy8;^Z1S%r(_`jpOS+llVcLe9lJ8R_1jI>T?lRj z&)fd&iDJ|HLw6I=_wHowi@N4qv*qvn$Z+OgULQV0;Lyj}r~s=uweW?ymu&n`A{8}ce|Ko`0B|y%}|fKA1eyJ z5;n?)d^3q0d&Bs$fI2xhxH|!HlzOTQGQh9ghu+ko? zVZV~ z%3b`SquyyVHpe}UUF5#-jOjrWS=w42w2rkLesWD0K!$6~9T_E~jILj^1ot@m>gsE= zlr;uJbfmQdi0>2G>-P3c5ApDC*dBGm{w*D%Qd)5nnpNH#6;I^OwhCg`jOR2RNJWw7f2~=Yae9Tw- zP_Q_t)xL$J;x7uop>oDkQ7}bo5XXtWHRGyjzj@tSbx{mG$Yzz($o#*2MlRk`P_$znYw>E zf@NuLF?UuespFmxX@-Y`-dFp*fGMh1tKx47nn6;(RCgRO^y;oQ0|=6j0l)F(5?dZ$ zY90XG1o)OL^gf=^KiD#p=NN3sibyZ-J{4|8FK|uW2Ut`6oq#(4>T?nKNi01c65%<7 zBiUc8&kNgxS$mFlzb&mm;=pj;j3s7|NT16(RINVObkZRlmqR$wU6O!rer<6V-)R)z z?;ef@m;8V>Zc)SK&KKYCdYnG(M3<0;pL7WS-673mJO;M5z*UWTg*L21IW%7yLwor$ zaPvUEv|gL*>rYd0;@-o~1R~tCS3Y@%(uWJP!{AFLSN#};_d}C$I3ON!ibTlakIMNe zx8HbHmI)ON<*5Fn1J{50CjSpub5U@?W@@Gf_~~TeI^0GY${G1@NWJ`O1RrbZGTNkT z?G|IepU)YC!Cpf{g?+G>D&TBJ(1q_h10G>#O~T-e<4^OE{n<-zAV+DC{%ObjkP6R( zW2VV|?G|W!;`0ax&?M5AL~t7gP4;7`twoD1KQIwFNt3@YIrg8U$#st=X>yV#c}EvR zI!Qkj&3}X@BYVSc$|FkHHfjuzjtomx8XQOuimQLPb)nT|gxxquQVUxNE65mS(9M@V z`Ffn=;!y~=gOw}^=K4x^)9)F|4gDFI3eQoWz=WAN^d0j|lH~scNlqSu{4_V;$;&jFqg};BS34Y#Lf3C4WWF7m8QI9w9XiX5OBen?g{xL@NdFR2` zoy8fuNFTUZdMLa4;BCly^`nTm&J&ERqD!@+yF~(jDB$W*a=4L^YcWUNVp*n*Z#%pn z3+2cKO06GUu!ak@g(yQ>T@lQl$~<ili2`1F(4NPD)IEb45B$LinySfGrdy3F{ocu>Rr`CM#c zr32S)IyVQ4BbAp!kfCxpK0(!~2*;b4TezxnOm2>~)L#8&EW%+kB!t>i$;pd{?U&K4 zsy&_dsqSG^>QxzJplD~!tmXt|*Rp(qew$Gm+%7*vpJ8YlLtPsRTiHM(r-;&6tpy!L zVRY`y^!cr7?sw{W-*LU)?|Z*1d%qdI-*X#yPuBq7te5RnPF+@4Mys+i1wET90{n#r z(b|IRnB@GN&3|No5NxAaMcwb?_ zm!*5XkZ~)wxt>&>%2t1?qhA0;yR{R!ker%YT@Jktkyg$Hg-&_yenB&w4CT@t=+{Xn zo_A5(Nyxk9Q_4vg=3*p^==ip08MI(pSU5V3Nq~Y&anEBYVZ`Us7acFRk)4+z!E26k zug1q;jKU$|08BgBX+1UdA<8CDy;ZO7LXB^=Dw9%m2vD?Z-YXJ}y2uv8s9Q-yQ1ig4 z?79$r-aqnBXA-#g;!8LoOgQimL4u-RljtE(G99QeR1v#1XQ@&JrMD%}5gSc{*<&cm zr1GJPpb(9u_L2MS9T~}d!StmwN9?n2&h`nTue*sd`npj67o(rBP1a~6q3MPOxkOYR zA(86d7bsImAU1nu7;6}*eU&WG?t8sn{pyhD$P+_p zcu+ka4%mfsHV8jjMRvluLa&Ae(f1+#zfBpAVRBqSiNm3@SI!UXnZ?+Gy>gIHvMpIE zW-sJ;G;~&C2|dxZ13)*YfdXj*cGQS+;&6B}(nD}Z*b!fK3-rw7h*!}#m9W=a-1=*F~^{c!e$VLn+=dJ!U@T2s-!v4IU(pR zMEFfgI8_kJprjByaTIPFsRC}#uA(tYM3HE8N{XvpR~EZ9BahwM#ndE|jPIdS5q4eS zP~*pIxjvrEVsB9f29xIARaeOdu^><~CN(XE(ap$<3Q4JNPGLA8Nt!*LEOK6kCS8wF ziD?(9Cs{ObI?pC!+yXy^Fh&2us1iwadNDX=ds9?uVhzt!qX!>sE&2;C{<-@6 zl#FDPpeZS>^49A<{+8kpzRJ)uTCis!ZRf5RVmZ5uriqu9c>cK@3FDHgr5(FIU%Gl< zYx#;=J3`d)7`LmL8ld7Wr`(-A*t^B0Zp^@%<+|+oTybwF<#Q>May%=dbspiiN(rvMcO_e>80-O8}Dmu z)6y*>e7H&%OU>TZG$s7ng;l!u7ES|)l`3w}HxK&5;i>^aP{RzNxI*NXr&!>ORiBMZ zSg9XMOJ-E;5miVqwJ|wPVih?yUTk;BYg_PkwdJv9oT0wcxt?inK5dM_H9NW|+zXp> zf+VCHy+LVd&n-!d>QZf6jWRQ5w`HUSa`v z&wDF=Jxe*Ttt;Otk>Joa?PPo2N*H%nl!0^mv;`ZN=mmZJe4mZjrS7?B3qke@Q~>ty zZo25|s~&2}ir#=m(JCh9?6tE0Xv$V;%$aaNHh5D@TQr& zur%WJEvDp666++c2d{oq-+k-)yjJr5CcLA6&&Ayu`x~URCHL&s-S|ja=K3OUr_;Y9 z?gTXo$2eKXJBvDQSy$}lDUrN$=k(lNmqGLDg4iFt{2J-) zJzaT)!_#&pAABmkgnPWqVnNfZ+O`<$#55ax=7$@W^grW_uP{Xd8zj}d>3^Ke>R8kj zvmF!lvBD5?U%$2^3sM4)ir>)dFIUmB5 z#Cs%6*Lh~1@%L|SOP0#_6IWR*efUKF%f$~Jb-z5%Ek!;0b6X^VnY|A9s1Ey)K52gJQf>DphnsQQYxLx6C5@FR^P zH#z1Li+i`SKHOM-OhjC`r^UsqWJdY1yDj2p!QMB$TAJ43%`4pJ%bCwjZJW0be8+G7 zhE+1&h5HFsn@g8Sb=VcrR-HZMfn7ZXwVSxdbkQ65P1NOC%!4<}PBPL%qW35$|8eFl z)1(#sDE6Sxyk#Y`1Mkn8wduBpfcIvZb=+fuxo-Ps+&c6y{;xRnl(%iDzos}j9N)ca zepS?i_?gn5ooJh7AHyQ9ie0XjRy5sYcm6F~_0YC(h1+MVP1asSTxeFYvDs9+s9v$r zE68-3C01eg_IrVbp$`mJ878gS`C7OxdZ|>yk+muN$*gC=w=hc&dzr8_4{B3n&Q6Wf zD3xlfbUJ$C(Wb|(cK5f>KD_#mrzFvjTY^7NDf~@8ResjCsm`D3FiSmqFnKDwGahZe zx1waqtm}Wrf}ZZ1^FqY@{hy>YnP(a+%>R0E>-x1P7n3%|nfkw5W}~to;jr% zgtew=YjYcJgQlnPcmUy~@2R}_sI(ugHL4;M@X?Aa_W;L~Ts>>XUK&Fy*S zE7QmdTD5Z#8(qW^$|*wZ5itAB@BDtPDq^6Un@-bnC(IJFtICL_gwE>*t;lfu9RFuC zP}>y_Js_XZ3Uw#HPPA3G-o!B%)yXbcnv@%bIh11E>t8|--_0_< zkYP=HuWax|*8a=_9myyHydl##ICy2cSxeOUOk>(BVmaelJ{w`_6k(?6Ta>$c>8#+mP1i()YGvw-7i@TOUE@_p zmAspro}t6Vrv~s1vn$0zTjm7Z$Zu^~e^s}&`0A;h8eNS(4F`pT)KpzR%TO>vup8F1 z@(DdYh#RtXS*J0_;uFF}-IpM;kIY~9cJC|WJ$rE4*k;F+6;Wcb>lWMB9ml8KiSvA$ zr`DVTcg8=nJg|X`^%bTOl^&~^ePnNhCEvN%Dh{qYe%J$ABKRaDAjQazm$nl;u z?XYr}tyXJHty#GW8?WsD{r4~RhAWZBMy5e5SEvHS**P?zKYELXm@Wv#YAz5iWA0?u%|}*cA?1& zVW+p}Of_DvD%Q9(MQjT@fO_J>PMnm&L1pugLKiAe$S>)X$jR1Jx&;Z}Mz}kB4{`rO zu~S~p-fTU1s7yG%czZ3%?ZYM7lNrK_+J{g4z2;d);JUVb?uVvMyZd0R{Kx;t-J8c# zxxM}4C@C@|LuD*vNU2U`9vavrWTrv`4Kjwzwo;igD;3f~lp(cM%9ttBK@yV8WX?RZ z_iwHH-g~2?^9;Yw^E{u|_b=S*UTa%DC-1iyOWILpv((f337W z^gPQz{eDkEr;q`wLH5P=xqEoFzI6n#&#@m`rtPyg<~TfZ+GKpapKY>r^KM%Q3U;cU z7e}|vS?}Fx`S`w@>gERACl=*fpSCt0&60jiQ-AdR+pA^voT7!6*~3N`=Fid|Rr)-Y z-Ffql%7yq-3*$La42pl!#+;{PGiSR}ysp$&N`U3`>vq1@2AxUG%YXie`=n5V`SW&C zP_LA?lzwX0{^pK?FC`RNKc6+3(G~fRckg|ou%PfU$}&Bzr*S6@i)@pUZtW?VFA+Jp z`_g+O)Z!VPToQ_NV=isu92q-7r_0lwE!k_EUU9g4mLiPNMU_WhF-~N1i{t{YpU27F zgzBWNaxb0#;2PFb!UZ(HoAGn!*!akP^p%G%*XMpSNu6+-Hm8)3+f&{gTU#z}&cU{R z^yjr}RJ?F8Ao^*vfyaRh7dYkd%(n;l8NN=1f&U8T{!_&^_QBXgO$X#YCSq@Cq)}z>%{*dJ0sWr zbl1IBjWW?Mr}?EKw$cc$cPsCD#hjd6wEi4Mqm#L)HF4WgDXOOzS&jjw#cMC}s+K2C~r};dOcRvGsB3;o9}07rhd;8^rSl z)&R<<$u=Qp~#SF&R@MwRo|CIs5dG2Jiq-t z66e9l61naAT5;N%@OdDnageVP)wcP72W9?uBp zZgM{6)?Y^`IXR?vX7J1gTokIRdtkL2IiDmea#TX(cSRoi9Vv-R#SXQ{I) zEL7byw02-zLL&+H_i=KqQ$I#@r2(r;~G2h^-aX|U}VaH-VH&% zR~!fzzi%~h`(Cpp>KGE%&mF+_#)}; zjJt5OVw?O+LbMD%+^mQ=KPvHAS@djvx9Te=&gX%4q8v(liaTuMeM3EO+h?&P`^Krg ziM&A1@&+rh1tY0{rB|z60L&?W|4sidU9gO1mF~4!En}HL1=b1N=*Oo9GJ)5kU$PF| z>g5ZHOIcLVoDX8vt#VS`*Qv_FEuGDLAeK^3F^>5*My+Zr_x$|`AsORq9!-9;MzJHx zlo}(YA36HD5AN%)=>O)|UzKfU(Xtnj74l$X?@BFe2^mLbk+_%fq%EtVhB%`r7+O9gH=TaDUQ&2VL0__E{k zq~M=hK6Nv&b`ZX^-Ml-vV*`)l=&bWB zFGuvxmK_ewjFK)ze7S8!gV^_-)BSs!>E`;^TxZuv=l0C5INNO**YVWZ?)+Fo9?q2` zU)=q6_4WHV&xxG z_)I8Hi)ftAd7atT_hEMb{?B5RCHd2Yg$%}FlZ9^lc!Xn&9DZbMr2j{^|9p_O{NlvV zP9Ch&Y#zP`uQ5=;ZjzfjJ5w7u9V6F57#SO$HZjJJ2N7oF-3bjEF@%Zki23<6u@UfJ zPtUe@i<#u%=b8r^Oj_{Q2-`Y|3kg!SD$8Zq+Ovwnox*`Tz%g}GULr3PaH*q%{b ze0+e>y2agXc4lktyjx|@%*1&0a7&AIObdRtaIqvUD5h(CabDbHA0fh|WpS>%>C*hj z)FX}Q_R1dl#n}d|%Y0v9+6)WUX&T?$kSFid+}#0VP>?pM;zC?xxzDi@>zj|68XlcUGy4ZAu zvnL`AyMS*Oo@*Tjy`$TB0=r4;LOb?*ULJOS5-)h>d4yQ5$J}II3t?e$3cu+3wZY77 zw!=*mKhjqlQ`LekiL)AU$dz%bGU=&oN*e|?85$k9xoe)loi~-ar**N_y%1Yvf}b33 z=phiAMCS`x7p-GV7VHV*k@9(jxmNkb$-M7*^POTQ`@YQ39+i=iZe5(19>Q0gKEron zwBHH;+FCxRq~`;{eYBm+`0AR+9pYHmnPC&~)+GDa9{rL|8#|eewH55vgoW;bL`Fi7 ziu0JfRFH=H!gQpa+dnic?_N;MTkD1aq!f3y&Tbo<)ok>=?No(VMXOhNy<|4)gU7cjO@ziOFc?(Vk z4ObTMlO`kmPV*Dbu!}<&wYg_aC7AZ|ik?T4noZX7<~5k+#i=+w_b>P+yXXl`!c=6? zBkRXJliM@~$J6~shZ>9N_C0R?Y3G7xk&?DhI>ot;Dd$gI(!`Yf}`k6#VaBS!-d zjt`|A{3xH-UK43D{U)eHE(klqp6637_Qjjy!sg05*_$;3q_5I@j{6RrqL7)QI_ub; z>LXRM^P5>PO{Vmwx_9ZMJU={u~Xz>6~9Oxs##dahE7_ep096mbKFa8y$54* zQk;dzoMlSVDaTExxAYifP2IEq;3c-jLo7Kd9gGZ-M#A~-mUN|1|7_nUEa__F_i!=L z*=38Om0MS!{0_1CHFDC`jqW{?@-wr2+zY7~9aq=JW1J^)HrEvy71h@U+{)ti>a_7m z4AYG?lYS|2=8m%)9dlhumJfTPF+G3tyIn8@Nj z8oS@hR?qVO(1(tiFVdQ7-xV#+@vccL3I1^RbQB_mQ})Jjd;fIvdZX0p=i4)8Y<&A# zv6|653k!E#Cr+Qyi8R|h+MDt2*~MnXY#B;FTi?E2dnFQrJp36`zKKTqVDgF;4-V`( zPuIy@tADmFKO(t3W9CCrCC=9g&QAZiFXWp3geVuJaz+k|B|NBfkUwxY$g?c6!S_7J2NzcWXA0NzdCpCNiuZYB&MEI91^3Sr_Cj4(Sumv(3_9DTVDMH zZB`wvh0=4zdT}8n+Kb{fZ-wyn4G=MA)M%%2)=Km0f%I z*g;$NSGR90WaG_kzV3P4fdTQMR@A-!uUce-9Eol=o?XHo9wT;sVjlkf{abeI0Y6CM zV$?^Ai3-A>Bn3-_b7z3)!0+$iPoM%cI*(+rKG8_}q>VLIMnkmSCehHc&Dl8agf8x{ zZ9RJ2FNpK)Rm2yOr#jh&4IF{|!N3mfu|W>biQv(tgL@6mfFHmOZgp(y#>QPXGBh1T zV%*ZyHUKD}j@rnri$(rdXX|LWb-k1&KAl{ya11aKR5%8Dc;7LZ*(DufB#Jel{vbdf zFY~`fR0qlb$S~2Hg6gA%0j-@P@&tq4_U^prP8ZT!o~N_`S1SvY2v)(tZjph#k$&P4 zw%pcs_v*4>uv;3djHysf@BC>O;_#p{+cwTIJIm=buX0WDQJc`x9A9Z8Q<_bqJFOf- z>ar>tEN}2)(r7|H<@mZ9nQ~o>JeKVnX=FP2v%~U+&X`+hQ6Saha;d)(I<{L~pZ(I` zT--$UoPUl#-_-}a#dYzIVY8^j$ehmRVprSpN;&=giwkW%C*(O7F6uWb=*Y}ezQDNv z@A2N#iIJ>hq{(a4tv`2&mC++TnW#p?rK-uoeCzA?93H3@d$kUVBs;RdqSjKGG7Oa! zu||}uan?4>0eKR999JDWsOh3@=-sGuw?4AGzgf}ZhEAya{h5GokxM=!vH_l z`novqRx#&kx}h)sAim722~?d4=x-9mF{D4=(ku>5_7!L}FFNWvaUmO7SmJw*c3#{Jn*dFDrA`zB@km=E+D^Mo%i54ug6_|MDaaQWW_^F zgZ4)u-svrIBCE2ahRXq6qPLK|1lUlh2-#2_53Eg6dq)}fJ>t7y6hzj#(o-r^ppJ=W z5iU-pqW0)O?a>uF=-s-Q6Qmm|Yi^6G=}%Ns6=y;TmMVUy3t~ch-y>VpCf8J^b}8^T z#%;^+LsS(fs=BAlgW8ARHM~;~M5tQvvoB^s{PTe@m(qCuUdTL&2uMutH2n#!x-FuJJ2Gp~^y9(K$zocQYQWv|*} zjL=u-h_9Y6!}HAECe+T_b@@eC=)2AIeH*GR>}AJy@;NSSnl1bGocVhXjmgh$p{eI7 z8s8GmADD-VcTk%g7Rh%HH4QY6LA=~A$VBwq+G&+g$#Qqp3qMK0W)s8j7T1!9#P*`x z@>gj+kXHo>EjN+q@qFSxvEUWes`1ksV`4QeH2d(y_*t>LYYBb(KVK01VDE6@;KnR5 zE^aF#94N(>w-wV@ZO^q{qJPR-^wA5e zwwGDH+GS&f0k@pP2`9jeI4kQ7576i1jLH**mDU)STs9sa%tL&o%j~CUx6+??kEifh zNi@8w)rpBYT{mR3p*km1tt31p(y!-n-48pH4bz46iStZv6zeQ`+n&wu|C}+syS|d1 zQ%}q|OX{AF{CAs=jGD$e&FiQFGZ){*X1>2s_;aVaKrf?s)WlJpExH*%il1(+=bOKO zIQPa^+t)Saanim{5Cx*}BA}xKikTHpBV$Q5kVw3P9&T0@Cx9@XPT1*;Mm$6_1G4(q+A*R+8`GbBziv100gLcpkd9%AVk zxYhJaDwv+dhJu;ib=&;{lOj1J2CX`HucrO9y)&Nug_Ik~W(>1oLeWYQUR>W1vE5)ZwFJ>!N%kcC&si?n>>hLq-j#NPxccv=X+pY0#R*U-lTtTmx zUNhWnCX2n=o0ns~MAX1h9RXc&ahtErMThIzUO*Kb%Dhs-(_su$C~FWD5GAIIlL-nE zVqUx2Z1yw0k{{ts?zRB2CEZGE045t)0#nmTz+D9yap%!pU8!SHFNCX8vBVnNY^9b(js2dWrQRe_l7(*YaZ5z^*924b@Cz1*>A zU^lWVf6;3`N20~s&fQ1rX+MmrNQtM~H&PyP#2Pp=!C2{;W2!q&jFsbwRECn`$8yM) zroB(JG!)Ur$|sa8;ule(QG}yuO{tribSu1i4>8$DGWngNg+i0aG7G6Rz6xkNVfm7f0<&po0;nV zA}e-@s2Gebk*w{skI1oALyWCNdy(LK*N=YTf%1K5Kf@DC@tlYr&{IQqgbtHEMZerr z-|01PlRdRRewn8-IbxZ}3f)si6w0uvQXPCD&stiZwcQ+v@CA1fkQjb2F|e_I#7J(X zHw<7weH>h;T!Z2P^zjYxBJLuRS}96?ODVG>dwX&SQTFo!vCHHrB0d*gdR|O?-WCH00(2i5XuLxkEsJQ^7i~W0J@F&Pu zzW3bzY%to0&x^^=A6p)U?y}9W0q!z-9RdCXD5m_Pb8uhhDo?4%09h+h?|Gx9NiFnVb3*@ck3{rl1+DTMb!|eZjszXfkWQezaA5_v++>vhC zv`@&iPO|#2aDa|P*sI(86QE3m|czHR6Vq&DXLi&OD z0c+iikVCpb#);Y5&EK<hv#viuP=&S<58&CSWbEUXbxKun1ysUel|T%AsFR zKcYC_j2JvkhiGsHCfpkeew9I4HDF0Z#|ROUj_VswQH1hOCG7Mx$Oxe*>aV$a56u5g zasJJkTNb-1RG3}$HBJmczszA=Ge|YoasoMvVN@R2Z=bEex?u%8^NN8HYhcPropyfttXT z&y!c?S++7YuX;y~Y68(VapFgo8vstbNS-G6>okAzw2Z$^Gbc|IBTr+}r{-nIsHq@N z6F-XX)~{T7QdT%B;s>jz#P^Sv9T{*ptCgsNGu3FA1`?=z>KK?hk|>JW4=Lqso|o>M zw}ipL71s*tGbR7eAFLv&Gld=++nny+N$iJ7vxQ!xt}-Y2TkesbI_CzH?S`+#l}a}6 zQrYko`u~Ex3;=G=qUPKqKFL%}-c4I}Yor_)qIxBzRFOWgF8E!O0`a-5hJ_*Wyn5wx zH4Td^$n)Bj&yA`NvyC+xdAce$Pk9YU1Gwk4&A0)z-jH$G^}K_{G%eVqX=zgMtg%uYSRy&|$S^`wLnHW~-VRPSc?1oXaDj+8KRLWv{G6JPj;+J~>Z+pH#p- zx4K&;__lBAMewr=_HtQ2jp`Uq3LBW|H*ZPR5S>9J8$dRR6nj68e_y~FYUAG`$hOw; zh5=WnhP`7m1+yc^dRtuz@cf71bvF3?LbYkbGI4u7&iB}|`_%2rj4^_?S|>uCJea}} zw`Q~&<+$(Xo8efE|3gPq>LX`ZJ^8<94*{$h+VfS1E9b$6 zCxHh`^|6$Eg5vYVhh|hNZ}e1`>t8 z{RcHfB))bKZY~XEz()d6TJG0Z8Y@v7eFvC=C9jfU(7CrOifR783!=itQyzNII08 z*^Rs=v%QibCOO|8X2asVS{{g*jI}4wFeQg&4B6a9;wAc-+hrn_bg{}okAON_)^wd{ zAbR_jLI>Gki=ju^1&;oCM?PmAiB)fTn>CQ>s4K1T^z6MHqcHs$u*aq9(S-hEt@Cc> ze?I0=Sa^>NRvH1Z6g7AQKML1NcU0qEr->m2|EBJBM>RtV7TFsT+Y&`7roMwD8CPr1 z4obFRw0#Fg!iS7E#Q*G_n}8!6&sb7$c~^n*y&H;ZB+MvZ_8UlTD=EzzC&PNPOOr-o!<;H;pQIEY=f55k(&71Se2woS7ymImN)@Uq zS6`=ri?SidsI^*D#(dr#Pk9?sHSppECbZi?dup2^BfstqmP9M}TYSFX4vSEyqK(YcJgFHJghE@2fm79X~@u?}KJ*bSI8=JSkF7Tu4xAtDigG|=J!g4?yJB8`Dz*2}-WF~Nk!pS6+|BVp>yc@i zyRs5?4$qOMjnx?$$s0Qj4)bo$rG3wTF2d+sqtZR)K{=DB60#Eu3g@vLzSoV6M(MI} z73O32-ek;F7)~7GP)?!}R%e`Bk8Ou)E2dgRJ;G7!cG+R8^Egc_irWRxg%!Q~_$7mu zu(?^!m#$QcGXe~S$Cz1_ZC!e2ZxrE?fq^gKsa7?cedEU5?sZIjLaZLI^`*S!d0Fz0 zcgH#J`0|SclLq*U8YYLGaL(rCNtwOAMVh|J;jKnPpY$P5< zm*v;bo_=>EsveO!6S7Xhv`nxBK+mBx7l(<8sVtb+ z`rHbs<9+eGzu(SvQI`Mrqo*l4UOz^>1$niUa~&6{qy^^znm153KTgE=WhMeT{9jJf z#NuDI#Us#u=;Re_z2?*<#rGY04jfms54vtdPd>L6a`3ce49UIQDSS{L%<^F&xdNz; zYBm!hi&kB8y!{zye}L*;)|5WAQXZM~D4%{LudD~@yCV&%aUjoHqPKrkpMiW377sj| zr$lP!B@#cK?NnL0%_ulm!76Bu=hs-d4KodCn+dIz+nl0AgX%}MH>pM;+gwW0k~1ZW z-9Om8h|tCB88?p8yy@MxK}=GMY)3foiFcsfdA=%hPN+oIKNh=RDN_1bmlc@2mPpaRXV(pD;_#L2-t zCJN$t#?_H$WjH>hUDU`IIbCYOPvP4Xxl9pc$C_;UayF!dSBX<2Yc?r7rN4w})I5Yy zF@o{oFeNubgq7{sw7erYGmAjEX}~8oC`3)B>nD;xfEeL%b8g|gO#uje8H$!%;a160 z1(?PokV||wE-hvyp7M00giG(glB9iusR8L^TVLH`L`^zTc3HR60;|->$`WOqDo+RP z6{aj{1ypa&gO#172qavxKGs1?Jg1|E?zwz`+bs1Fzzc_-NGjqP6^T}tK&4L2`XoS> zm>mynTM?AYCY7k5#KrQ-=km94qDGPFHA0yIuis0zu(D|Uyr0nSi0C&>{YON@DAEMwWX*Wf{{Ak(GAsDO`vV*u)NPn{Nb z$g)Z)4iE!F`Ac!HdJz3U45p~TEnTR9O&Tu`LRQAWG?pH5!Xo#yJvyeKHc%d;(#BwLM&Jvbn50czc8Ex zXzAJpA6xNRVl;uSpdU(MjNk>WyG#{eG z^3^DP(mkN=s8fN`gEvq+uSJaqT9F7p#L`WJFb76^h*S<#G?KZCuR~oRU_b+EqI47L z&ejBVhusKha3vx`JuXOXXdwAK34T{Z4K+&YCR}WR-6$|X) zz$x<=1xP6$D4;~7uF!v9t)>KyQFI(Ym^;Bd^D47!9!)g~{0PojO_fOA-6%<^_nJHi)(p-V-Vat|$ zoLlVZPhK)*^yJc#yWRcM+9^m&es%hD$r&6J5r}J{Gs=k0Xj15jc5P@qiu=79@2^E`f4FwiOQdSHJ6p}ZF+*C>4$TMB;jqBsP$=-l-(aHi$+xS-od=c@6 zzcpVj=r)lSOLbpmF;H{bjRI?3%9J|Gk>p3jM{pF{mAOEG6m%xI z415t7yK1huVX8yz2B}eK);2jEEJ_@H&829BEa>Rqh=hdLJF?tROtiW|gn81s^{zFYyz zqE*lq@hG#W#K20!JuX@@+<6RaWHV(&DqOgN=`4(k$%xopb6E#gN+V1nQ38TMo1Z z;v(2&0yX&O5x|--okG&vkmUh3?19FBO;H46`N5x@C<5gji_=_k_tf%{qCh2LL4-jc z_U>4mEfJiU1OEL-0A-TihH0z;VrwG20Gb>*Z9oWw9_S>d&{7!u=SL2bLkFD`Kwjd5fN9vUl!pIrjnM0StC1*YD?W(Sn8+-52$T>E(YURI#S$?9 zN|GQBp#~t=q?JU7xq)1J;oK!6q;du!oUkUry-*_bf4T{1q`5h{?=qO;e}UAnZ%Ueo z@FX@&dJgHH^qQ}~r~pq58YBXbR&4Mma+vt< zJ_eT)scpg_SOl3co!}>W^Z;$~6jm8CM3BqiCvw67{O;h*2Eyhu_Zc1oPUAx1>rxKG zuLYxtv_0S4Ohn?+GVU4j3!wY#DLsleZtp5;zYg9^;d%`Yus>(#8?dvZ^9|PUKNAUx zX+e*(cDIj%<~}u42a<0@7E%D;)UBt5J3__~_)&W)8c0$?9>^I$+!Uq{t)Ag7Cny}u zt8K`lC_kLguvr?J;i*|R2c+Doe7HCgL0CjJ^0^8z21+-{Q|RrD`JCJt%03fkz194J z$Ts}~rBh4VTv~({UP?#3k#JH7#~|#G#K8XNr+gwL4&J?Xdf1LH>mD!1mWsFhbjoAr zO)O2>n4Xy67A5;BKRb9(Z;o&-rAx;D2oVjzrZ+&TI4GQ=+?W7=V-#2D z^QNYECWKj`aRB+PeVtJAnok$C-u0)nA@XWb3Arw!l2bf& zrTBJ&RzI56?Tb=eC+0YXSsE7p=FRcMo>3uEr9BB4;~P)~H3s|*D%E;JPmn%M>IzW` z4^DSv(tKYp#p_2b_K3FnM58Z>hZ@~HZZzp{;+boGLab-ZD*uaks1Kh7d`#~6RlH=C z!-%#{y1$4=dHJAlFQRRl->)`L-ARpT+o}6Eo1?D(b~#(bBOdYLlFfgo6rSs{!{?Et zusf)c`buh$5O^08$e{2y@iKv5P;dN8)Q!kEbwy^a@qrscLu+cxbv_v#z9tol&pp)^ zrBH4awAg%8-ur`Q@Mk&R)H~EhZ2aKA2-6A1#qoUL6`s?(8sPnbkw$oE&1ds7pDYgt zzra7|HPf)>S8O$ZW&7GIe2VhQ!M(kiyvox@%3ri7`{mY|ch*%;7al%7@A-P$R(lhs zcyFx8u-4S1lGa4(eGZJY@)ZKt6^G`Lq=7pT8Q-jA)~>@###+B=aawPIm6GC3{kX1q z%i8DVUer|^;s+PLRufn{n7%S-eWQu5YkRWGt4pUlpQ>lA)|AI!k6-8Zmt66$8I_Z3 z4m++ZBTd48%@dumThB?2i0$<0>EUZhV`p#JQ3*E@x>M^p8E*{nK6O_(rN)?fP+1+L zHjkQODkvv`hRy<2*5%Wi!`J%9g6Z)T>r`qoPC3Y|y^Sa<+uOpcY{ZSr7Y_we4?0bb z(;?fqd@4R1oGD}Kh1jNfw7-WPk$K`tq!+J)bLqNPXq*CI9I^Pyk_$y#_D=Ci>N>ytAbBHvh{sipk&S4wi6;YOlf5NWoKBVFrfNc*^N8CX8ypq*Xv+P~ zDzoTrb$#jH&aptb5vqxIT2D*VlK#k&mXu>lTJE~Fq$O<^q9yQ4-(kn~hoKpBLs;CC z1xk}+Oi=$*kM{5Kw$7oxa>H&;*!7-w8U8iu5k)8G0a;}_THz-7sYl#9LAdY)>(zR_ z*c7S_Eb{B)pQ}IK!%TV`IJ{xIAZZmV=FnQr+T1iY7Ol6~K_hN{5I%PqpqTm_%AN!7 zM{Q;m0~_yQWCr$A0wFi?B#UT?QSO`Zy{E+#Pn{%+v}f~8Xd*X0;ko*&As!yvpDsGa zH}vJ^;l(zm$xTexyN0kyB*xUX_=kioUIFP~{zmGDqw_!|)Xr64N`x^C4PL!uI}aGv zH;XoUetjAlv()wL3LKV7E}b1>tM5%!%vB@(DE2Gkl36jHnL|%90;*&93@5 zdiBR#b9{-9xJBXG?Da_?-=hbKNi8)=RJiT#b0?5LODZRLyG~hytmXw+prVPV{6^Ix zumQkC96&dhPm5?|%eNd2X6a^h7o-ne8+bFk2GQi^c2drt;8EYkk4(zr%Xz_!U(A#3 zy|Y~zNlJNr%;@Qn9wv!7Vj7=!Y9}mc=cTbp(1L*b4qhVS708Q?B)me5V{n!fqkFa@ zv5V%uK1gYj*_!wBL$gT;2ICelqya!9qu51db%;njF$aQKawh8IsYy`vcstK9-<9&C zhi3R_Lt`Ua9-%I-31L^1nHL8t@dG3gcIiu1p|j{=7aLl`%;kI|e32s_Bmme4T?~O3 z-@t5zay-3O1kDB@nV+%C)z1iy3@fKe-@yiTC40lwKS(Z~;X)*MD{qP9?H-QLSAwWU zR>hd6J0vg%$p}K1Y=RdY%S^BW{;Yooe+Anm>i|wdjF;EGx@dcD$vU<~>u4@B4p2v^ zqcIOa6A}wGs@7_!&Poph#O9Y8qZ0nrHZUQ7XBv|bt7K_^$oHZZgR91D)<@M=Z_4>n z-?jbaVqdT4>xbM{nb%8s-e4$aHl@m6#IY+NaRTOSVG2KI*(Hr%+ zWrBC)9`4XuLv99CttmSfiM1%+{~`O`empn|*$t@?F|~!nQW)9So{;Q~g7>J(8kHJV zOEvDBM_@UIlDL-2pW;%{hS37;0mT%871X{f@29G`k=)wn6(Cwbt=2jnR)Una6?(S_ zD2lx~=)B&dCmmG7UxUK@>KLLI7IUiEIJ<9Z2Qe)YbKdR*MHkRt2&i;E3-hC+S7vh! zAp!ZN>e3%0*J_CWOZlSDv@Bn)x-3hJ!^_j6FMp}LZ3u~i1zBG13W)LNsbxn=$ZfTK zERS(DD}X}Kz(lH7&^VQ_S|ir6ev|3FUMs@eVk98G_vzc6)+j8-@`(lGuwGxf4^#CN zi9L>u`1VL|$Lx33N!;`s>qIN@C+=ZvYzxxZ2KYw<$=yKF#7&095}^suK(T=78J`aGM)4m2 zv=TWCfai#s0=gs>K(>IZrCQ6v0t~BT82mh3jbt|WwA8XlQkj1+`lImfFw`7o1spnh zcD@$H)B`(CYnIH9xTmi|KWcq`0}bkYzkvp+fZsvGfgMZGz;UOig_J4Defbfrtyiy( zT}1N>!Xb$dmG>nX@z8)XM3n(_2zsck)rMd>_8boza<;kf2 z=2Y`0epuijETk0~1JaAqHaJBY7J3*SkS>roARq>q;3#vD8Gr-kFuMY_gmT%Wy19+* z&|m0UrVsPTG#3n&w=E3;uX{m+0sg5ocQ+e>&POE!Oy@8Vpd8?t`J3GRGay>T5qi1{ zfzTmdvkAxeI@ZF-w2g>*fC*qGmSsIpKTx#d4E78ncHZmRVRI1SWWfKqK2)1%gkMVA zlCA(K$hrb<5y-pbRY0Yd_^$NLE*(IOQKVe~6u_WMsW81%CTD;R0RAKSR*j|o3RQKE zfE+1-#$>D8FsP15H72QwQ1phuRsgaf>(_?H4(A-a0_zRne|6_RMluTK!quz#5(jm; zcaq4^fgQt;(?bSJ*l<;iME+pvl=VHk(khOUTQVy|1|TOzIPWiyfhBIEM4!kZSH8WR zzk*bPG<9KAC9XqwuH|$XAYSk=HPKe+iwKU?OhTPIDD4(KM$pBNxZNa1b24@ULI=(n zG~}r84P2O3rIL%9fvX@q1OYx67sJZQg?Ghy)KP2IYBU1AHtgmSt^>RWV#lN0xceNA$a>WI#`d7h zebMg0^91iQ^!z&U1USQf!Q8zS;jLe;U9QhUtPGia-kG68b zQxc<~2c&;hzJ3uyF@;x`0UC@lq_jgK_}^97CHlz1JXU?Qy(kDJd*3-1dm(qkegn+| zSU0+il0YE?$Md&XD_*^23?jj~ z$8xIo6NFZlJ>+okARc2^c*%JgXLEo7Z<0EE6fNzGQGnVZB>vk8Mn`C&bQw<6c!NC? zHtSLNzUcC90Fz#g;2b|JDMN!%0V z1oN8)o^`;A^LslnfES{hErk$R(1;W$ap1grdFLdSFvLTc9mX<%N6eO|chSl>-CVrPR4ePhm>mi9?HcozgFDcd zE9U-i77@jhmz9ctBml&+xUy8tfD{GQj|67q;%DwMVg_Z)K8+&3xFaGtayU+);Za|B zmRd%X033Ts$L4<;A(Jg;Mv!EX^?~Js`8790N*;+tW&Uk|sxh15VJo)>Pd-+Rq z$|6jc)IOD(w$Y=$zN;CA%+&FvkkL!6*Iy?O+;0V0l&b)VMFH<;o_CsNEvzOd3Ybnj z6Cu2(!VS+D>4>t3S4#)oQ>n|?fc}`f!_ui){>w6ogT1oy5d4o!frp)B!{sOf_!4qJ z@YsD=Ya$)Ehg2Xk`N&n^5(piL39fjXpwzSqPptgg{y^T=5NG~H_lyscqkBLjt_3oN z+2RVMblQ_v^;}vM5(C!4th6oAgy5tH$PwI*bR+`*u5P3wv3ps#qN@kW4yoPOlYDMD zn?V4zb_~jZwETXF8&bn_2n`fiwC6SlPmxZ$iFH|DgxuXSM&)07SzInB$~i0 z+qYN#>8P}-4M0(C{2Q-~cP^3A-jw&_PnFpPxiOn(y z1rnp_2)B|qgPbSkEz&1V+~geb8_t6^`|x5hIR}YdJyfPZjf&}J&@_Z_M{F9RpaGnJ zcstS{Uir8WwivPk#AifcS^w_0X_O5ZzDO19AFT3i+VsO+k)^bwnI%3x-ZrMT}$e| z@u+7{L23mXIKNE!`@kGH{O|2-_THQZPX;SH+yL+^&VU07!rwvTdl@x^bpSjjTpLO) zTje>t-$NCFH__V>xhN<2;@{6c zs||qjUxRQ_UaRFKX+e*lfyS<|O}G@{4?!hIxzCEL7MQC<+DNE)19F4hB?W-hCsf;t zRtXp*OMM>*fW-4LxC$YkkI~d19)o|m3Lzhbu5Jj8h2AAmz~#=3faXAZf#@L#2?GRV zVOx}RF91$Ye;>dq&VfV0LgJiBL+lGu*CS`C?mgtr1;7w7D@r7YJoA#WoWz4YIu=z0 zdV>g=GeH(0alo0+z(`W%6Vs$V;r(SKFaiQ0TnQoGgG-#V);tfEBhs4s=a+HE)G1ZR zweU=Ey|A-^nO`xD$XC{UPN?&k-PryHp(~)IcXyux^#D>j&cZ7TqHtszau|yxn#4K0T3pfHhcqOjuf&Za&q~l#6`A!c!UKk_a>2Zag2m4C^9^>>*7M^#1af zmNyg)lyD^1R^0dvH|7yrd;CqvQcD03an(}IW3?vgvV2(KC^;ozTOXdF!C^*R208SS+rhfYb!e>RFN0zTDPYBzvLMY{u;GF`2okpd4qM<#g9o5(j>Kw|PC zcG)=}_!VjWr6~u2qdGQ;;7~kb4C@WVZ*WCI#BXrD`ls~G2;{-9Z0iqM8H8=YJK(?H z%7STK_JFmm()(kCcRi%uAAzpb-zq=mXqynsGtiOi+&wQY3DX?%LWUKLksI8|eV(-@ zvB{-Wzv$vLgWF;9a44ocE1Vwh#CTXMJT38Uw22Jydk63W2y!ty^g>gpwRy%?%3@8vvhb) zDh#>2iMds#VMUZ1+ZfM+FDZ68SkkCaVTeaBm~f=i{EGg~%KN)t=sbxVVA~_rcDJ!> zEL#qAR5j>go?47RE;_sIN*z@aH;K7v#w^)Kb=2ZtXrHVyQL=rGVT|4G z%9dv9y8;^(0A0*vSJSsTFRWgZrI^9N^!yAi5B&$!kVf2d{*xHUNXm z34nh!35^@@Rf+P_Cl#8xZl%PnkVY^PG_s}Sph@5+2Mzf402^VyZL~mtXeRL{2v_jQ zon~(RN3u5%(uCfl!>YXEx^Klz@$Wbjd+y$1DvwblgrVZam%t|;pvBB4r;2>%(%q!^ zTMb1Reyd?!!S9Tj=K1os#@s~OiX1Mx=)p%qXt<;?zWiIbd?!q6Pz$5q;(h;?K?-8@ zYAu+Q8!N9z(T2!xI40?1$lGB(Y$N`HH{#%p8TgVxP8A$B`et5_7>0tG@j}!2q{s%b zyTb3136_+~%;2jgrC&doDeu1WJ9`C6oTeatQ}xT2BiCxb{u(QR%=3vJJX9ELpb(Ac zZumK;JNP=ZCWL@D`h2B`j@@lh`*8U>EQMFRP{XxFx14*aWK=qF>ps^{|gH-R#dOzw7|kV8(#B=b84#37?Qp-i{&FMX2sX~uv?AHlC$S$b0fpD&)1fi3%Y z%g62&rmfXHi|3@32OnyEc)g9+o@-M=r^6j#SGPZeX|;88${4lhXcFqy{yFZmmn-d$ z6OCPwDw+=hlgj4#6>~JUay`)FyY-W=z&^WbuUUlkPQ`QJpH-N3j`=LVw znZ-Qg@MAn)=mch0n>!-B)ZUs0>?ayOo|7`Z^Z-N^kV88lP46q*ZKu@uP2qWo6D0#1 z!vMm9HKpb_hQnB<3d3t|_||8iEmvZw9hE8saDEef!k8^P$8kan%v7S;c?!(rkX$}9 zX+1iIy>zPivfIp^9T8C^pkYaf%UhIWnF8IJ2YPn5s`!m1y1Qa%!*)_*&S}BHeE!>u zd(G_6o~qoG8MYp786J)2y#w{fuM1--M#Nc|juGTKeyh(Z`dqns>j}RC`w8&}@j?lA z8BQci9*JN^G{n`4hsEyYTBP48><6wNH>Wy}%9-(b!$|;UMza!uX|P@@wDYqvV87Ud zVh?a3h0vxdZBb`e$nswq3&)1a{U>e1^~7yPfnPj&HQQXS#1iEC)^**EQ^!BwYnF&c zO-<|B&;ku_RGa+p08SV-Dxm#FQgra&er&A zBBO41IYErjK)~g@3lhE$YqyV7Z@n|nYl~I)jTwxHOzOc}Fx-dgZXo(y+_a z9nsS=D~H{ehNY(Oh;qoT9QIrqo&&>8zYKdV4QI}Pz2#QUzOyv!G7I*WUp9P^W~kR^ zX(Xl!o`X)sCZ<{vY3vUR zfOMmZJAq?&RE!)`!n6i=Q&2RH`sJ0z+Zc=Ozr9^rs>A;TvwXYa{dV8Gfw|i&C@FBA ztk@8h_H1La=pF_BqJhR0L$Ta+A&dW!>BfwgOqcZ_LY(JgSN-oz$1Wlk74`37 zx<*3Wphf7x94n4&)(CN?$;63j-l?L{w_ze`xJ8O>Ul~8}-Ipj^yM9khhULw-);zaG zapuRuZVPNaq2$b`9cNPNMB$T?`>w1Y#O|S}X^1Z0BT>@n8QKpt_HV0U8|LLbo`kEw?3!{oNRi zzbKcmzo;3=azD}C4|#FHFu2>RMU8(h#5#iU$h(3^%0M=wBI7AmP4)i~ef}wJ{@Woa z8*=)ef;UNqh=bduWu@l26Wv&J(j2=P*$kz$*bK`70?@$VL_KeTB`w-xqQDS;Hsp5PM{+QY(JX;C2BWAKx57vj{448;y-X>w)a+jg zR$I9kalvR(oLE_?l}fxw#WL*f*z&4YGs;U$>wncYi-og@MO0Suh+d~)P#16yL`8uF zF=2iC(&-v`rm%Tob2YB#X1xfL0$c~D#C8KRG1~C9i*Y6uRx^A9;jf9<@>YTpZd
5Og+)I$gbPr9qWP^+Op7P|d-!{Zhvdkq-B(q~!0tf_6>*4*`ZSQ-jt1@}H&_yhQH# z|0cBv`VXnaY<1a$&%o_L#(Avq<~oFVK5dX@nX$$MEUH$3v|MXEpUF+cY~fE^`N{ke)UDk*ps*)`?r`;%iO2oVm-UJobG`MhpcCDXZ)k9 zdxC7foS~vKq_lIs6-Tv}4Xn2VtT+AUVb9oCZgD7I*D3CHp~kZtzkbl^V&6NJ`{Bpf z*Oo(IdT^;u%8#D(CltZ{!*mvVf`-h11wNeN zZg=wBcXo|-2+(Do%2kw6%6yNPrrrlAIwgJ@ii}Jdm~$qLDM)6^fI4?JTpZmc?LAZv zvCfDAH}Fipko8%SF}f|TCU&wwy@L_?Lc7|al_Tc6FS;Nupp!`^yO!N&;}bdnHy!bvuQRRktmpE%8I zFE;}%d<$50odultcvsySXi8vjMjFIIz!hr_y=>~P{r|@i)1i{%h*B!s zu@ogs95J$GJz0~j87gZ>;#jgYm_rVwEG;->U!%po)Rd)CoFtTE86+X3O*J)h|6bR1 zFEiClgqr*Fdw>5qXCCgZ`@XK%^;({<<$7Id(-4Q;akWfrv>aC7Ii@NSTJXIl7u0F4 zyOo+@Lvt5$?oAvM4AVd4ZJa%#khlI0>^D%}#;Dnt#$Egt?r@{l?9@r+n*DYtT{C*6 z^@yHnz!AXBao250_R}VrX0q}7)prVEckfT*91LB9*tecGk^#&&lCa&iKn{B#N3x$P za>NfWp5j6Z8$q_QT7RWIK$l2;TWVk zK%hz85vW;}tjk*EF`Tn#IVhIMZ`2TLk0)60l`>-8{Kxw>!H@iJ*9tD8!9CjgsWLv@_FxD6diRqaVaiu znBASi&Bl*X4qsmrVRLV6UC~64_RBV2TP_SP6y4vFiGdF?Fk5&@Ai4VCYxi{Z3&}V< z_D;`0JA@XHGH^70ODcoD(~VpHMU0Sm$~MeJ4=0v;)Mj`%`o>~|P=Hm#7-JjeelsLv z=UA!P+X$QG2FguL7heW5?YIuMcbg7leyUpjMVo@K-^;Fqmjhd><*kLKsNsq_n>!4q z*tvf5ND>zOWc~`PM~#D$i6`WcA#p$O%{CoMcWND=&|78QxfaN!M0Z}9Zk!u)3>bw* zHKf);R0ds_B#f#8T#1I3)Vx~Vz7N!@ttz#8)%1jT$zEpi5 zRj?Fz1m?P+VJf3&N?AyU-1sJWVYCk-Ch4+Z{I3MnY6XYX2bYDJVL6ut;e`fcrGLEm z23cvKT2|J5qpVn9M+u zYUB;u+w7o*--}wnr(cwmoA1~`jj#t?7D$Ror)~^(7|`b|_+%J|J?-kpm}VRUz~Pb@ z1T;}Z#I(BR7s5HNp5aAGFe4oVGUBjuzqE_k`!V0#TNG@R5VBC7B}= z>lr4sZKd~VY6Ca^(WF75pEq^LE=XS068;hNSm%94qQHYL$QuO!Dhaq(AN@6Yz&H0p z5h;vXb)_ffuk$4Vt)3--SBSs>t$q*k_L|fy79(NT@J9ORJ2-aKIZqU=SJ?Mz!(Lte zP~hWarMO2{6dP2BNn-CG${vgjE04}pvWKgTAkuP(QUOtBA`KBqWqzWhqhy>+*JU*w z=c~D};qbc}jtsX~3LC;|xIH~_P!+@SMROn)h*<@JZxw*z+eE8#UQ!-EM+sD-9S&|c zDHAQu`~*QXmntKo-{Sbyd)>iSmoHye%s>Y+RI_&d)wOt81^G*48;;9P7|O1^q+;6T zLWeYhDZl$Da8P{+3&G>6Lx&+@`PQQfFBleO+D@+9^HPvzD~M9j5pPNpmDraHp{v59 zG?6PuSzB0gkyqD(hS`<8I;{ibJc?Y>GJlS&H*XP1kk>fw%!or?NTmRBjZtLMLA6uF z-A`<(gTmDiP*#?;adyc#zcd@1SKXTYLprarlFaM7m|BoDG zvPhXW{U72E!f2G=5~mnhIFY53>JHW{b?jnkUVGQI2x&GdK2@(*cxq;DPp2l*RUx7o zyXgFsVl*`jnQIElLS|DDv-*A0v*QVb#G$MuvQ8eJhp5aaooc4kAc3YM>G@3m)Fo|) zx)sq#3=>TI&YbR-z!|2>i4MLOMEXIbS1Efq_)ihk_0ntj9e_? zC(NTIE){TULcI|@1ydosyQ79Mg|9(63XAT*TQU*98Qg|n2Kqi6w64Q87mEV2VP+G$ z3O&q)cAjI#ayS{wHB!L?^2iaaPPQ0TSlaz_-g8Gzz!O-$uTESp=Lmq%1g-!Fz+jn4*fseC+4G_l4vLX?!6lloc+kp9jb{#th#lV{J ze{(b zN5GJg_`5P4&C(9q96L6Rli|oggwfWnNJMP~8aB9Xzs@)Y;?J48GJoEb*gjl82~U0i zzZ=d5Up18!=I5@T3#38|+t;kK->U^joDZs(Q4Aul{?V4c)#Ey%o}1iq#9*VMxXY@S{CzeBZOH~o7DntRZOS(a!}pjJ>8e#TTDtoU2r_j}Q!;GsR-*J&F}!plg0$2oR4|%E;e4+dlC}V8@oX-F#fXUQ zO)seO!(hgiv zzi3MxN-@@$>i9A>%03rg>!Ef<>a`Lqo%$uEUlkfH0MXP+0^^iYJq!ewkSf=(rUN)G3~a`YkO) z=0xiEZMh;e54DFq>_kPclLZp7pd>#;R%#)T50Zmg#=A*=+gd^u+LfM`0K z$-=1*hRxSvvI~_`Qe9K(n*~G8?>4F9I(Lyr2k30#lzVuvSvWJP)gnn3BZx*mgzn$G{ zL4S}(_Mq(VITdcBiW{6|MMOanQ7Dk*&6dUs%A_LM_}?I#X|^aQ`%)-V6;(04uLNh7 zuR8ouQLzc`|H%s@)t9kMTNzl>Li818*Lcq!Hke(_qb$HqZOxvWSj__3l8ImD#KBgaJh^fdRQ)}x4!vJm%RnLaN# z@W3MJSm(7%Ja?dKQ#jPI$TJ~uC6N!sQC%Q13B~d+!w!>G>eIXGK3bHc6`FJqCFWf3 zW{#!G@{=-KPyM(WzXR1jUbY!QW%DoDxFkVu%&vapplmY0Hps3MSpjf1f%xFCqf1eA zj3lok{z`?T7x?=RbdR8DtaGJ${aSPG-(*2q)CrT@N&Coo)Kr1#m#f590c#WrQSmRF z%cxjUSuGQ)8k>H_VU7|I*LRxvR0LOjaWJkp0}dVW$r^U`*;lVHU!&fbI>0f#2}DLo=kEpGdA#9b;$&Ru_8#sVUS5k|n>CZp7ykO|9S zMIuua&1J(;5HUNBf~*#>AjOThgatLr5*Zt6mhqOTJ@QTzO4(4ejJHJn1yk9jHD0p} zZB>^-!hczbiF>eD2rn2wB3xUxr9m&KQFZ+^)d01v%9x5yo;rKY*hTZlO&Y~Q5Y@ek zASyJSRC+3^ieYdxndg3!e5uM@f0zlB$-1lm0BSrG)=jPPa&GDzjd5ly1)UY~{b9XJ zMIx`;P>Xp}?WZpBuCU<@Dje+-zf}8)Tt7I*c0v91?f+ZC^5wJZcw5w8Y{-%VJ4yCg zqQsBL4-?2TL_}dSA$u$$vU7;3g!&!A0_&GsnC2Dg%h3>TEYAI-_Ck>qKbh0zv8Zo| znkz+2qz}fOp}ShBFM5(9ZrmLXp{o6O?m^M>8G%%%7xl&CxhoE?-hrB^sJSzUU9x#H z-2tYC%7_S~_eY^9K$N6#m?|h_5p|eKoQRvLa-qSuNxwt?F-M;|Dq_|U)MQ1;u_)94 zV7%(nR9>4@)UHAZc7@qHi@UN?v8+bl&>Ya}|Q8>x21BveT;z>h#DwBYOnkb552h5{o-M!UY1h z#qRf@9Z(N+1_~}@RCv;^Aqv@+|K};M1W|e-bfL{|sGoA;z*BiQO1k_f1a(`QRQ+RR z^QRe0F8o56g;qL$BySO^SgiRq32|sZ<+YwZP^P|4Wzi5n{I5>7G4$u`d@0GfTg5Jx zH$VF+w6RouUhKQtwxNAFzToewI)QR)qZ241#&0G?RW$-_tI))%uBh_v zQ+GQYRst^pkA__Sm1>q6px7!^ceUAWKG~7Vfy4BpIx<9-Hg&A{)350lakDCiiaoK@ zasqtdoeedj)LW@~%xlnM+>u;O!Ss?4B3?vf5wh$M30F{BB#=&rqf@BeeE(UnGu8d@>Z4dX0pn z0@d?$Uo%l4b&tbk8?P$*p`wARj`jCJ2lt`tDpf^;`mf@F?b0>qK}S1lk8DqN(zIc$)_t7mChToxdX{t>&`;Lj#Ivf$wQ>dyUHkdEXD zj51iDOHDlS9ZEIahV6@ugt!jh@1qn8cI+8@y4@pRmkama=$u{YxqP|JfP*1h&u(>! zsUz)nM!G*>!epDFoYt})cP~0Lx6v#4*mL3(t2+buCClq=_FknCD3%7Fykrx3?R8Vf z{*8sN^AZ|$Z{pbBIOc5AKkIJLInZrVl+C{IOZBwlXNS+Ag&MGJq@7=I(P?)p|*=7yvAS6;1U#?=oL4${A$q=8=AD>!E9Ee*rL&Zk#+ z4w$jHp}D5F5-JQ=;##CvV0KRsR0Y)tI=x&H1kc~?vp_YAUgNS{_O zDSpOX^miQi^^2p;E5q=zkMYy)WNy`ih2(kY_kceOUK^8_Tfez(3CCPi+HKNec-Niw z;j4@|=+9ubt8CWHZU3g8HnWrl`dhB=b21(iY`f;g@_LWk>$)}Z)oUhS3V+i@AfoeH zS7Af9Ae(U89>^eS>bjTmP4NPbCgZS-fi5nt6w9dWmTJ}?NmnT;%sylsJr zEQNKh=hiid?FS5B*`mJ#s(%Mt)j1NdPs$`QX0{T?z6=wJQKWXU_uHer zMja2oB>QaWrx6O*Wd+A_Z}aO-ZSPk+^#hU5mDMjjt~0(f2<^_bon#A;u!Hh-xRv3n zb0A`6Gz_4$NMfcfrA1D@%8f%Brn=8^{fW{GFAb3@+-7qODQ8glm6T|1n&}Ssz?QMV z)wB4Grh@_ofoBx3rlVW{86Er0gwhChSl2a%(Xx})yy#7;%li6TI*^*Q_~g)9Qb3gW zfehV>DQ{x2m^|48%1QL^QC4YZfvW>H`gkvc+jQ0K2r>_Lm^5sp;=-yM+q|_gk+GCo zC&d;kF0Ao2zF_gd{_aj{tHQ?8`(JkM&)O5Rui_n(Z1xzhjIc?6FsLY|*=2x5U@hdZ zs7k}9%zA$>D&)J_Hi8}}wNDjxh=h|$pI?Q+FnYOMwW!;+U$iZl z)A9&HaDx{1e%E+>XMjtV!$jUv9+5AQiFrg*B8w}_5=dviS$a!oIN0yVj79*GEbDt8 zoEtn4K%y|V4&bLJrYm~rj7J!;b#J55*P8*h*4O5MVtdX>!GE~8p?2&G^d$hYe9JZ1 z%zyf50)N_f=pSGcA)l$1u%bS#P-ZTs_W(15|<&24An%BTJfqy^5k-e`>W01VqtjmZVo=LqWp%rCdw zyEb$JKgUvkl_r4Wo0+jn$uKDI?uffO`p=}Wi!}C8=fyjEQt75 zADp^s@@ljY+^3goU(@Ug?o$rQ;Q)eLd(LV9raTJ;x7nuIY^k}WzP9)W&Y}v5sSSc+ zdB`2Gn5HR+K@r{tQ9s{8s#ITlgS#r`QuDTc13|<1 z$qT&S=H&5C_Rl%UK-%m3${f1r&HAKkt&c$K3r@-z{0y<(!wsFl1qW8(17Zb+oNRam zfmu+f^RMrqG~vX&T`=4_&Mo>K5+0zEJCwd3w?tlNYJPZytlGgwmW8i!A z4lK#DpQ;>_+Du>#u>~X&6<>E*G>Y1J|&+UM$9bM%rHJx|LK!W%ZuQv(x(eA z>)qK`_9!q#t}e*g2wq6yniwhU0@j+LI;on}F8mQZ4x7DYmZ$1ZFB|s?a{^51G|0$m z%nD8TJtz&NxWHCNCXj}zW{DzaEUX-1XLL!m`4vl|EcwF?Z#768k9b^B2hYD=uogmL zpq&wqqvd>Rh5TcrZK<^)oq-?Pu1TR)x5BVx6!pI0Qx89VY?@`s66{b_+jG1rqfvcwh4H5}ygZEA5`?0} zm}E`(y^UqNy&cvqh$;SP&0uu-`bB^x)w5$27f-^=Z`hJa$RgO>rTMY^;{%s6B;nr>NEViC8Z(&PJkQAWn{>-qPqwlLbZ z;Q8Utq730;E1bZ|7}tG03R^fsGU2VmllHn|Q_0i@No0&{3l3V~Tmp(Y!J`xWJ_aac z8Q*PE$(4D?Ozw;gt6O$ijGxLfOG`^n@HSC@Q`bRudJ2L*vp&tQvu^d$zM}*|#1x}n z7O(ayk!krf+MVq#%I&Q!D|tbRWk8485*% zU=p%27+js`OB-tly6ReQbV5)7yXxo#q#6H~C!4*?#P&rd3z|gDqoFANDE9p+-+H3q z5fjSoZtppU3JZ)dRx#+jswZ+x1ykk%07Mq#1OknwF>@#@2FsFAAOyauh^cDqNdTub zLvS9Y#DunztS(RIw}126;l>rggAH#r$?ydg(q>{F)bzmzxQK|R5Dlr;6VfZ4?PEAN z3_vS@Xrxo{ZVKxhqysN#79=*EQ~_6@T_LgZvP0 zq+CqkNiWKopv6Re98)u#DF@r%%MNni54&56v}2svZ-4SsrGzf=W_XqMqbN@R_DmJ8 zE|YI8H8~uz8iIn0Co%NHVu7(AD2!vryygebBLg<@n2B0}15ZY5$VgKdg?8$DPa?q{ z6C!&+2b4a|V*-}g^@wI-P)-z}q+^`;71%Mt6OxBTCFm767_hu&`REjn3DJegeRS;N zR_A5dMc=Hs%WyFHKFCk55;2I21Rb9~qJLTH^WU_3-8IG!#>rcb@P#3ctF1=U!g1TH zco>dj;I02Y0?iHQQpEF@dE)(eofmV30CLd5BPMZsS#KF~AQcEg+HY;nb!!{|{VF2T zW5^&@cZlke3xITXG=6pWpDc}Zxy}fCTrW3~pP}$UF_cI06pB|MPEhcFe-y2#=(pmo zF!c`$ZmQw|Dx6X+CL|52kB9J$Tu?}MMU2BnWapo9NejZ;YoDg9t= zEC#y*(MQ<}97rsKSmty(mU)p53gY;ux8dL%^ru+mp}!$RTc@_g1Mqyt0M9Fmz!QN% zCYZTQuKq_Db0GklMh8GYG67I1=n-%|%g;g{4V;))4A>Zbfs7!c7cfy+0LJ(W7#N>s zqK*KWmCjtw8ZeKyG{C^$k^>BQp^S=So@Ssn)}gSh0t$lVrfCt9)WO7w!m*0UG4ib_ zd-2lUB9u?odWi||*M1;@UU8p3iUHMLc@b9Tj^gTxyr=;`8x%$_ZY|BXzbQlF!U3s5MMDq-I<1pRne-bW z|8)}UV>sMdlIMC9=$X>zgqWIB!AMdYD7@Bvu0uFg{Z;9c zf^MfMI-{Dp-67qsmZBZxQ%S6w;?Yp=0ixZ#;!p^h0fH1rDQ|=p z17*zAJ31WK)B$l`1RWr?F4}S-t@0{p8f9N3^I!_JQIMeuyCs*Qie!0G!4ZH-qdi29 zid?{P_DspjC_G)g$zc;@bC=;JRQu9&B1+q$%0x020Lf1zAu1qB%`I83O)7}O!nE?? z`syv2g0ym>XZ9lp#mAQKyJTCi0OLa7hhlqUoT-MNOrG(IT>n>0wl1SWlQ!uU@hfmt0ndcYRAF&P zufVGK6Pk%at|OX?o;ERhM#E-#x|LiHikFjU_vOY~+ zq(SEu(MsdRY{`87aps_k_aMz@QlKqew8K%6{#Vbxx;&E}?J;UJ zL{x8UuL|)d$Hery)z&TdBlqx(c_`2}>v^foC<@&TH=eP18PQ2+{CF^;-I=ord%OBA zhik50{d|6TQOG^Zo+u96-IBo^zJF}9OMm%PFyi`s1g~y0M+c6&yKT3*);vcx9W#IL^Sg8U{D&Au!G0Dg?rIS@o0qg#{P$Av^4o=`&xWzK#=#8s&E&^79|Y= z{t-io4=g-Gcm^GH=--%xD@=8lWXFcNs}}ywfyw51tU;B~3L#BAjtZh{grYMCbU{|h z;f;tmsm0I9GZGr1^cjhxNzT}4;D`Tc!zN{Bq_3F4Fb&3R?x62rO}Vk;849u_S6=J> z3GE0hiaaK<2A!sWFH^@PR1MWd7Pt0j2*Cx4;`go*Ib=Osr5`iJ8q;_g}=NCB0*q;}5ui5=wWJZUuQm1qWgHjG#<6CW{0WKl>zo@q|W?uXG~NLCC?{8+zC{R6C6T9YB~m=iJ^+TAzY~_D$bWqQYR@m!kn}ya0;Tq zM}fieHIavHn82i>u#lS|kJjOFSuT8Z*htfn@u%RNQvS%FRf!Q@YpM9r&3i^Ok-6{S zn<|H5m9+*mRw~AfAbE8i%Bw3cCe+%W!Hf($37BvubyA5Dt+{lxwRlIXBS#cmN-0yG zx+<~p`0?d66wHFcGt4OgM&96!bih(x?S_sT0UOve){Z&9m1<38#Evo${umU=A#J(A zz0$BT+i_x(EWvC52A*6tN^i(;jRQK`RyOWFS%NA59DR6;fx}z|;)hg#_%IJt8v(&g zL~G>~kq3T3a!@ovfxrlJ$vtxgGL{>JI2XQ5q4j;g0&2yDRWh#YZ2v>qOP-{k>V38D zrNPmgByI2SJ$uM^dEHhoY>Pe{-W||?fYYpw9rm`X|MKE6mu)#Ki=b!KD%%3onhdpv zf4Q*O6E5G{WM%27Z_dAv)RxyoivJTZrA@)d6OdIPO3e07?0lI-6v^?b!pRlB+Ob=rm3S(q2}^rIGXHg8m?~<*Tr(nBs2nb2s6P){IZi;r@Z2vJzWpL3f?Sof(U45wCBbTvAZriP ziUep?V217iLBuj-h=r9*xo7lODFyT+o;7(dl6?>nX`=bI-dJrGi?imh=6N+OxVI^y zhzqxr3G`+8y^c@gmst5Eymg~UkJ}Y*%1dUug+Z;4Dx+)EtW7cn; z!6PMP0DmrRcR+X$n~~D9ftDW9CY5`}NY?-TXP@Hvz^)6CNun7mW@cG7)+68>>QJ@? zi9V0A*WJaSV-)O8xo1fK{Qu>dO#in1I%ABVNVAJ&io{P%9DRa#DFxg2wXpms%^{X6 zn6m=h3sd+SV9uc#O^mE8h$|HnWl15jY%Y=K$1^0v5-s}X=lq~~gQz>cuh^iQ zX(X%HvawMg03wg)Ery|^-Ha;YyL5h3%OTEM+NJR@cQcy)p zFc_)w!mli(R)=~XqV63)zqGaCDhALLa1$*z9^|)B8*S-pJ=82HHnCD;>lmg%Ivtpxo7*DfO13cl z1dSOX4r1iapYjR-`RYvQTuAoGeh%H}073V5ih*cCU31j`5%*852e-Q*nb8JMPzPdU zH?$6jCA(avvEYVPv82HZHo%Xtw?1sRe)pjua1R?4M^FGe6i3iOHZaF(R@}ZjRj+3a z-)|;!4i_(Q50(v*aovO85v!%ij-5NF@dQZ`F&HY!oWKEpn^)Y$sfpBKW5c+ledOf@ zFWnCxi$IP$1ZKsm@0;CkO32)a{0lGLAu=}sTy>wi{>0 zQXj0)tQJ~!K?u>Ej;>t;0rJ&}%jFyy;sy6}wMbX(;d*$!$@#r(yd!pv75(OVaZzF5 zQtv}R+1Y^p-q(1!?lD_f(3+H(n#qEz0mY&_7NeGo47FS6<2vTnL@+lIv2R3lcn71n zk`A?SbyE>A-1t3yD?JyQ3rBpUBSPf@AhN#|<38mceO+wiEAD)gJ}$d9A^yn}<8Fbr z?I+) zDxhz{!@E+LvzHa*AoQHO_~|F@+jbI?tq?~P(1AJ}R?D;Z@fMQM1-YptbRk1b9{lodC7<%msq!EuHMAgp&til6 z??)tL3VH2|5Gsv`?M(|3zVRH$RQaMw6h$F#K92?C1AORlb?w}(yqJqcO0L-a3cnW5 z0_FW|j9kVvBCiB&>4r)gR4_dmj3;B$R$r@A&L&u7#wxRW)E*P1MG6HF)iATn6(v8! z#Nt_?^bEQKaojOdZ_xRNYA*S^)F>9|-5*Q*`@?GdUyBKN|$`{~GJ{vPDrztiY&@atJLEk~H{J}9E!y;w2KKyQW-ZuWG>xKLr>nY- zxAxehWt6(vLrj)PY9qf*eK)R(M65umIaFn*nxP2VlMLS!WTrZQ4&PtWql;33T9BZ zvF~d}Ufx`#_o^C$&}ACTC0cTQ3??N}xRR&R1(6jMforwg`78zmOi2i-XSCikcepTh zA2s9upCY#P?dpdr(!iSh;M*kk5mH=lfy~pF$Pq0gq_lrx+X-6a13s!En^0co2F3Oc z{2@-wiDt7Q1Oo9j@bJ}mC#@-yJ*kw8Q5iB&l5$Z^q_TMaiqQOepLI*Pyc=W53%LXj zLOjAm#yaJqs(Kb1--)M?FccF-0lCJ9smR;|NG;ohq>{Ni4BvB$V?@6PsT@Wo{CTK; zNl8T%AY60v)TnpiW{PbgX={guf2 z83 z{a;+@ilYYT7YC&((RnG=bDEtP$$m0P}6p-scqFy*mMkN9&_-@%B z@;y9P-BfcLYpit5x>^t!%4x3R23y?@o-8oTzx>4t!+g}64Tkw=0V@jRz~o+il_9{mf+0)KpkLT-aA2!L9?vKYzUf_d`73j)t>ssdvdkgluOzUoQkoK z2A}E3z*hvuz6W$jSFJ?-3?Qp$+!zAAaJUR=Gjw`Y5gDaU(#h2>`h|~tR8dRw#Y`36 z6Y4Z?MFduRMG?{cSdsb0dqSV?uMkXK%NUvpDPkpFzUm0#SNObKG1U)3z0p(w+LM~C zZI`XKTzzCo-O|xAKkHFs*fT9za4Uk$+k16^Dly30Z~o=#3`t3T862j@bxfOh^21Y- z)K8U@`r)aW`?<$QDz6S0|5xP!5F_P2+aziAZ~c`NvdSh7q3S4YZKm{;DDy-q-H^H~ z@QKrksTm~|rm7P#6VgpglRQMS6P?9#HhEYKMJBX&cXp}Ik6Sh6Dv9M{#I z`?DdUENGR%0`1B3lw$(*c_(2ahho|vtD#J7aZ#+-<)|5w-O$}CSO%v$0A*%piC#JK zacEN%h(nuRke4rmj?060v9Y^VUT^JN7R^~+~NLaFT;d1Oet z!bw5tst__iPga*IfKhywSb2ip3z~%__JmYFnS!xINq>Ce783iah8-Cqi=Uc{pJwC@ zqugft5IudEFn_hz3`tw{XAzPuMhR-X4w-ISIM(>8Hm)J1Gex(FvJhFRNLJ)7cpxfE z5)kpC5l4r3%^mVlnp}js8f+knHBYOzus^F5+Roac4y|fVNaA^@KM4m?BvXGdh(OXT z+o z2b`h1idQU_Q_=uObx9o6!c9pv1QSlaiE~bHD@_t^jsh+iErxLPeis zLts7kab=D1Nw8y&Z6rU4sA`-0qd(ItUm{RYzYZ~Z2wwT`rIJtK0&~JE; zjn{eWN2P=<_@lO4l<`cW``2*klq`)exC+UCIL|M(l)`}l2)K%fZO&_bA=GJ5c8UzQ z#zT6achrxGe(rb~Chw8TjZ+;{^+RX!(W}T}BOmlqeDMkNU3EssUX_GtA>NvE;iU;~ z{2ye84yi++j&24`*A+{)cVdH-6{lC`Eat`+c{b;3>eRp3{tmJ-6)$^%I*E~Hi*mC4 zw$wDAe9fut{HLtYzvr*Bz%Xk%%6DIlxxC!NEC6g4hgeaEn!S+)8e^~J9yS2Btj#P) zYescrN4cRWh6M^kRNsXSfK66!9}6^wU?kZ}w+32ERp&^9RA)5{REDhO9ad!j&Hk)u zok7eG=RSRADfKQBh%G0Q&7}|+HNd!$2BWCfRFGWA9HqDIB%4C@i3L*-XJvJmxOjAAcXx{M9iZ5`!$ zS=aDgAYb9WgvjdOVZ)7%_9n5(^i>^dJ4pBDX!0~WHU!@VtVn9E9&J@qtuCv9N2Kx`nh1d;^k5bfm0LJ!O=1PM46vJHmdvcmAj3CP2m&Anz59EcZ=n{)>>KOxFgU1;^ zDOEB>>UJB%qT{9R$x$}YCAa-DxOCjP($zP_jjw7Tt-2`S%gyqOIa2D9SnAFp;s)eMzUDqH)g8%EE}`mMQSdxWPJhmO?#KyvQvO~#s;Hr?He@A} z6%D0|lGxBtN}9)t3f83BVi7pf%HsE6_kq{gRJZXJbsO}V@N;zqXYPn0+8Kbt^E9qwCSZP<%E!XH4N5~6R9 z6NRwkVyR>}nq;BALm#gRf?HNZNCkqDGqMn(IERqfzl9hg|4FGBO^vHf6bTkigd1in zb%3a~mTY*hq;mrb1?O*o^`8d*KU~Wqqneac*Qf|)!i|2G&_d)(w^)8pxhfY<1xhqV zsQrG+f1rHVR-$%{ieyMS`MTOM>c4Hov?ppmNG6rA z!kH^Yds6)vVK&o%2vv}9I2rWahf1y_5OGqS_p}HXBoIYIj51rIOGyi_MC(4_`f+g6 zDS;X8d|KwyVz5X|Vp#I%L)kg1OE5G6=#G-|TiYr@}E>LfT7YDK${{DLYJ)75DV5$5V&8)Yd#1(c^*H z!>X)ptz1Trrm^zPd`~rlQxV)KQCMH*WNZYNz+WkU!8R3Wtc_bf(KG}<;=b{KSgs%_ zi>Glw)cob=-9DRnvG1%2B89tiQ=?f{5F{3jl+H&N2^+*)6{opO$qbS_e;wp5{b+5V zr+3@MNFXY_@XxOY4``2y%N=oKx>xIrcay>;9d`R{YPs9T+2DT8`0ZoIa(>NN-agez zLzDJ-9o*%EUv0MYe93yBBwp-^I-`aTY0w>gEX#en2yWo*W&r&=thP+D zI+d?wa6z=LU(3J9nSGkmq;q17i;=sFmqEdR=DL4(PIvPkGr@A}&EnEi+&A}=&6~NJ zM(T&TT+nLg)N~?DDtnT1$9Zm6#!ak(b(+F=C$}uiepvK)Ur>mFZk-0Zb(;G5I#_NG zh=teeSbOUpzx9=;rn!N~5@reiIVY7M->j-n28(wz%>^%z?&$X$oBh6$Py=jj=aQ>b& zWC;1z?Kd0d7N+fCSRufxWOefvF=;$s$)vWJRkC?^NXlO0m*kjwbu1W&o`?9t>kzAn z!bCX*$s|8yCyz3dqQ^z?3@_1(wM_S#HRWxK$cuHNWee}SOqgJ~-NQW66ZS}ZRCA8u zP6x?)^R8>cL`F3I+@6{4hdo;#JM;*UcC*&=YH=Kkx4CmVUh3fH8Bla@ z^8gLqdUJVu#0r;>t$VX4v+0f&X%+2`>4ZhQPd-fUgw^ z_^gE@0mYs)0b#D0MU$u1;R(3!c)oZgp@N=gfYh8{wS)oNp%?RLo+uBHrMWDg%}gf zXz)C%&YgpA^=|&?pe?ydY5)8y`!yq%&zcbX8sw+ZuaWvNpO44U(2eGCW{4e@4b=;k z-IDBFe<1GH&A+_N&gln~HVF2~2zb9#cw^APHoL8db%fWx{Hs_Zw5L@ABJRCo3HYtE zB73)vmc2}Mk@LJL`DMLg$;ffUyhBKooTVpslJcu>{`5`!AaX68sI?TAN_N{5x5+8X zuo$AHcB!<~^9=pCzp7%D0fJab2=R$4D9JaG$%42<#^S~>>DW zaq)L0B-1(oBwMIJGRepTc|6~iAh@Jkbu^ z+OveRz&C5n_Zm+O$17>GIrk_rXo>9PSR~LOg_v<3A8h16xPZo*=Y|LrB7)aos}T7Z zw6@=RPju?|Y4AMOrPV6fLMaN-xD*AI}{+7c_x^4OlB= zJIyFr&B+}-&t}||*ijCgata@`(#loaTZZkx1_&gsnAovr`oE_ic}zXp)TQ2VV)Z-C zg{#^Q`6X9-(bin=33cXgJvV*K^p-Csqg(eTl5-YZH+md#1wEfKWctn+-g_>k=SC+@*X$n4GWM@8SE*U)!@z#v+t$UXGhg=-gIWj_sgwfn#BmOH=5LVnH3OOZz z4?5JwurkfWZno>9$nfJfV;{;y$yYB-D67KQaUio0^;Wr`nT@Z1C_j=11XD~5B z;7@8Hk8NL?9$)9n)hxmKzT83<^c^;>o!+A-q`fq|L6RM**2u?=n|2sJq}MWJgty;p zlnZMek2SsT`}4vZqsMIpY}0ojLO+t^R~h#7!%_B} zlilh7B?~)z48+`nK8@_hhmc2qX#RcXkc4~0PPotx!wk-1O-j+D*(@8b2jJq#&q&V) z#?s@~-wqn8OQh+057#5*Dq&_>7P*X#<~n#8LBsVzy(ag?@>q^Lo-Xz8J-Tz`B@!`} zV~z{0+AY{lOKN$>0DAU5PQ$EZ{K ze^lI}{>NpLWOJH){0ZUIr1H-O97jNsB(_yBEQDlknEu5vC-{Dx7hA?4C9nOuF$Ri= zUHYsjCeHL8dxDSbb1Y~kt_VxT0Dya2(Li`qnDie!bgsO)TgPp^LxO{f%;MBZir5n? zalMxykVi-y1ABMN>@eQfX0U*WfvZUFL;?!j>3O&S2`>hw6)6_B195VQGA?@+a1Ya~ zl32q6u8xx+>BBg$0^e?%Gy)d;&K@aQ#jP9o`piM^R_){;1n^C&4XY-TTe`Wxp39$A zqRJ1R%+RHeZSzLF1x}SJ70U{gUPj9o2w#Pncy^%G5=e9PhdCy!T3Qf}UW(K`&@5qQ zsQtLCkV6}=Mf)JiFL;!qWnf*W!Aai35aEqhsV#ShYQM(MM-3GQAZ-u;48sLk1#K|t zCxhGE;W|j*Ic7+t%?>x}MYQXQ*kW317fbXLjA6@AMDEi&I;WRyzmN9bW4(VY`Uy&X zPWU#&q2o^Q^X<`vh``v%1S=#-vq1)lgg%%NfJ+?UUtk)IT2n>{=1A=e>6`kP z{iTh5Y0KFM`LoEcI!$}K209K%=T90zY4uwd2PW`If3=6>t%^HF^#80l`#;-aZe0rV zFV7x8s@55teV{V;V{9&GkDYr9FpncY6l-8PdmyuXv2Mq7_yTE_XzC*N(2PWUN-0_A zRxa3AZ!+0u5;c1;Jg_o|F8ru9lL)#TabZ<+n<#AM!^|CwK+r2LOj^*SGlUbMSdNNB zgt@E$$LdL)X2@g5ZmF=+sA|yZ8B!wynll>)S|oKiX8Kwd6lp>R~2MyoBt?9V=`Jh?L-wNVQg(0Y01d8#1%VG)zk<|q(impK~U9JQL>j^ z&%y`_ln<>Q)uB|y78JC<#wgBrK@i)4O;M%=tF>m*S}Rkxu;L)j3kBsU)iELQH<%_` zJ)Y#%x>C)^38Ike3c# z7}Wt+cbEQsp+*2fa+E+C<D*&&xO-HRkjdYR zO-N4yWjWQVZ2i;`RjrtX6$oyVWhG=3@t!X@#x;JI=!XGTBE&iS5?) zOoCPoY27kXY2hpnia%Q~g7~w<)%qvBT2>rhP)kOp|Ecu8di*<2b{Jx*%{QSmseOf< zzn3dn_*cCo4pYk@)zBxF3aI>`8a=#-O$*czVy=kc&y7)xBCAbQ9=`045>RT6A%+rb z%4$E!U0ID5YK~k_i-ZupE@{8TbMmHJ={?! zN`t!m_ojK7I7%hx0yzi=4tj#IBKgELa)JLisKp4dwI0@q%${`ZyK&W}x*J0c522zU z*Sk97NY^AXsc{?Lf;w%oIh_FIPB!>c2v>7a4z1{kFMP%{@|o=jh`$DMz`cX(xhTW| ziTt~QGgH)2EHs8JYs4oMYAyXx(Z74B*@rIRL8&CQL5{)~kJ*s8>~FccqCcXJng@yh zN;MdjN);f)wHuX+Ueo}<9*Tl{u)(Yd>V9IXB-NP4&E}omgU-;XyRJ@j7b>)CyOgZ5 zm0i+%CL3f$b4sP+IW^=PA{w_wPMo?^{MpY@eJI#+kE=}mtU46O3=x!rQHKC)&BRtJ z9cy)W6&sAoZxi~mL5m9SDgq8%k6rV*7k}xZE8EdES~-VgeQ+qW^sz~whc60IttcHR z^+L6x4x+M2QmbWu;Um!Hs!ZFXR6HECqRR8hBUcc&g35rZic?h$dpn#+yOJA(Dg&G~ zsj^mS15Gs$M@bpk)`TC3#$+b0v;9M}wzj=>@@!!PNsIRVx6bMrHFo0kL+*Ds_aS1= z>1){!u-t$Cr_GvKc0)HzINr`>a_hu>9X2-es|yEowmtoAqf@6-H&?71mTS(L?6A@5 zO~W=fo$E|SrzRR7m^5O3L~Gl~wl12ZIAD>u|1jvj8A6#3gdi$}pa`eC= z-s)|@y(ytE^W>RBj(A9KI`*?Yv|M}BC^!oF(6(U2+%BKXUX5tdX>Ygcu5hpEIJ7{$ z1KNlT`U3(X;c-g%hWVPm>-vsD^hX^3!?7bA>?G}NBkSIuIcVLXmy@+4jna4ntlJIi zY^;&6=<2oyTj7*CXUyh)+?_zH?iHen2mp2!F>OzGpVrprHO%G#5AyF;z3g?C?29dm!db)1*dYIhfL> zBcTR^q%{6ow}i-nJ8a>PVCDDtXw$cuD(-By#e`PC0KjK`oNm1vCh~XHICgVy$S7E{ z!JxnlEB#6j5tp3Ncj?nrh`0kbA|oJl3!J;|wPuPNVlKpmUp36v2OS?lYtIIDKI6D` z?lggi2b!v|O)5CYOPWNDn*w`usVPuRTPfRDk0~fhy_PSCK|FCh76;JoY-h=21DB6AtRpOJxC3iy5~bs$6K9aW(^7)_VNxN_&BEV=c_rf#wB<_~U4(|XOT5|CR(UPXzpo#z1B9^_j?P%54{wG|sxT;)rXA2bE-w3! zX0Lv;8cjtrpB&*ijYxlb2KK4h?l{=mpf`O|XBsXDn*!UEXhabM4xHP-{ihDcmV5(LcVyAS7gLhf`k&(ZIKZ0EY=IU`; zFcxj{(lxLoG=&*3g^v-`6cn~Lffo&gV91wgNe}uaI&3}+bXcfBhs3L}x}_a^`A#}N z)gtAWqc?j!nR8Cbw)_2~YTIus-FDy<-95^Nz|M{gbm_o90~?wD0&xE?mAQY?`QKhyxIJpfr&*7o zouOe^uyK09n@(>1Mw;i&y7}5eDt-z-BL+pxy&Cy+#ov4Tbvgec@T9VBFIKhfN9|Q{ zN}19jOA>gI?fTZ;P4n^PeOC0=B7Oi3YWVR=&GN&w&mTTF%MQsSh-PMPT}B%JZC#pG zG<({l2U7xVn)WR#^>BRjd(^Aldk3EK9$OlfW=F|K(l$HTlzTH=`xb6Elc`c zu5OKx?oiM(bi6JF(s3fmT~LzEPeThf|w)mV`pT8QnWVf<;N|&zq36y zA-jznkf`M2d3c>sA}hLwlrcWis)IYL(5ikahm7hB9J1}){-SMZ`^77zvxd)3G66%i z;&0;-UCsk(cDDyRft0kOf(+_zs=!%ap&=82@awzut?Nb`D~5W`84d1h>^2^?{uEM! zq3JfKiNT>opdrV&wG2ZVvcvezr_jWZVFZaqVno_fnBr(KjP0>ug#AYfm$aopZyrtP zg(+Kk$nUC#yqy3_u-*JYIqky+iHan5w*4E(bVF&y&YMc^*(uo}SBcz%uSn@8N_kY5@%sm6YhF4WDLv(e98oo7@d>wHF2f&gcs9}r$;R&Xd%6f>ut^$oE?p9p<_-jp zM#6{%VATbLDiV1Au6bV{#sREQLl-vq*KLKP-g&gQXJ+PK+&k-Sl!7&# z`(S2vk&|e$5_1|qQI(Q(3Q%EAH62t9nMo;$mAA6*=0tg&Idmpd7h@E^PIyYsRgZIiXWdd+& zq6z_cHbs>HR5_&e$jDv=PIsF$Hm@C)$bm8EPGi4@)NxROyFvzE1)LSLuCl+?q;)h1wVD_ z$#4uB^>)V>wwtFY8}6r?KVF#gKnb5molBerL{q{m7gTQid{w*xL);R!h3ZIGt!%Xc z2#?JM0HvURZvQ^U?RwNC?wfaaiWgwGolct#Iney^46*oi1%^PAPzIhKsB#u;pd;tYb)>9i#4`ni`D_Xx%x6jw zW>ws+dacTR5k?^1d(}QGIHh|BVUkAVem`xd#Ob0$arMj^=izY--Txlg@56gim;pS`lxl)zBZ{d(8_W?uL? zbI*2rJ}goA`?3=k97z-F-|1zYHu8bmi*gP*%}<6pvSDbKs)BE zE|3w5>TAp!_7M*uOyly$o2XYy-V`~VJR~a&airW%q%R6jKFf)6D3NA^@gNOi0p)Wj zF&<>F#vg(;N-X97$KJPqMOCeTTUO>Nv11qWf*do_QX?}pQJK=pjFQT{fr91*6OWgO9!;e*r7|UNnHNMwL`4|yM5bs8BPxuFiZbd5Is)U&?C*Wo+I!F1GkX)@%-Hw* z&;NP8?>WzzGqPvxb$QqC{ar{cCOb-9I=2V_uqLU$2-f5zMIMwCP;Liu{~C1!kRvRr#X6YZc4-w%it0=r&Z+qcb7AeEFu*Ekb#*%?+31sF zl^c$bKis`i((wEcp_`x$nv8$;IV`xLBrIU*Gp@X)$?>Wq6$dxTWil%YKQ= zg_<|+Snkrjq^K0o%Nj2T<-19<&iH6w0}hYWn_acz$wo8H=GPYS0k3@keYti~l%A|qk92Tn=h z)HeU1r~3uLtX5`{J7Kq*1%M?&GhpH)EH3=_C>^=Q%AT@5;ZfIb@4Ew)X9Ej>Q?bt% zUQ5&^mKMj56Xd2Li(r?#ir1@qR>H{+XyPMh^v9yJThZZI7Tu>{PwXiQYr+Q%a=H4( zO+N~ieubrH*}Jq;ur~PPv~Rq&Q$+KQ?=~n+Da6yyXWiZGhCzA)b>4X$4iFycoLu4^ z6?qzgt5yJmliQepbVEs+wkyUWb~tj%NlipLFff_m7gwyQNkd@%e7nm?#jOk+6gWG& zVv~a$am8N8tiO3J1Ds$#bWTXw$u~N}QZo_P0-%vLL4u)8R52dAWzlnLIcxAdeOz7m zn)PHyZLl>Yb@%fv_EQYkzwhYQZLs9C_L|?lFr$f1uE7)Sb3Ah6{wZ+BZ}%OnF}rK3 zP_ACvqg=1b?irtay><201C8Rp`Jf0(Ox)h@m}jhq-;2=Z+m;gM?Lh;`Y4m?_w-Hf2aeuJy71sE)l_@{zv=d5k+}xslXiIQqToeF}d>4R} zrb=LC&;|v36LB9INEB*_!3%8wov>v2c3j!+JQGaaB<_nz*P)w>S11wUF+eL3Cu$&9 zzvL)w{?-1dvE9=6j-i?E6VNdv@PBE)jj4n20*9@QlgWL_z9RGtvB(63T&Am9!)uy- zuS|Fd9!2k-oEnFfxaysdobmDBB*EV#8!dbdTOl9nVCzfbevS>Lw=~CPA6Z_9$MNEM|gVxXj9 z=-RC!O#HF1doR}pYQ&Q7Wb#pQvLGA`dxfid0P0Nqt722g4)})sQzQ_$?);Ff46M&L za(DUt=>PJRxScl^7&pP~q27WvoIsKx)wB+JpJFHep8BQ3Hxv)>30MD7l%Y+=vTbUL zI`7H4#=85@)8q8KE*|(JCEmtNeahgwp+93&9g$6FxC?!AE!^d&7lkZ6knWzdvQ_%ZPm}62soFQ^k2pH>i&+iXvGEX zRdN->lcWyRuexe=iK@KHI(CT?bx13K{c{oF)WpqA?Hpr$!}5{Jmwyo8B=rduFwU{D zX)vPcLLG`^oZ4f4c&#U0l3A*VrfPDIwk$Qzp3nbmu?}s~hO?o5l%hq;uDqCRYhhT% z7t5~@JlL^`kp3CpNwMy>FHwQ^B3^GCx`^aq;ML6i0C{H#SKwrWcB=j}lez9Cm`(%nyvvLd&z$Vj@5*W=7wH z4HaO~c-IhHA3LMHo}pD;Dh<@f3&rQ9Z(r(p{$>gR{3^0u<_0(yv3)D3om|lD<~XsBNl}-l5~B9>Nk0mdjNl3qYVV$pFV~97}3* zM)&=E&eB7PiGTtpsNdxaUAVcb@5CgBP#WJ{(|FPa2JSm;7Z64xfGrJoMRzAxghbQK@d>Wn&LtAwrlZ%TSbX(o~Fp=kVVJMWQ7X15=0fQRo3l4xQuJl zZE3rp4W|b6owL90`t?V0%(F*6Jbw4Q_JbcwUEDVL%gF3y+f|S8fK*~%?gr311Tl#s zQaVYoXj2^M0w7LeU!gna3vFp1l_g!<`>%ZHEWu0gicC7P{8BbB19P4Qeas4il!Cy+ z_TIDl0S6Jhrhhx9)6n$`U3bY#HMi}ds)xMeSCjYBnpC+<;7=y#gk zNC}p2aLrL@aD*D5*S+tFP9c4;Hwac3V3OO2`Zx?sNKw$XVeQD#O<`ZQP09VfPM%lDd6W& zM(FhN^-@MC`?8A+A|up*jL@1-k@@rS7F%GWC~QiJ)C?*sZ(F*9=emstjx@d-N3B_v zvs+$AQRTo9UaSsyu@yIR;f@OG0oc)ywDJ@_z)=Zj1-3|AlTjmbRy2gOqVU3#abp#~ z#p(?jZ%;mxp;cevxWKS+q{d9ql&E$Me7jBalE^Op);RAL+^u;7krw(_Qf`3d^MFC- z!RkqQvqB#SrWrQkC!r1z6h!{8%i6)9dkm=51d$L-wWY`om8)%)(bF|>w2(dXyspdq zEjP=68BDvF2Ov+RUWZbsboROHdcD0z|o!%M|gz_i>UC_>qw** zuq;q)nzSgq5olhec@(f}5^K?UR>D5+Sw<{}7gDV}J zm>ST|5kU*efygxnUVB^`gPe&5T$cl>zsB_%PMGv-7{B zVQqXuTme7?K?bcw&F|rFTTWaRy9;p299HVLDb-PC;V9g1mvpcTNJsz&vV7FcXh6*tTF za@|HzZ#Xk8vLlm>TCvD0Nj!?@8zn};393;LHnRt>RN!6hDoeX|1!7%-p4aYZMFta( zPPuM@_+4%x2-Be*jq`Gr!Lj$~;$h%|dP}E-%L^@slY?uO$LPB+5Q2iHhzhTi=$v#2v1q4NR?eXEemS}MW^8>_Z;gZTXjZwA7UeDoJz4w9?i)^-|rmypd z{hScVRH|j)KDC#=kz*4 z2@Tpl*Z0O>Sn>&6&dNOH@-Yc3DS6a12ybkovXSVC`d|1@!i?v1k!9plBj2_E$OCZ; z%9cTSJziS!P?=9a)$8g*0)vsyp>A~GJ5ZqDLI8la9hclQ;)cx@PvB4kl3Lv}>)*{Af*LH^~!EM<@>>d#J2d5PfdL+S)HjdvV z#6fcPiJB5CEwb{|?}P)S;L2SBfeML@4tMM_bCj%5LiACwsk#ISZ<2WV0yJj~f z#@Sv4*)CnbHc$-aW?av{+*HQ_dJWtV-la(juiCtm;5Ms7`BS=M)Cl#*f=aSQFr_AA zv*oheN5w4yC5kp9$d0z%1jUI0h^<+{Rmlm5r@4|$LD6MPT4>_EMCgsngHQxusabUa zKS<&>mZ-DcFK89PK&-AgJ3;k6zC4&)oRy)~0TKZgM;7DVj#hIaDI_b3si{)$v;nHr z{K((0=9pHc@QoNy53No?(M^fB3TqHMCTAS#n*sTRugX@F(ASU0d%fM)(5MMkiKh4> z`IIV=mL#ogP99Fs)59P9V|2hEw2fHafj5^UY)2l_6U9iB9D9@KeU(5O#U6npyqRMl z^{&7G2rpq-t}L$ry~K@xcp*fT>yP2U zOZ#N_E{<2x9iH+r@5p#_%Bx`3=macJZN+XKgLa$N9a+BlH*V=>H!Y2uX8ohU(ox}2 zLij+{>=}w|XtUGi1bGG}Sd($5blTO!ZijGx$I!Mfu2#PE)UZtfC{EwUu zU(vg|xIG}H0~DCxH3sDdO1rVPs){k;hBe_<7J)iFM4n6GD>as4Z`;q zQf;6NP;p&?Vxyw3dUI{#W0KX|48bAb*{SzbXP%ytoP5B8>ki80zx@B`(rxeB&N2Hg zWZ4^c|a9%JzX0ZOzHmu$>vT$*ti$wbSbi(3OsyS!@^N{ayX!u=E||Uj7+pSrkL=oY8_*5V_oy*pj=-#&~2>KQ*pHj{KYG98HN8sAAj`pu^3T5^S`n9KR6Z*rC1Fx zGy_V16I-4?i11UcoB&N!SHbKxk7$|w(9${01W=V=^o$_8FBDAaTYYNd1cacU3d zTBnnDL8RieKmc=iL$Ed`IW^zr)W}{b?s+$rIY4?K6_MqWVBOER?%YB$`rl*#TaDNL zHyNN1`=IDPOorii&)&$eVuh(gVC=#X>w4~~X-}{Cyy7Z0#=Dtsy}mJgZE)G~q}-h1 zwWO6!%Iuft#_?ZOlCEu&@N5#hiJogJ0L)c_ZC0T5RV{Gt z@fimMU&6<^%+Jh~@Mhx7vk5ttzm%HR0^*#+z0t?oa12mZ1s^2|a$5)xXB1CS8D&=dA`b~ z0b$`xie6pG7#VpE?NiyKlRH@{W{nU{RgDSGGUv$&0{jbJTVNcN|Ku~di1`8;nJ73DdV5k<{}eIx*tH)Mj?I>rL1N~nPvlo-KELPd<6Q@rd-!uS$Jkk7FQ zH`7@)WpxhAH&!sbZ}2dx#~dqCouES0?aAr zM(%#g)soToDG*x=3GeXqOqZj)pvU_VY6RkmW)X`Y#x;ep;r zf(g?}^=`Gi0jPDvh5bCwGkCTbT!fBJUR_$qIDq$gKn6yok}z8Lf;f5RyA>lT^qgB8?~rIXqFE#0wwKeQkrDyMCvQ= zfdOg?M>23tjWE$5Swi88xAAg3iNF$#ZQ^b>*FV__@MdCnNeyCUI;YOE582T(8SnN& zQwf{S@C-spz+U?mt5O9=%WB()49pgj?4aw01}0!KB-|Fnk5K5XBrPI&da`n}>W6iN zJjSvcspq_2uIF6Sp9`yB;VZuOGZIbRhHZcP8jJe(PQS`J;%s2mkqwLceylry=gxZwnuQ=+W6~D zR!rjtdv$wjogHx!0ZFvP)|}l%UFmSCEk)s=cx}P{yNly|98Qd$zN{Km@&s<%AGoon z@AojM-fzlC%%qlAF0!|DFk0HA8gPTrUrHZB(mZk5!Kqb0>h^IMem5@0VDy@{yF5^} zKz&7}X)z~Dol#^8*w@~Fz-)~dn8uv+2d~cD=xH0VjDpyqhdtmUAvg2%^IpR?VsPfd zqi7c|1{KY{L{#m*=sG_#inz;w7Jd`t8a?fhYXqeLw|tQf!;45nWJZs?=4i`(A<^?x zSv|rPP3J9qAcJ$_t3o!S3-VO$td%AVEiPdb0qNn{Hn{B3+Zg#O35gU^8*E*8p1WPs zx)MWq0ZSz21~d{dZ*Q4FGh#S6w!mj#F1l%!-(jr=f(a9&ARuwBDW6d(yVgxe+y5G? zr{Zla*Z-ke+Z@=UkZB1%mO^?FjT0nss-zEJ`|KLgSSjbY$I?SaRRA!aiB%;TDiRj? zk|t)!7-B{$WWjZ{3^Q)OOQIiDG6C>;=1$vC$`=y)T9AQJ@b-tqf!XCehZudDK zA5S8|QBY-zQexN5bOommxXy`;H?iYJ`ULcLZzm;y#<<%}MMW=- z$XJ8^ffPx!DMx0TU1{cNyg224-#A)a^}7Exre@PByHkUilWb$4rrQ9t!sNdKwUtzb ztKNH5+#rZ$p&Q&hgNAm?02nhK@d!AOCQL4(}VHqUTy#+~T zrzBB8F~|2^N~4w@r`>lT`~m(An*j*z_IeoyHu3-*7#R)sWUudd|IoaUg8oA!j+{Be zv?U$K1404CmAKQ9*G6M$9dgIzO9x`VURAY04F`X!1JzaIGw=fiBX9&bpCVy2s}3#q zra^D4c{~Z?c13-qxv)!IDRd(yuI=30p-f7m3(5*}++mvo@DA(8CibKNhAXYG)+YDx zr%}O_ZNT=9 z5?grCA+lSg7i%zKyOFIuWD+B3T8wBHUgCwk3}dmZGbgrA72}PdV3T17%A*|)mf