From 77f6d67d84291a0ead3d3cb71a8f97ed8c3a1a52 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Fri, 17 Nov 2023 11:39:51 +0100 Subject: [PATCH 01/23] 6x6 spring element stiffness (symmetric) --- modules/subdyn/src/FEM.f90 | 161 +++++++++++++++++++++++++++++++++++++ 1 file changed, 161 insertions(+) diff --git a/modules/subdyn/src/FEM.f90 b/modules/subdyn/src/FEM.f90 index 0fe0376f29..5c68ddbd03 100644 --- a/modules/subdyn/src/FEM.f90 +++ b/modules/subdyn/src/FEM.f90 @@ -1157,6 +1157,167 @@ SUBROUTINE ElemK_Cable(A, L, E, T0, DirCos, K) K = MATMUL( MATMUL(DC, K), TRANSPOSE(DC) ) ! TODO: change me if DirCos convention is transposed END SUBROUTINE ElemK_Cable !------------------------------------------------------------------------------------------------------ +!> Element stiffness matrix for spring +!! The spring element can include diagnal and cross-coupling positions. +!! Assuming that the stiffness is symmetric (21 stiffness coefficients). The stiffness matrix could also be non-symmetric, if desired. +SUBROUTINE ElemK_Spring(k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66, DirCos, K) + REAL(ReKi), INTENT( IN) :: k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66 + REAL(FEKi), INTENT( IN) :: DirCos(3,3) !< From element to global: xg = DC.xe, Kg = DC.Ke.DC^t + REAL(FEKi), INTENT(OUT) :: K(12, 12) + ! Local variables + REAL(FEKi) :: DC(12, 12) + + K(1:12,1:12) = 0.0_FEKi + + K( 1, 1) = k11 + K( 1, 7) = -K(1,1) + K( 7, 1) = -K(1,1) + K( 7, 7) = K(1,1) + + K( 1, 2) = k12 + K( 1, 8) = -K(1,2) + K( 7, 2) = -K(1,2) + K( 7, 8) = K(1,2) + + K( 1, 3) = k13 + K( 1, 9) = -K(1,3) + K( 7, 3) = -K(1,3) + K( 7, 9) = K(1,3) + + K( 1, 4) = k14 + K( 1, 10) = -K(1,4) + K( 7, 4) = -K(1,4) + K( 7, 10) = K(1,4) + + K( 1, 5) = k15 + K( 1, 11) = -K(1,5) + K( 7, 5) = -K(1,5) + K( 7, 11) = K(1,5) + + K( 1, 6) = k16 + K( 1, 12) = -K(1,6) + K( 7, 6) = -K(1,6) + K( 7, 12) = K(1,6) + + K( 2, 2) = k22 + K( 2, 8) = -K(2,2) + K( 8, 2) = -K(2,2) + K( 8, 8) = K(2,2) + + K( 2, 3) = k23 + K( 2, 9) = -K(2,3) + K( 8, 3) = -K(2,3) + K( 8, 9) = K(2,3) + + K( 2, 4) = k24 + K( 2, 10) = -K(2,4) + K( 8, 4) = -K(2,4) + K( 8, 10) = K(2,4) + + K( 2, 5) = k25 + K( 2, 11) = -K(2,5) + K( 8, 5) = -K(2,5) + K( 8, 11) = K(2,5) + + K( 2, 6) = k26 + K( 2, 12) = -K(2,6) + K( 8, 6) = -K(2,6) + K( 8, 12) = K(2,6) + + K( 3, 3) = k33 + K( 3, 9) = -K(3,3) + K( 9, 3) = -K(3,3) + K( 9, 9) = K(3,3) + + K( 3, 4) = k34 + K( 3, 10) = -K(3,4) + K( 9, 4) = -K(3,4) + K( 9, 10) = K(3,4) + + K( 3, 5) = k35 + K( 3, 11) = -K(3,5) + K( 9, 5) = -K(3,5) + K( 9, 11) = K(3,5) + + K( 3, 6) = k36 + K( 3, 12) = -K(3,6) + K( 9, 6) = -K(3,6) + K( 9, 12) = K(3,6) + + K( 4, 4) = k44 + K( 4, 10) = -K(4,4) + K(10, 4) = -K(4,4) + K(10, 10) = K(4,4) + + K( 4, 5) = k45 + K( 4, 11) = -K(4,5) + K(10, 5) = -K(4,5) + K(10, 11) = K(4,5) + + K( 4, 6) = k46 + K( 4, 12) = -K(4,6) + K(10, 6) = -K(4,6) + K(10, 12) = K(4,6) + + K( 5, 5) = k55 + K( 5, 11) = -K(5,5) + K(11, 5) = -K(5,5) + K(11, 11) = K(5,5) + + K( 5, 6) = k56 + K( 5, 12) = -K(5,6) + K(11, 6) = -K(5,6) + K(11, 12) = K(5,6) + + K( 6, 6) = k66 + K( 6, 12) = -K(6,6) + K(12, 6) = -K(6,6) + K(12, 12) = K(6,6) + + ! Stiffness matrix symmetry: + K(2:6, 1) = K(1,2:6) + K(2:6, 7) = K(1,8:12) + K(8:12, 1) = K(7,2:6) + K(8:12, 7) = K(7,8:12) + + K(3:6, 2) = K(2,3:6) + K(3:6, 8) = K(2,9:12) + K(9:12, 2) = K(8,3:6) + K(9:12, 8) = K(8,9:12) + + K(4:6, 3) = K(3,4:6) + K(4:6, 9) = K(3,10:12) + K(10:12, 3) = K(9,4:6) + K(10:12, 9) = K(9,10:12) + + K(5:6, 4) = K(4,5:6) + K(5:6, 10) = K(4,11:12) + K(11:12, 4) = K(10,5:6) + K(11:12, 10) = K(10,11:12) + + K(6, 5) = K(5,6) + K(6, 11) = K(5,12) + K(12, 5) = K(11,6) + K(12, 11) = K(11,12) + + ! Temporary check. Looking at the spring element matrix (local coordinate system). + print*,'Spring element stiffness (local coordinate system)' + print*, K + + DC = 0.0_FEKi + DC( 1: 3, 1: 3) = DirCos + DC( 4: 6, 4: 6) = DirCos + DC( 7: 9, 7: 9) = DirCos + DC(10:12, 10:12) = DirCos + + K = MATMUL( MATMUL(DC, K), TRANSPOSE(DC) ) ! TODO: change me if DirCos convention is transposed + + ! Temporary check. Looking at the spring element matrix (global coordinate system). + print*,'Spring element stiffness (global coordinate system)' + print*, K + +END SUBROUTINE ElemK_Spring +!------------------------------------------------------------------------------------------------------ !> Element mass matrix for classical beam elements SUBROUTINE ElemM_Beam(A, L, Ixx, Iyy, Jzz, rho, DirCos, M) REAL(ReKi), INTENT( IN) :: A, L, Ixx, Iyy, Jzz, rho From 2781cfc697bc3862096cc949a30dc870eb234cc9 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Fri, 17 Nov 2023 11:49:14 +0100 Subject: [PATCH 02/23] SubDyn Registry with spring element --- modules/subdyn/src/SubDyn_Registry.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/modules/subdyn/src/SubDyn_Registry.txt b/modules/subdyn/src/SubDyn_Registry.txt index 0287f2ab96..064bb8cf06 100644 --- a/modules/subdyn/src/SubDyn_Registry.txt +++ b/modules/subdyn/src/SubDyn_Registry.txt @@ -81,6 +81,7 @@ typedef ^ SD_InitType INTEGER NPropSetsX - - - "Number of typedef ^ SD_InitType INTEGER NPropSetsB - - - "Number of property sets for beams" typedef ^ SD_InitType INTEGER NPropSetsC - - - "Number of property sets for cables" typedef ^ SD_InitType INTEGER NPropSetsR - - - "Number of property sets for rigid links" +typedef ^ SD_InitType INTEGER NPropSetsS - - - "Number of property sets for spring elements" typedef ^ SD_InitType INTEGER NCMass - - - "Number of joints with concentrated mass" typedef ^ SD_InitType INTEGER NCOSMs - - - "Number of independent cosine matrices" typedef ^ SD_InitType INTEGER FEMMod - - - "FEM switch element model in the FEM" @@ -90,6 +91,7 @@ typedef ^ SD_InitType ReKi Joints {:}{:} - - "Joints nu typedef ^ SD_InitType ReKi PropSetsB {:}{:} - - "Property sets number and values" typedef ^ SD_InitType ReKi PropSetsC {:}{:} - - "Property ID and values for cables" typedef ^ SD_InitType ReKi PropSetsR {:}{:} - - "Property ID and values for rigid link" +typedef ^ SD_InitType ReKi PropSetsS {:}{:} - - "Property ID and values for spring element" typedef ^ SD_InitType ReKi PropSetsX {:}{:} - - "Extended property sets" typedef ^ SD_InitType R8Ki COSMs {:}{:} - - "Independent direction cosine matrices" typedef ^ SD_InitType ReKi CMass {:}{:} - - "Concentrated mass information" @@ -111,10 +113,12 @@ typedef ^ SD_InitType INTEGER NElem - - - "Total num typedef ^ SD_InitType INTEGER NPropB - - - "Total number of property sets for Beams" typedef ^ SD_InitType INTEGER NPropC - - - "Total number of property sets for Cable" typedef ^ SD_InitType INTEGER NPropR - - - "Total number of property sets for Rigid" +typedef ^ SD_InitType INTEGER NPropS - - - "Total number of property sets for Spring" typedef ^ SD_InitType ReKi Nodes {:}{:} - - "Nodes number and coordinates " typedef ^ SD_InitType ReKi PropsB {:}{:} - - "Property sets and values for Beams " typedef ^ SD_InitType ReKi PropsC {:}{:} - - "Property sets and values for Cable " typedef ^ SD_InitType ReKi PropsR {:}{:} - - "Property sets and values for Rigid link" +typedef ^ SD_InitType ReKi PropsS {:}{:} - - "Property sets and values for Spring " typedef ^ SD_InitType R8Ki K {:}{:} - - "System stiffness matrix " typedef ^ SD_InitType R8Ki M {:}{:} - - "System mass matrix " typedef ^ SD_InitType ReKi ElemProps {:}{:} - - "Element properties(A, L, Ixx, Iyy, Jzz, Shear, Kappa, E, G, Rho, DirCos(1,1), DirCos(2, 1), ....., DirCos(3, 3) )" From 81cb349b40eb3b4a0158bbf9d60c59c29ff7ee08 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Fri, 17 Nov 2023 12:52:34 +0100 Subject: [PATCH 03/23] Spring element --- modules/subdyn/src/SD_FEM.f90 | 69 +++++++++++++++++++++++++++++------ modules/subdyn/src/SubDyn.f90 | 22 ++++++++++- 2 files changed, 77 insertions(+), 14 deletions(-) diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index 7d300e83bb..992f9f20d2 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -37,6 +37,7 @@ MODULE SD_FEM INTEGER(IntKi), PARAMETER :: PropSetsXCol = 10 ! Number of columns in XPropSets (PropSetID,YoungE,ShearG,MatDens,XsecA,XsecAsx,XsecAsy,XsecJxx,XsecJyy,XsecJ0) INTEGER(IntKi), PARAMETER :: PropSetsCCol = 5 ! Number of columns in CablePropSet (PropSetID, EA, MatDens, T0) INTEGER(IntKi), PARAMETER :: PropSetsRCol = 2 ! Number of columns in RigidPropSet (PropSetID, MatDens) + INTEGER(IntKi), PARAMETER :: PropSetsSCol = 22 ! Number of columns in SpringPropSet (PropSetID, k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66, COSMID) INTEGER(IntKi), PARAMETER :: COSMsCol = 10 ! Number of columns in (cosine matrices) COSMs (COSMID,COSM11,COSM12,COSM13,COSM21,COSM22,COSM23,COSM31,COSM32,COSM33) INTEGER(IntKi), PARAMETER :: CMassCol = 11 ! Number of columns in Concentrated Mass (CMJointID,JMass,JMXX,JMYY,JMZZ, Optional:JMXY,JMXZ,JMYZ,CGX,CGY,CGZ) ! Indices in Members table @@ -60,6 +61,7 @@ MODULE SD_FEM INTEGER(IntKi), PARAMETER :: idMemberCable = 2 INTEGER(IntKi), PARAMETER :: idMemberRigid = 3 INTEGER(IntKi), PARAMETER :: idMemberBeamArb = 4 + INTEGER(IntKi), PARAMETER :: idMemberSpring = 5 ! Types of Boundary Conditions INTEGER(IntKi), PARAMETER :: idBC_Fixed = 11 ! Fixed BC @@ -374,7 +376,7 @@ SUBROUTINE SD_ReIndex_CreateNodesAndElems(Init,p, ErrStat, ErrMsg) ! Check that rigid links are not connected to the interface iInterf = FINDLOCI(p%Nodes_I(:,1), iJoint ) if (iInterf>=1) then - CALL WrScr('[WARNING] There might be a bug when rigid links are connected to the interface nodes (mostly if cables are involved). The problematic member is MemberID='//TRIM(Num2LStr(mID))//' (which is a rigid link) involving joint JointID='// TRIM(Num2LStr(JointID))// ' (which is in an interface joint).') + CALL WrScr('[WARNING] There might be a bug when one beam and one rigid link are connected to the interface nodes. The problematic member might be MemberID='//TRIM(Num2LStr(mID))//' (which is a rigid link) involving joint JointID='// TRIM(Num2LStr(JointID))// ' (which is in an interface joint).') endif endif enddo @@ -394,6 +396,9 @@ SUBROUTINE SD_ReIndex_CreateNodesAndElems(Init,p, ErrStat, ErrMsg) else if (mType==idMemberBeamArb) then sType='Member arbitrary cross-section property' p%Elems(iMem,n) = FINDLOCI(Init%PropSetsX(:,1), Init%Members(iMem, n) ) + else if (mType==idMemberSpring) then + sType='Spring property' + p%Elems(iMem,n) = FINDLOCI(Init%PropSetsS(:,1), Init%Members(iMem, n) ) else ! Should not happen print*,'Element type unknown',mType @@ -403,7 +408,7 @@ SUBROUTINE SD_ReIndex_CreateNodesAndElems(Init,p, ErrStat, ErrMsg) if (mType/=idMemberBeamCirc) then if (Init%Members(iMem, iMProp)/=Init%Members(iMem, iMProp+1)) then ! NOTE: for non circular beams, we could just check that E, rho, G are the same for both properties - call Fatal('Property IDs should be the same at both joints for arbitrary beams, rigid links, and cables. Check member with ID: '//TRIM(Num2LStr(Init%Members(iMem,1)))) + call Fatal('Property IDs should be the same at both joints for arbitrary beams, rigid links, cables, and springs. Check member with ID: '//TRIM(Num2LStr(Init%Members(iMem,1)))) return endif endif @@ -454,7 +459,7 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) INTEGER :: iDirCos REAL(ReKi) :: x1, y1, z1, x2, y2, z2, dx, dy, dz, dd, dt, d1, d2, t1, t2 LOGICAL :: CreateNewProp - INTEGER(IntKi) :: nMemberCable, nMemberRigid, nMemberBeamCirc, nMemberBeamArb !< Number of memebers per type + INTEGER(IntKi) :: nMemberCable, nMemberRigid, nMemberSpring, nMemberBeamCirc, nMemberBeamArb !< Number of members per type INTEGER(IntKi) :: eType !< Element Type INTEGER(IntKi) :: ErrStat2 CHARACTER(ErrMsgLen) :: ErrMsg2 @@ -473,9 +478,10 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) nMemberCable = count(Init%Members(:,iMType) == idMemberCable) nMemberRigid = count(Init%Members(:,iMType) == idMemberRigid) nMemberBeamArb = count(Init%Members(:,iMType) == idMemberBeamArb) - Init%NElem = (nMemberBeamCirc + nMemberBeamArb)*Init%NDiv + nMemberCable + nMemberRigid ! NOTE: only Beams are divided - IF ( (nMemberBeamCirc+nMemberRigid+nMemberCable+nMemberBeamArb) /= size(Init%Members,1)) then - CALL Fatal(' Member list contains an element which is not a beam, a cable or a rigid link'); return + nMemberSpring = count(Init%Members(:,iMType) == idMemberSpring) + Init%NElem = (nMemberBeamCirc + nMemberBeamArb)*Init%NDiv + nMemberCable + nMemberRigid + nMemberSpring ! NOTE: only Beams are divided + IF ( (nMemberBeamCirc+nMemberRigid+nMemberCable+nMemberBeamArb+nMemberSpring) /= size(Init%Members,1)) then + CALL Fatal(' Member list contains an element which is not a beam, a cable, a rigid link or a spring'); return ENDIF ! Total number of nodes - Depends on division and number of nodes per element @@ -569,8 +575,8 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) eType = TempMembers(I, iMType ) iDirCos = TempMembers(I, iMDirCosID) - if (eType==idMemberRigid .OR. eType==idMemberCable) then - ! --- Cables and rigid links are not subdivided and have same prop at nodes + if (eType==idMemberRigid .OR. eType==idMemberCable .OR. eType==idMemberSpring) then + ! --- Cables, rigid links and springs are not subdivided and have same prop at nodes ! No need to create new properties or new nodes Init%MemberNodes(I, 1) = Node1 Init%MemberNodes(I, 2) = Node2 @@ -681,14 +687,17 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) Init%PropsB(1:Init%NPropB, 1:PropSetsBCol) = TempProps(1:Init%NPropB, 1:PropSetsBCol) endif - ! --- Cables and rigid link properties (these cannot be subdivided, so direct copy of inputs) + ! --- Cables, rigid link and spring properties (these cannot be subdivided, so direct copy of inputs) Init%NPropC = Init%NPropSetsC Init%NPropR = Init%NPropSetsR + Init%NPropS = Init%NPropSetsS CALL AllocAry(Init%PropsC, Init%NPropC, PropSetsCCol, 'Init%PropsCable', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropsR, Init%NPropR, PropSetsRCol, 'Init%PropsRigid', ErrStat2, ErrMsg2); if(Failed()) return - Init%PropsC(1:Init%NPropC, 1:PropSetsCCol) = Init%PropSetsC(1:Init%NPropC, 1:PropSetsCCol) + CALL AllocAry(Init%PropsS, Init%NPropS, PropSetsSCol, 'Init%PropsSpring', ErrStat2, ErrMsg2); if(Failed()) return + Init%PropsC(1:Init%NPropC, 1:PropSetsCCol) = Init%PropSetsC(1:Init%NPropC, 1:PropSetsCCol) Init%PropsR(1:Init%NPropR, 1:PropSetsRCol) = Init%PropSetsR(1:Init%NPropR, 1:PropSetsRCol) - + Init%PropsS(1:Init%NPropS, 1:PropSetsSCol) = Init%PropSetsS(1:Init%NPropS, 1:PropSetsSCol) + CALL CleanUp_Discrt() CONTAINS @@ -982,6 +991,32 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) p%ElemProps(i)%Rho = Init%PropsR(P1, 2) p%ElemProps(i)%D = min(sqrt(1/Pi)*4, L*0.05) ! For plotting only + else if (eType==idMemberSpring) then + if (DEV_VERSION) then + print*,'Member',I,'is a spring element' + endif + p%ElemProps(i)%k11 = Init%PropsS(P1, 2) + p%ElemProps(i)%k12 = Init%PropsS(P1, 3) + p%ElemProps(i)%k13 = Init%PropsS(P1, 4) + p%ElemProps(i)%k14 = Init%PropsS(P1, 5) + p%ElemProps(i)%k15 = Init%PropsS(P1, 6) + p%ElemProps(i)%k16 = Init%PropsS(P1, 7) + p%ElemProps(i)%k22 = Init%PropsS(P1, 8) + p%ElemProps(i)%k23 = Init%PropsS(P1, 9) + p%ElemProps(i)%k24 = Init%PropsS(P1,10) + p%ElemProps(i)%k25 = Init%PropsS(P1,11) + p%ElemProps(i)%k26 = Init%PropsS(P1,12) + p%ElemProps(i)%k33 = Init%PropsS(P1,13) + p%ElemProps(i)%k34 = Init%PropsS(P1,14) + p%ElemProps(i)%k35 = Init%PropsS(P1,15) + p%ElemProps(i)%k36 = Init%PropsS(P1,16) + p%ElemProps(i)%k44 = Init%PropsS(P1,17) + p%ElemProps(i)%k45 = Init%PropsS(P1,18) + p%ElemProps(i)%k46 = Init%PropsS(P1,19) + p%ElemProps(i)%k55 = Init%PropsS(P1,20) + p%ElemProps(i)%k56 = Init%PropsS(P1,21) + p%ElemProps(i)%k66 = Init%PropsS(P1,22) + else ! Should not happen print*,'Element type unknown',eType @@ -2283,7 +2318,11 @@ SUBROUTINE ElemM(ep, Me) CALL ElemM_Cable(ep%Area, real(ep%Length,FEKi), ep%rho, ep%DirCos, Me) !CALL ElemM_(A, L, rho, DirCos, Me) endif - endif + + else if (ep%eType==idMemberSpring) then + Me=0.0_FEKi ! Spring element has no mass associated. Consider using a lumped mass at JointID, if desired. + endif + END SUBROUTINE ElemM SUBROUTINE ElemK(ep, Ke) @@ -2298,6 +2337,10 @@ SUBROUTINE ElemK(ep, Ke) else if (ep%eType==idMemberRigid) then Ke = 0.0_FEKi + + else if (ep%eType==idMemberSpring) then + CALL ElemK_Spring(eP%k11, eP%k12, eP%k13, eP%k14, eP%k15, eP%k16, eP%k22, eP%k23, eP%k24, eP%k25, eP%k26, eP%k33, eP%k34, eP%k35, eP%k36, eP%k44, eP%k45, eP%k46, eP%k55, eP%k56, eP%k66, Ke) + endif END SUBROUTINE ElemK @@ -2312,6 +2355,8 @@ SUBROUTINE ElemF(ep, gravity, Fg, Fo) CALL ElemF_Cable(ep%T0, ep%DirCos, Fo) else if (ep%eType==idMemberRigid) then Fo(1:12)=0.0_FEKi + else if (ep%eType==idMemberSpring) then + Fo(1:12)=0.0_FEKi endif CALL ElemG( eP%Area, eP%Length, eP%rho, eP%DirCos, Fg, gravity ) END SUBROUTINE ElemF diff --git a/modules/subdyn/src/SubDyn.f90 b/modules/subdyn/src/SubDyn.f90 index 1258379d05..855cce8d49 100644 --- a/modules/subdyn/src/SubDyn.f90 +++ b/modules/subdyn/src/SubDyn.f90 @@ -222,7 +222,7 @@ SUBROUTINE SD_Init( InitInput, u, p, x, xd, z, OtherState, y, m, Interval, InitO ! %RefOrientation is the identity matrix (3,3,N) ! %Position is the reference position (3,N) ! Maybe some logic to make sure these points correspond roughly to nodes -- though this may not be true for a long pile into the soil with multiple connection points - ! Note: F = -kx whre k is the relevant 6x6 matrix from SoilStiffness + ! Note: F = -kx where k is the relevant 6x6 matrix from SoilStiffness call AllocAry(Init%Soil_K, 6,6, size(InitInput%SoilStiffness,3), 'Soil_K', ErrStat2, ErrMsg2); call AllocAry(Init%Soil_Points, 3, InitInput%SoilMesh%NNodes, 'Soil_Points', ErrStat2, ErrMsg2); call AllocAry(Init%Soil_Nodes, InitInput%SoilMesh%NNodes, 'Soil_Nodes' , ErrStat2, ErrMsg2); @@ -1173,7 +1173,7 @@ SUBROUTINE SD_Input(SDInputFile, Init, p, ErrStat,ErrMsg) CALL ReadCAryFromStr ( Line, StrArray, nColumns, 'Members', 'First line of members array', ErrStat2, ErrMsg2 ); if(Failed()) return call LegacyWarning('Member table contains 6 columns instead of 7, using default member directional cosines ID (-1) for all members. & &The directional cosines will be computed based on the member nodes for all members.') - Init%Members(:,7) = -1 + Init%Members(:,7) = -1 ! For the spring element, we need the direction cosine from the user. Both JointIDs are coincident, the direction cosine cannot be determined. endif ! Extract fields from first line DO I = 1, nColumns @@ -1250,11 +1250,23 @@ SUBROUTINE SD_Input(SDInputFile, Init, p, ErrStat,ErrMsg) CALL ReadAry( UnIn, SDInputFile, Init%PropSetsR(I,:), PropSetsRCol, 'RigidPropSets', 'RigidPropSets ID and values ', ErrStat2, ErrMsg2, UnEc ); if(Failed()) return ENDDO IF (Check( Init%NPropSetsR < 0, 'NPropSetsRigid must be >=0')) return + !----------------------- SPRING ELEMENT PROPERTIES -------------------------------- + CALL ReadCom ( UnIn, SDInputFile, 'Spring element properties' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + CALL ReadIVar ( UnIn, SDInputFile, Init%NPropSetsS, 'NPropSetsS', 'Number of spring properties' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + CALL ReadCom ( UnIn, SDInputFile, 'Spring element properties Header' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + CALL ReadCom ( UnIn, SDInputFile, 'Spring element properties Unit ' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'SpringPropSets', ErrStat2, ErrMsg2); if(Failed()) return + DO I = 1, Init%NPropSetsS + CALL ReadAry( UnIn, SDInputFile, Init%PropSetsS(I,:), PropSetsSCol, 'SpringPropSets', 'SpringPropSets ID and values ', ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + ENDDO + IF (Check( Init%NPropSetsS < 0, 'NPropSetsSpring must be >=0')) return else Init%NPropSetsC=0 Init%NPropSetsR=0 + Init%NPropSetsS=0 CALL AllocAry(Init%PropSetsC, Init%NPropSetsC, PropSetsCCol, 'PropSetsC', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropSetsR, Init%NPropSetsR, PropSetsRCol, 'RigidPropSets', ErrStat2, ErrMsg2); if(Failed()) return + CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'SpringPropSets', ErrStat2, ErrMsg2); if(Failed()) return endif !---------------------- MEMBER COSINE MATRICES COSM(i,j) ------------------------ @@ -3789,6 +3801,12 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E mMass= Init%PropSetsR(iProp(1),2) * mLength ! rho [kg/m] * L WRITE(UnSum, '("#",I9,I10,I10,I10,I10,ES15.6E2,ES15.6E2, A3,2(I6),A)') Init%Members(i,1:3),propIDs(1),propIDs(2),& mMass,mLength,' ',(Init%MemberNodes(i, j), j = 1, 2), ' # Rigid link' + else if (mType==idMemberSpring) then + iProp(1) = FINDLOCI(Init%PropSetsS(:,1), propIDs(1)) + mMass= 0.0 ! Spring element has no mass + mLength = 0.0 ! Spring element has no length. Both JointIDs must be coincident. + WRITE(UnSum, '("#",I9,I10,I10,I10,I10,ES15.6E2,ES15.6E2, A3,2(I6),A)') Init%Members(i,1:3),propIDs(1),propIDs(2),& + mMass,mLength,' ',(Init%MemberNodes(i, j), j = 1, 2), ' # Spring element' else if (mType==idMemberBeamArb) then iProp(1) = FINDLOCI(Init%PropSetsX(:,1), propIDs(1)) iProp(2) = FINDLOCI(Init%PropSetsX(:,1), propIDs(2)) From 4cdcfeb34009f93a44cd78104e9a731e08e50c71 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Fri, 17 Nov 2023 12:55:43 +0100 Subject: [PATCH 04/23] Fix typo --- modules/subdyn/src/SD_FEM.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index 992f9f20d2..24d1aa0c2c 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -37,7 +37,7 @@ MODULE SD_FEM INTEGER(IntKi), PARAMETER :: PropSetsXCol = 10 ! Number of columns in XPropSets (PropSetID,YoungE,ShearG,MatDens,XsecA,XsecAsx,XsecAsy,XsecJxx,XsecJyy,XsecJ0) INTEGER(IntKi), PARAMETER :: PropSetsCCol = 5 ! Number of columns in CablePropSet (PropSetID, EA, MatDens, T0) INTEGER(IntKi), PARAMETER :: PropSetsRCol = 2 ! Number of columns in RigidPropSet (PropSetID, MatDens) - INTEGER(IntKi), PARAMETER :: PropSetsSCol = 22 ! Number of columns in SpringPropSet (PropSetID, k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66, COSMID) + INTEGER(IntKi), PARAMETER :: PropSetsSCol = 22 ! Number of columns in SpringPropSet (PropSetID, k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66) INTEGER(IntKi), PARAMETER :: COSMsCol = 10 ! Number of columns in (cosine matrices) COSMs (COSMID,COSM11,COSM12,COSM13,COSM21,COSM22,COSM23,COSM31,COSM32,COSM33) INTEGER(IntKi), PARAMETER :: CMassCol = 11 ! Number of columns in Concentrated Mass (CMJointID,JMass,JMXX,JMYY,JMZZ, Optional:JMXY,JMXZ,JMYZ,CGX,CGY,CGZ) ! Indices in Members table From 30e736823c9d9465abb2d4a71f2902f19f9e8c97 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 20 Nov 2023 22:12:40 +0100 Subject: [PATCH 05/23] Update spring element --- modules/subdyn/src/SD_FEM.f90 | 70 +++++++++++++++++++++++------------ 1 file changed, 47 insertions(+), 23 deletions(-) diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index 24d1aa0c2c..fa5f217692 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -827,6 +827,7 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) REAL(FEKi) :: DirCos(3, 3) ! direction cosine matrices REAL(ReKi) :: L ! length of the element REAL(ReKi) :: r1, r2, t, Iyy, Jzz, Ixx, A, kappa, kappa_x, kappa_y, nu, ratioSq, D_inner, D_outer + REAL(ReKi) :: k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k33, k34, k35, k36, k44, k45, k46, k55, k56, k66 LOGICAL :: shear INTEGER(IntKi) :: eType !< Member type REAL(ReKi) :: Point1(3), Point2(3) ! (x,y,z) positions of two nodes making up an element @@ -887,7 +888,28 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) p%ElemProps(i)%Area = -9.99e+36 p%ElemProps(i)%Rho = -9.99e+36 p%ElemProps(i)%T0 = -9.99e+36 - + p%ElemProps(i)%k11 = -9.99e+36 + p%ElemProps(i)%k12 = -9.99e+36 + p%ElemProps(i)%k13 = -9.99e+36 + p%ElemProps(i)%k14 = -9.99e+36 + p%ElemProps(i)%k15 = -9.99e+36 + p%ElemProps(i)%k16 = -9.99e+36 + p%ElemProps(i)%k22 = -9.99e+36 + p%ElemProps(i)%k23 = -9.99e+36 + p%ElemProps(i)%k24 = -9.99e+36 + p%ElemProps(i)%k25 = -9.99e+36 + p%ElemProps(i)%k26 = -9.99e+36 + p%ElemProps(i)%k33 = -9.99e+36 + p%ElemProps(i)%k34 = -9.99e+36 + p%ElemProps(i)%k35 = -9.99e+36 + p%ElemProps(i)%k36 = -9.99e+36 + p%ElemProps(i)%k44 = -9.99e+36 + p%ElemProps(i)%k45 = -9.99e+36 + p%ElemProps(i)%k46 = -9.99e+36 + p%ElemProps(i)%k55 = -9.99e+36 + p%ElemProps(i)%k56 = -9.99e+36 + p%ElemProps(i)%k66 = -9.99e+36 + ! --- Properties that are specific to some elements if (eType==idMemberBeamCirc) then E = Init%PropsB(P1, 2) ! TODO E2 @@ -995,27 +1017,29 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) if (DEV_VERSION) then print*,'Member',I,'is a spring element' endif - p%ElemProps(i)%k11 = Init%PropsS(P1, 2) - p%ElemProps(i)%k12 = Init%PropsS(P1, 3) - p%ElemProps(i)%k13 = Init%PropsS(P1, 4) - p%ElemProps(i)%k14 = Init%PropsS(P1, 5) - p%ElemProps(i)%k15 = Init%PropsS(P1, 6) - p%ElemProps(i)%k16 = Init%PropsS(P1, 7) - p%ElemProps(i)%k22 = Init%PropsS(P1, 8) - p%ElemProps(i)%k23 = Init%PropsS(P1, 9) - p%ElemProps(i)%k24 = Init%PropsS(P1,10) - p%ElemProps(i)%k25 = Init%PropsS(P1,11) - p%ElemProps(i)%k26 = Init%PropsS(P1,12) - p%ElemProps(i)%k33 = Init%PropsS(P1,13) - p%ElemProps(i)%k34 = Init%PropsS(P1,14) - p%ElemProps(i)%k35 = Init%PropsS(P1,15) - p%ElemProps(i)%k36 = Init%PropsS(P1,16) - p%ElemProps(i)%k44 = Init%PropsS(P1,17) - p%ElemProps(i)%k45 = Init%PropsS(P1,18) - p%ElemProps(i)%k46 = Init%PropsS(P1,19) - p%ElemProps(i)%k55 = Init%PropsS(P1,20) - p%ElemProps(i)%k56 = Init%PropsS(P1,21) - p%ElemProps(i)%k66 = Init%PropsS(P1,22) + p%ElemProps(i)%Area = 0 ! Spring elements have no area + p%ElemProps(i)%Rho = 0 ! Spring elements have no mass + p%ElemProps(i)%k11 = Init%PropsS(P1, 2) + p%ElemProps(i)%k12 = Init%PropsS(P1, 3) + p%ElemProps(i)%k13 = Init%PropsS(P1, 4) + p%ElemProps(i)%k14 = Init%PropsS(P1, 5) + p%ElemProps(i)%k15 = Init%PropsS(P1, 6) + p%ElemProps(i)%k16 = Init%PropsS(P1, 7) + p%ElemProps(i)%k22 = Init%PropsS(P1, 8) + p%ElemProps(i)%k23 = Init%PropsS(P1, 9) + p%ElemProps(i)%k24 = Init%PropsS(P1,10) + p%ElemProps(i)%k25 = Init%PropsS(P1,11) + p%ElemProps(i)%k26 = Init%PropsS(P1,12) + p%ElemProps(i)%k33 = Init%PropsS(P1,13) + p%ElemProps(i)%k34 = Init%PropsS(P1,14) + p%ElemProps(i)%k35 = Init%PropsS(P1,15) + p%ElemProps(i)%k36 = Init%PropsS(P1,16) + p%ElemProps(i)%k44 = Init%PropsS(P1,17) + p%ElemProps(i)%k45 = Init%PropsS(P1,18) + p%ElemProps(i)%k46 = Init%PropsS(P1,19) + p%ElemProps(i)%k55 = Init%PropsS(P1,20) + p%ElemProps(i)%k56 = Init%PropsS(P1,21) + p%ElemProps(i)%k66 = Init%PropsS(P1,22) else ! Should not happen @@ -2339,7 +2363,7 @@ SUBROUTINE ElemK(ep, Ke) Ke = 0.0_FEKi else if (ep%eType==idMemberSpring) then - CALL ElemK_Spring(eP%k11, eP%k12, eP%k13, eP%k14, eP%k15, eP%k16, eP%k22, eP%k23, eP%k24, eP%k25, eP%k26, eP%k33, eP%k34, eP%k35, eP%k36, eP%k44, eP%k45, eP%k46, eP%k55, eP%k56, eP%k66, Ke) + CALL ElemK_Spring(eP%k11, eP%k12, eP%k13, eP%k14, eP%k15, eP%k16, eP%k22, eP%k23, eP%k24, eP%k25, eP%k26, eP%k33, eP%k34, eP%k35, eP%k36, eP%k44, eP%k45, eP%k46, eP%k55, eP%k56, eP%k66, eP%DirCos, Ke) endif END SUBROUTINE ElemK From 434f8f7c462e7fab5d93a6ba592e1847ab12b57b Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 20 Nov 2023 22:33:28 +0100 Subject: [PATCH 06/23] Update spring element --- modules/subdyn/src/SubDyn.f90 | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/modules/subdyn/src/SubDyn.f90 b/modules/subdyn/src/SubDyn.f90 index 855cce8d49..133555ca92 100644 --- a/modules/subdyn/src/SubDyn.f90 +++ b/modules/subdyn/src/SubDyn.f90 @@ -1255,18 +1255,24 @@ SUBROUTINE SD_Input(SDInputFile, Init, p, ErrStat,ErrMsg) CALL ReadIVar ( UnIn, SDInputFile, Init%NPropSetsS, 'NPropSetsS', 'Number of spring properties' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return CALL ReadCom ( UnIn, SDInputFile, 'Spring element properties Header' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return CALL ReadCom ( UnIn, SDInputFile, 'Spring element properties Unit ' ,ErrStat2, ErrMsg2, UnEc ); if(Failed()) return - CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'SpringPropSets', ErrStat2, ErrMsg2); if(Failed()) return + IF (Check( Init%NPropSetsS < 0, 'NPropSetsSpring must be >=0')) return + CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'PropSetsS', ErrStat2, ErrMsg2); if(Failed()) return DO I = 1, Init%NPropSetsS - CALL ReadAry( UnIn, SDInputFile, Init%PropSetsS(I,:), PropSetsSCol, 'SpringPropSets', 'SpringPropSets ID and values ', ErrStat2, ErrMsg2, UnEc ); if(Failed()) return + READ(UnIn, FMT='(A)', IOSTAT=ErrStat2) Line; ErrMsg2='Error reading spring property line'; if (Failed()) return + call ReadFAryFromStr(Line, Init%PropSetsS(I,:), PropSetsSCol, nColValid, nColNumeric); + if ((nColValid/=nColNumeric).or.((nColNumeric/=22).and.(nColNumeric/=PropSetsSCol)) ) then + CALL Fatal(' Error in file "'//TRIM(SDInputFile)//'": Spring property line must consist of 22 numerical values. Problematic line: "'//trim(Line)//'"') + return + endif ENDDO - IF (Check( Init%NPropSetsS < 0, 'NPropSetsSpring must be >=0')) return + else Init%NPropSetsC=0 Init%NPropSetsR=0 Init%NPropSetsS=0 CALL AllocAry(Init%PropSetsC, Init%NPropSetsC, PropSetsCCol, 'PropSetsC', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropSetsR, Init%NPropSetsR, PropSetsRCol, 'RigidPropSets', ErrStat2, ErrMsg2); if(Failed()) return - CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'SpringPropSets', ErrStat2, ErrMsg2); if(Failed()) return + CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'PropSetsS', ErrStat2, ErrMsg2); if(Failed()) return endif !---------------------- MEMBER COSINE MATRICES COSM(i,j) ------------------------ From 95be02fb85e9e5ba7b5a5214e3bc15b930650c9a Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 20 Nov 2023 23:06:00 +0100 Subject: [PATCH 07/23] Update SubDyn registry for springs --- modules/subdyn/src/SubDyn_Registry.txt | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/modules/subdyn/src/SubDyn_Registry.txt b/modules/subdyn/src/SubDyn_Registry.txt index 064bb8cf06..ecc7a0f1bd 100644 --- a/modules/subdyn/src/SubDyn_Registry.txt +++ b/modules/subdyn/src/SubDyn_Registry.txt @@ -42,6 +42,27 @@ typedef ^ ElemPropType ReKi D {2} - - "Diameter at node 1 and 2, f typedef ^ ElemPropType ReKi Area - - - "Area of an element" m^2 typedef ^ ElemPropType ReKi Rho - - - "Density" kg/m^3 typedef ^ ElemPropType ReKi T0 - - - "Pretension " N +typedef ^ ElemPropType ReKi k11 - - - "Spring translational stiffness" N/m +typedef ^ ElemPropType ReKi k12 - - - "Spring cross-coupling stiffness" N/m +typedef ^ ElemPropType ReKi k13 - - - "Spring cross-coupling stiffness" N/m +typedef ^ ElemPropType ReKi k14 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k15 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k16 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k22 - - - "Spring translational stiffness" N/m +typedef ^ ElemPropType ReKi k23 - - - "Spring cross-coupling stiffness" N/m +typedef ^ ElemPropType ReKi k24 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k25 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k26 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k33 - - - "Spring translational stiffness" N/m +typedef ^ ElemPropType ReKi k34 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k35 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k36 - - - "Spring cross-coupling stiffness" N/rad +typedef ^ ElemPropType ReKi k44 - - - "Spring rotational stiffness" Nm/rad +typedef ^ ElemPropType ReKi k45 - - - "Spring cross-coupling stiffness" Nm/rad +typedef ^ ElemPropType ReKi k46 - - - "Spring cross-coupling stiffness" Nm/rad +typedef ^ ElemPropType ReKi k55 - - - "Spring rotational stiffness" Nm/rad +typedef ^ ElemPropType ReKi k56 - - - "Spring cross-coupling stiffness" Nm/rad +typedef ^ ElemPropType ReKi k66 - - - "Spring rotational stiffness" Nm/rad typedef ^ ElemPropType R8Ki DirCos {3}{3} - - "Element direction cosine matrix" # ============================== Input Initialization (from glue code) ============================================================================================================================================ From fc8b31b5b10972c3fe3bb01f41a8db6a42024d74 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Tue, 21 Nov 2023 00:00:46 +0100 Subject: [PATCH 08/23] Update spring element --- modules/subdyn/src/SubDyn_Types.f90 | 293 ++++++++++++++++++++++++++++ 1 file changed, 293 insertions(+) diff --git a/modules/subdyn/src/SubDyn_Types.f90 b/modules/subdyn/src/SubDyn_Types.f90 index b6dfcc095e..8beeee9dc8 100644 --- a/modules/subdyn/src/SubDyn_Types.f90 +++ b/modules/subdyn/src/SubDyn_Types.f90 @@ -77,6 +77,27 @@ MODULE SubDyn_Types REAL(ReKi) :: Area !< Area of an element [m^2] REAL(ReKi) :: Rho !< Density [kg/m^3] REAL(ReKi) :: T0 !< Pretension [N] + REAL(ReKi) :: k11 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k12 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k13 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k14 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k15 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k16 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k22 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k23 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k24 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k25 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k26 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k33 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k34 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k35 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k36 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k44 !< Spring rotational stiffness [Nm/rad] + REAL(ReKi) :: k45 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k46 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k55 !< Spring rotational stiffness [Nm/rad] + REAL(ReKi) :: k56 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k66 !< Spring rotational stiffness [Nm/rad] REAL(R8Ki) , DIMENSION(1:3,1:3) :: DirCos !< Element direction cosine matrix [-] END TYPE ElemPropType ! ======================= @@ -121,6 +142,7 @@ MODULE SubDyn_Types INTEGER(IntKi) :: NPropSetsB !< Number of property sets for beams [-] INTEGER(IntKi) :: NPropSetsC !< Number of property sets for cables [-] INTEGER(IntKi) :: NPropSetsR !< Number of property sets for rigid links [-] + INTEGER(IntKi) :: NPropSetsS !< Number of property sets for spring elements [-] INTEGER(IntKi) :: NCMass !< Number of joints with concentrated mass [-] INTEGER(IntKi) :: NCOSMs !< Number of independent cosine matrices [-] INTEGER(IntKi) :: FEMMod !< FEM switch element model in the FEM [-] @@ -130,6 +152,7 @@ MODULE SubDyn_Types REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsB !< Property sets number and values [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsC !< Property ID and values for cables [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsR !< Property ID and values for rigid link [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsS !< Property ID and values for spring elements [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsX !< Extended property sets [-] REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: COSMs !< Independent direction cosine matrices [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CMass !< Concentrated mass information [-] @@ -151,10 +174,12 @@ MODULE SubDyn_Types INTEGER(IntKi) :: NPropB !< Total number of property sets for Beams [-] INTEGER(IntKi) :: NPropC !< Total number of property sets for Cable [-] INTEGER(IntKi) :: NPropR !< Total number of property sets for Rigid [-] + INTEGER(IntKi) :: NPropS !< Total number of property sets for Spring [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes !< Nodes number and coordinates [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsB !< Property sets and values for Beams [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsC !< Property sets and values for Cable [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsR !< Property sets and values for Rigid link [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsS !< Property sets and values for Spring [-] REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: K !< System stiffness matrix [-] REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: M !< System mass matrix [-] REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: ElemProps !< Element properties(A, L, Ixx, Iyy, Jzz, Shear, Kappa, E, G, Rho, DirCos(1,1), DirCos(2, 1), ....., DirCos(3, 3) ) [-] @@ -1719,6 +1744,27 @@ SUBROUTINE SD_CopyElemPropType( SrcElemPropTypeData, DstElemPropTypeData, CtrlCo DstElemPropTypeData%Area = SrcElemPropTypeData%Area DstElemPropTypeData%Rho = SrcElemPropTypeData%Rho DstElemPropTypeData%T0 = SrcElemPropTypeData%T0 + DstElemPropTypeData%k11 = SrcElemPropTypeData%k11 + DstElemPropTypeData%k12 = SrcElemPropTypeData%k12 + DstElemPropTypeData%k13 = SrcElemPropTypeData%k13 + DstElemPropTypeData%k14 = SrcElemPropTypeData%k14 + DstElemPropTypeData%k15 = SrcElemPropTypeData%k15 + DstElemPropTypeData%k16 = SrcElemPropTypeData%k16 + DstElemPropTypeData%k22 = SrcElemPropTypeData%k22 + DstElemPropTypeData%k23 = SrcElemPropTypeData%k23 + DstElemPropTypeData%k24 = SrcElemPropTypeData%k24 + DstElemPropTypeData%k25 = SrcElemPropTypeData%k25 + DstElemPropTypeData%k26 = SrcElemPropTypeData%k26 + DstElemPropTypeData%k33 = SrcElemPropTypeData%k33 + DstElemPropTypeData%k34 = SrcElemPropTypeData%k34 + DstElemPropTypeData%k35 = SrcElemPropTypeData%k35 + DstElemPropTypeData%k36 = SrcElemPropTypeData%k36 + DstElemPropTypeData%k44 = SrcElemPropTypeData%k44 + DstElemPropTypeData%k45 = SrcElemPropTypeData%k45 + DstElemPropTypeData%k46 = SrcElemPropTypeData%k46 + DstElemPropTypeData%k55 = SrcElemPropTypeData%k55 + DstElemPropTypeData%k56 = SrcElemPropTypeData%k56 + DstElemPropTypeData%k66 = SrcElemPropTypeData%k66 DstElemPropTypeData%DirCos = SrcElemPropTypeData%DirCos END SUBROUTINE SD_CopyElemPropType @@ -1794,6 +1840,27 @@ SUBROUTINE SD_PackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, Err Re_BufSz = Re_BufSz + 1 ! Area Re_BufSz = Re_BufSz + 1 ! Rho Re_BufSz = Re_BufSz + 1 ! T0 + Re_BufSz = Re_BufSz + 1 ! k11 + Re_BufSz = Re_BufSz + 1 ! k12 + Re_BufSz = Re_BufSz + 1 ! k13 + Re_BufSz = Re_BufSz + 1 ! k14 + Re_BufSz = Re_BufSz + 1 ! k15 + Re_BufSz = Re_BufSz + 1 ! k16 + Re_BufSz = Re_BufSz + 1 ! k22 + Re_BufSz = Re_BufSz + 1 ! k23 + Re_BufSz = Re_BufSz + 1 ! k24 + Re_BufSz = Re_BufSz + 1 ! k25 + Re_BufSz = Re_BufSz + 1 ! k26 + Re_BufSz = Re_BufSz + 1 ! k33 + Re_BufSz = Re_BufSz + 1 ! k34 + Re_BufSz = Re_BufSz + 1 ! k35 + Re_BufSz = Re_BufSz + 1 ! k36 + Re_BufSz = Re_BufSz + 1 ! k44 + Re_BufSz = Re_BufSz + 1 ! k45 + Re_BufSz = Re_BufSz + 1 ! k46 + Re_BufSz = Re_BufSz + 1 ! k55 + Re_BufSz = Re_BufSz + 1 ! k56 + Re_BufSz = Re_BufSz + 1 ! k66 Db_BufSz = Db_BufSz + SIZE(InData%DirCos) ! DirCos IF ( Re_BufSz .GT. 0 ) THEN ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) @@ -1852,6 +1919,48 @@ SUBROUTINE SD_PackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, Err Re_Xferred = Re_Xferred + 1 ReKiBuf(Re_Xferred) = InData%T0 Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k11 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k12 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k13 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k14 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k15 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k16 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k22 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k23 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k24 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k25 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k26 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k33 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k34 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k35 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k36 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k44 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k45 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k46 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k55 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k56 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k66 + Re_Xferred = Re_Xferred + 1 DO i2 = LBOUND(InData%DirCos,2), UBOUND(InData%DirCos,2) DO i1 = LBOUND(InData%DirCos,1), UBOUND(InData%DirCos,1) DbKiBuf(Db_Xferred) = InData%DirCos(i1,i2) @@ -1920,6 +2029,48 @@ SUBROUTINE SD_UnPackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, Re_Xferred = Re_Xferred + 1 OutData%T0 = ReKiBuf(Re_Xferred) Re_Xferred = Re_Xferred + 1 + OutData%k11 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k12 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k13 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k14 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k15 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k16 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k22 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k23 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k24 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k25 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k26 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k33 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k34 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k35 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k36 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k44 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k45 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k46 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k55 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k56 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k66 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 i1_l = LBOUND(OutData%DirCos,1) i1_u = UBOUND(OutData%DirCos,1) i2_l = LBOUND(OutData%DirCos,2) @@ -3147,6 +3298,7 @@ SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, DstInitTypeData%NPropSetsB = SrcInitTypeData%NPropSetsB DstInitTypeData%NPropSetsC = SrcInitTypeData%NPropSetsC DstInitTypeData%NPropSetsR = SrcInitTypeData%NPropSetsR + DstInitTypeData%NPropSetsS = SrcInitTypeData%NPropSetsS DstInitTypeData%NCMass = SrcInitTypeData%NCMass DstInitTypeData%NCOSMs = SrcInitTypeData%NCOSMs DstInitTypeData%FEMMod = SrcInitTypeData%FEMMod @@ -3208,6 +3360,20 @@ SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, END IF DstInitTypeData%PropSetsR = SrcInitTypeData%PropSetsR ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsS)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsS,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsS,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsS,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsS,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsS)) THEN + ALLOCATE(DstInitTypeData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsS = SrcInitTypeData%PropSetsS +ENDIF IF (ALLOCATED(SrcInitTypeData%PropSetsX)) THEN i1_l = LBOUND(SrcInitTypeData%PropSetsX,1) i1_u = UBOUND(SrcInitTypeData%PropSetsX,1) @@ -3379,6 +3545,7 @@ SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, DstInitTypeData%NPropB = SrcInitTypeData%NPropB DstInitTypeData%NPropC = SrcInitTypeData%NPropC DstInitTypeData%NPropR = SrcInitTypeData%NPropR + DstInitTypeData%NPropS = SrcInitTypeData%NPropS IF (ALLOCATED(SrcInitTypeData%Nodes)) THEN i1_l = LBOUND(SrcInitTypeData%Nodes,1) i1_u = UBOUND(SrcInitTypeData%Nodes,1) @@ -3435,6 +3602,20 @@ SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, END IF DstInitTypeData%PropsR = SrcInitTypeData%PropsR ENDIF +IF (ALLOCATED(SrcInitTypeData%PropsS)) THEN + i1_l = LBOUND(SrcInitTypeData%PropsR,1) + i1_u = UBOUND(SrcInitTypeData%PropsR,1) + i2_l = LBOUND(SrcInitTypeData%PropsR,2) + i2_u = UBOUND(SrcInitTypeData%PropsR,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropsS)) THEN + ALLOCATE(DstInitTypeData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropsS = SrcInitTypeData%PropsS +ENDIF IF (ALLOCATED(SrcInitTypeData%K)) THEN i1_l = LBOUND(SrcInitTypeData%K,1) i1_u = UBOUND(SrcInitTypeData%K,1) @@ -3555,6 +3736,9 @@ SUBROUTINE SD_DestroyInitType( InitTypeData, ErrStat, ErrMsg, DEALLOCATEpointers IF (ALLOCATED(InitTypeData%PropSetsR)) THEN DEALLOCATE(InitTypeData%PropSetsR) ENDIF +IF (ALLOCATED(InitTypeData%PropSetsS)) THEN + DEALLOCATE(InitTypeData%PropSetsS) +ENDIF IF (ALLOCATED(InitTypeData%PropSetsX)) THEN DEALLOCATE(InitTypeData%PropSetsX) ENDIF @@ -3603,6 +3787,9 @@ SUBROUTINE SD_DestroyInitType( InitTypeData, ErrStat, ErrMsg, DEALLOCATEpointers IF (ALLOCATED(InitTypeData%PropsR)) THEN DEALLOCATE(InitTypeData%PropsR) ENDIF +IF (ALLOCATED(InitTypeData%PropsS)) THEN + DEALLOCATE(InitTypeData%PropsS) +ENDIF IF (ALLOCATED(InitTypeData%K)) THEN DEALLOCATE(InitTypeData%K) ENDIF @@ -3668,6 +3855,7 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_BufSz = Int_BufSz + 1 ! NPropSetsB Int_BufSz = Int_BufSz + 1 ! NPropSetsC Int_BufSz = Int_BufSz + 1 ! NPropSetsR + Int_BufSz = Int_BufSz + 1 ! NPropSetsS Int_BufSz = Int_BufSz + 1 ! NCMass Int_BufSz = Int_BufSz + 1 ! NCOSMs Int_BufSz = Int_BufSz + 1 ! FEMMod @@ -3693,6 +3881,11 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_BufSz = Int_BufSz + 2*2 ! PropSetsR upper/lower bounds for each dimension Re_BufSz = Re_BufSz + SIZE(InData%PropSetsR) ! PropSetsR END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsS allocated yes/no + IF ( ALLOCATED(InData%PropSetsS) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsS) ! PropSetsS + END IF Int_BufSz = Int_BufSz + 1 ! PropSetsX allocated yes/no IF ( ALLOCATED(InData%PropSetsX) ) THEN Int_BufSz = Int_BufSz + 2*2 ! PropSetsX upper/lower bounds for each dimension @@ -3762,6 +3955,7 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_BufSz = Int_BufSz + 1 ! NPropB Int_BufSz = Int_BufSz + 1 ! NPropC Int_BufSz = Int_BufSz + 1 ! NPropR + Int_BufSz = Int_BufSz + 1 ! NPropS Int_BufSz = Int_BufSz + 1 ! Nodes allocated yes/no IF ( ALLOCATED(InData%Nodes) ) THEN Int_BufSz = Int_BufSz + 2*2 ! Nodes upper/lower bounds for each dimension @@ -3782,6 +3976,11 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_BufSz = Int_BufSz + 2*2 ! PropsR upper/lower bounds for each dimension Re_BufSz = Re_BufSz + SIZE(InData%PropsR) ! PropsR END IF + Int_BufSz = Int_BufSz + 1 ! PropsS allocated yes/no + IF ( ALLOCATED(InData%PropsS) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropsS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropsS) ! PropsS + END IF Int_BufSz = Int_BufSz + 1 ! K allocated yes/no IF ( ALLOCATED(InData%K) ) THEN Int_BufSz = Int_BufSz + 2*2 ! K upper/lower bounds for each dimension @@ -3864,6 +4063,8 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_Xferred = Int_Xferred + 1 IntKiBuf(Int_Xferred) = InData%NPropSetsR Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsS + Int_Xferred = Int_Xferred + 1 IntKiBuf(Int_Xferred) = InData%NCMass Int_Xferred = Int_Xferred + 1 IntKiBuf(Int_Xferred) = InData%NCOSMs @@ -3954,6 +4155,26 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, END DO END DO END IF + IF ( .NOT. ALLOCATED(InData%PropSetsS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsS,2), UBOUND(InData%PropSetsS,2) + DO i1 = LBOUND(InData%PropSetsS,1), UBOUND(InData%PropSetsS,1) + ReKiBuf(Re_Xferred) = InData%PropSetsS(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF IF ( .NOT. ALLOCATED(InData%PropSetsX) ) THEN IntKiBuf( Int_Xferred ) = 0 Int_Xferred = Int_Xferred + 1 @@ -4207,6 +4428,8 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, Int_Xferred = Int_Xferred + 1 IntKiBuf(Int_Xferred) = InData%NPropR Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropS + Int_Xferred = Int_Xferred + 1 IF ( .NOT. ALLOCATED(InData%Nodes) ) THEN IntKiBuf( Int_Xferred ) = 0 Int_Xferred = Int_Xferred + 1 @@ -4287,6 +4510,26 @@ SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, END DO END DO END IF + IF ( .NOT. ALLOCATED(InData%PropsS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropsS,2), UBOUND(InData%PropsS,2) + DO i1 = LBOUND(InData%PropsS,1), UBOUND(InData%PropsS,1) + ReKiBuf(Re_Xferred) = InData%PropsS(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF IF ( .NOT. ALLOCATED(InData%K) ) THEN IntKiBuf( Int_Xferred ) = 0 Int_Xferred = Int_Xferred + 1 @@ -4466,6 +4709,8 @@ SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrM Int_Xferred = Int_Xferred + 1 OutData%NPropSetsR = IntKiBuf(Int_Xferred) Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsS = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 OutData%NCMass = IntKiBuf(Int_Xferred) Int_Xferred = Int_Xferred + 1 OutData%NCOSMs = IntKiBuf(Int_Xferred) @@ -4568,6 +4813,29 @@ SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrM END DO END DO END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsS)) DEALLOCATE(OutData%PropSetsS) + ALLOCATE(OutData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsS,2), UBOUND(OutData%PropSetsS,2) + DO i1 = LBOUND(OutData%PropSetsS,1), UBOUND(OutData%PropSetsS,1) + OutData%PropSetsS(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsX not allocated Int_Xferred = Int_Xferred + 1 ELSE @@ -4863,6 +5131,8 @@ SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrM Int_Xferred = Int_Xferred + 1 OutData%NPropR = IntKiBuf(Int_Xferred) Int_Xferred = Int_Xferred + 1 + OutData%NPropS = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes not allocated Int_Xferred = Int_Xferred + 1 ELSE @@ -4955,6 +5225,29 @@ SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrM END DO END DO END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropsS)) DEALLOCATE(OutData%PropsS) + ALLOCATE(OutData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropsS,2), UBOUND(OutData%PropsS,2) + DO i1 = LBOUND(OutData%PropsS,1), UBOUND(OutData%PropsS,1) + OutData%PropsS(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! K not allocated Int_Xferred = Int_Xferred + 1 ELSE From 4c32cb0b8481110acef9313414f2954489c2edad Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Thu, 23 Nov 2023 00:41:55 +0100 Subject: [PATCH 09/23] Two nodes with the same location for springs --- modules/subdyn/src/FEM.f90 | 17 +- modules/subdyn/src/SD_FEM.f90 | 4 +- modules/subdyn/src/SubDyn.f90 | 12 +- modules/subdyn/src/SubDyn_Tests.f90 | 3 +- modules/subdyn/src/SubDyn_Types.f90 | 26808 +++++++++++++------------- 5 files changed, 13429 insertions(+), 13415 deletions(-) diff --git a/modules/subdyn/src/FEM.f90 b/modules/subdyn/src/FEM.f90 index 5c68ddbd03..07ffce5f49 100644 --- a/modules/subdyn/src/FEM.f90 +++ b/modules/subdyn/src/FEM.f90 @@ -951,8 +951,9 @@ END SUBROUTINE GetRigidTransformation !! !! bjj: note that this is the transpose of what is normally considered the Direction Cosine Matrix !! in the FAST framework. -SUBROUTINE GetDirCos(P1, P2, DirCos, L_out, ErrStat, ErrMsg) +SUBROUTINE GetDirCos(P1, P2, eType, DirCos, L_out, ErrStat, ErrMsg) REAL(ReKi) , INTENT(IN ) :: P1(3), P2(3) ! (x,y,z) global positions of two nodes making up an element + INTEGER(IntKi), INTENT(IN ) :: eType ! element type (1:beam circ., 2:cable, 3:rigid, 4:beam arb., 5:spring) REAL(FEKi) , INTENT( OUT) :: DirCos(3, 3) ! calculated direction cosine matrix REAL(ReKi) , INTENT( OUT) :: L_out ! length of element INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation @@ -966,9 +967,16 @@ SUBROUTINE GetDirCos(P1, P2, DirCos, L_out, ErrStat, ErrMsg) Dz=P2(3)-P1(3) Dxy = sqrt( Dx**2 + Dy**2 ) L = sqrt( Dx**2 + Dy**2 + Dz**2) + + ! The spring element should have the same starting and ending location. P1 and P2 must be coincident (L must be 0). + IF ( .not. EqualRealNos(L, 0.0_FEKi) .and. eType == 5) THEN + ErrMsg = ' Spring(s) must be defined with the same starting and ending locations in the element.' + ErrStat = ErrID_Fatal + RETURN + ENDIF - IF ( EqualRealNos(L, 0.0_FEKi) ) THEN - ErrMsg = ' Same starting and ending location in the element.' + IF ( EqualRealNos(L, 0.0_FEKi) .and. eType/= 5) THEN + ErrMsg = ' Same starting and ending location in a beam, cable or rigid element.' ErrStat = ErrID_Fatal RETURN ENDIF @@ -1303,6 +1311,9 @@ SUBROUTINE ElemK_Spring(k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k ! Temporary check. Looking at the spring element matrix (local coordinate system). print*,'Spring element stiffness (local coordinate system)' print*, K + + ! Temporary check. Looking at direction cosine matrix. + print*,'Direction cosine',DirCos DC = 0.0_FEKi DC( 1: 3, 1: 3) = DirCos diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index fa5f217692..bc75a39cb4 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -854,7 +854,7 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) Point2 = Init%Nodes(N2,2:4) if (iDirCos/=-1) then - CALL GetDirCos(Point1, Point2, DirCos, L, ErrStat2, ErrMsg2); if(Failed()) return ! sets L + CALL GetDirCos(Point1, Point2, eType, DirCos, L, ErrStat2, ErrMsg2); if(Failed()) return ! sets L ! overwrites direction cosines DirCos(1, 1) = Init%COSMs(iDirCos, 2) @@ -868,7 +868,7 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) DirCos(3, 3) = Init%COSMs(iDirCos, 10) else - CALL GetDirCos(Point1, Point2, DirCos, L, ErrStat2, ErrMsg2); if(Failed()) return ! L and DirCos + CALL GetDirCos(Point1, Point2, eType, DirCos, L, ErrStat2, ErrMsg2); if(Failed()) return ! L and DirCos endif diff --git a/modules/subdyn/src/SubDyn.f90 b/modules/subdyn/src/SubDyn.f90 index 133555ca92..33a920e792 100644 --- a/modules/subdyn/src/SubDyn.f90 +++ b/modules/subdyn/src/SubDyn.f90 @@ -3786,8 +3786,10 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E !Calculate member mass here; this should really be done somewhere else, yet it is not used anywhere else !IT WILL HAVE TO BE MODIFIED FOR OTHER THAN CIRCULAR PIPE ELEMENTS propIDs=Init%Members(i,iMProp:iMProp+1) - mLength=MemberLength(Init%Members(i,1),Init,ErrStat,ErrMsg) ! TODO double check mass and length - IF (ErrStat .EQ. ErrID_None) THEN + if (Init%Members(I, iMType)/=idMemberSpring) then ! This check only applies for members different than springs (springs have no mass and no length) + mLength=MemberLength(Init%Members(i,1),Init,ErrStat,ErrMsg) ! TODO double check mass and length + endif + IF (ErrStat .EQ. ErrID_None) THEN mType = Init%Members(I, iMType) ! if (mType==idMemberBeamCirc) then iProp(1) = FINDLOCI(Init%PropSetsB(:,1), propIDs(1)) @@ -3837,7 +3839,7 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E iNode2 = FINDLOCI(Init%Joints(:,1), Init%Members(i,3)) ! index of joint 2 of member i XYZ1 = Init%Joints(iNode1,2:4) XYZ2 = Init%Joints(iNode2,2:4) - CALL GetDirCos(XYZ1(1:3), XYZ2(1:3), DirCos, mLength, ErrStat, ErrMsg) + CALL GetDirCos(XYZ1(1:3), XYZ2(1:3), mType, DirCos, mLength, ErrStat, ErrMsg) DirCos=TRANSPOSE(DirCos) !This is now global to local WRITE(UnSum, '("#",I9,9(ES28.18E2))') Init%Members(i,1), ((DirCos(k,j),j=1,3),k=1,3) ENDDO @@ -4084,7 +4086,7 @@ END SUBROUTINE StateMatrices FUNCTION MemberLength(MemberID,Init,ErrStat,ErrMsg) TYPE(SD_InitType), INTENT(IN) :: Init !< Input data for initialization routine, this structure contains many variables needed for summary file INTEGER(IntKi), INTENT(IN) :: MemberID !< Member ID # - REAL(ReKi) :: MemberLength !< Member Length + REAL(ReKi) :: MemberLength !< Member Length INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None !Locals @@ -4108,7 +4110,7 @@ FUNCTION MemberLength(MemberID,Init,ErrStat,ErrMsg) xyz1= Init%Joints(Joint1,2:4) xyz2= Init%Joints(Joint2,2:4) MemberLength=SQRT( SUM((xyz2-xyz1)**2.) ) - if ( EqualRealNos(MemberLength, 0.0_ReKi) ) then + if ( EqualRealNos(MemberLength, 0.0_ReKi) ) then call SetErrStat(ErrID_Fatal,' Member with ID '//trim(Num2LStr(MemberID))//' has zero length!', ErrStat,ErrMsg,RoutineName); return endif diff --git a/modules/subdyn/src/SubDyn_Tests.f90 b/modules/subdyn/src/SubDyn_Tests.f90 index 138435f85f..dd822f52e5 100644 --- a/modules/subdyn/src/SubDyn_Tests.f90 +++ b/modules/subdyn/src/SubDyn_Tests.f90 @@ -323,6 +323,7 @@ subroutine Test_Transformations(ErrStat,ErrMsg) character(ErrMsgLen), intent(out) :: ErrMsg real(ReKi), dimension(3) :: P1, P2, e1, e2, e3 + integer(IntKi) :: eType real(FEKi), dimension(3,3) :: DirCos, Ref real(ReKi), dimension(6,6) :: T, Tref real(ReKi) :: L @@ -332,7 +333,7 @@ subroutine Test_Transformations(ErrStat,ErrMsg) ! --- DirCos P1=(/0,0,0/) P2=(/2,0,0/) - call GetDirCos(P1, P2, DirCos, L, ErrStat, ErrMsg) + call GetDirCos(P1, P2, eType, DirCos, L, ErrStat, ErrMsg) Ref = reshape( (/0_FEKi,-1_FEKi,0_FEKi, 0_FEKi, 0_FEKi, -1_FEKi, 1_FEKi, 0_FEKi, 0_FEKi/) , (/3,3/)) call test_almost_equal('DirCos',Ref,DirCos,1e-8_FEKi,.true.,.true.) diff --git a/modules/subdyn/src/SubDyn_Types.f90 b/modules/subdyn/src/SubDyn_Types.f90 index 8beeee9dc8..7bc008b309 100644 --- a/modules/subdyn/src/SubDyn_Types.f90 +++ b/modules/subdyn/src/SubDyn_Types.f90 @@ -1,13404 +1,13404 @@ -!STARTOFREGISTRYGENERATEDFILE 'SubDyn_Types.f90' -! -! WARNING This file is generated automatically by the FAST registry. -! Do not edit. Your changes to this file will be lost. -! -! FAST Registry -!********************************************************************************************************************************* -! SubDyn_Types -!................................................................................................................................. -! This file is part of SubDyn. -! -! Copyright (C) 2012-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. -! -! -! W A R N I N G : This file was automatically generated from the FAST registry. Changes made to this file may be lost. -! -!********************************************************************************************************************************* -!> This module contains the user-defined types needed in SubDyn. It also contains copy, destroy, pack, and -!! unpack routines associated with each defined data type. This code is automatically generated by the FAST Registry. -MODULE SubDyn_Types -!--------------------------------------------------------------------------------------------------------------------------------- -USE NWTC_Library -IMPLICIT NONE -! ========= IList ======= - TYPE, PUBLIC :: IList - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: List !< List of integers [-] - END TYPE IList -! ======================= -! ========= MeshAuxDataType ======= - TYPE, PUBLIC :: MeshAuxDataType - INTEGER(IntKi) :: MemberID !< Member ID for Output [-] - INTEGER(IntKi) :: NOutCnt !< Number of Nodes for the output member [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeCnt !< Node ordinal numbers for the output member [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeIDs !< Node IDs associated with ordinal numbers for the output member [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElmIDs !< Element IDs connected to each NodeIDs; max 10 elements [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElmNds !< Flag to indicate 1st or 2nd node of element for each ElmIDs [-] - REAL(R8Ki) , DIMENSION(:,:,:,:), ALLOCATABLE :: Me !< Mass matrix connected to each joint element for outAll output [-] - REAL(R8Ki) , DIMENSION(:,:,:,:), ALLOCATABLE :: Ke !< Mass matrix connected to each joint element for outAll output [-] - REAL(R8Ki) , DIMENSION(:,:,:), ALLOCATABLE :: Fg !< Gravity load vector connected to each joint element for requested member output [-] - END TYPE MeshAuxDataType -! ======================= -! ========= CB_MatArrays ======= - TYPE, PUBLIC :: CB_MatArrays - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: MBB !< FULL MBB ( no constraints applied) [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: MBM !< FULL MBM ( no constraints applied) [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: KBB !< FULL KBB ( no constraints applied) [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: PhiL !< Retained CB modes, possibly allPhiL(nDOFL,nDOFL), or PhiL(nDOFL,nDOFM) [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: PhiR !< FULL PhiR ( no constraints applied) [-] - REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: OmegaL !< Eigenvalues of retained CB modes, possibly all (nDOFL or nDOFM) [-] - END TYPE CB_MatArrays -! ======================= -! ========= ElemPropType ======= - TYPE, PUBLIC :: ElemPropType - INTEGER(IntKi) :: eType !< Element Type [-] - REAL(ReKi) :: Length !< Length of an element [-] - REAL(ReKi) :: Ixx !< Moment of inertia of an element [-] - REAL(ReKi) :: Iyy !< Moment of inertia of an element [-] - REAL(ReKi) :: Jzz !< Moment of inertia of an element [-] - LOGICAL :: Shear !< Use timoshenko (true) E-B (false) [-] - REAL(ReKi) :: Kappa_x !< Shear coefficient [-] - REAL(ReKi) :: Kappa_y !< Shear coefficient [-] - REAL(ReKi) :: YoungE !< Young's modulus [-] - REAL(ReKi) :: ShearG !< Shear modulus [N/m^2] - REAL(ReKi) , DIMENSION(1:2) :: D !< Diameter at node 1 and 2, for visualization only [m] - REAL(ReKi) :: Area !< Area of an element [m^2] - REAL(ReKi) :: Rho !< Density [kg/m^3] - REAL(ReKi) :: T0 !< Pretension [N] - REAL(ReKi) :: k11 !< Spring translational stiffness [N/m] - REAL(ReKi) :: k12 !< Spring cross-coupling stiffness [N/m] - REAL(ReKi) :: k13 !< Spring cross-coupling stiffness [N/m] - REAL(ReKi) :: k14 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k15 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k16 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k22 !< Spring translational stiffness [N/m] - REAL(ReKi) :: k23 !< Spring cross-coupling stiffness [N/m] - REAL(ReKi) :: k24 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k25 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k26 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k33 !< Spring translational stiffness [N/m] - REAL(ReKi) :: k34 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k35 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k36 !< Spring cross-coupling stiffness [N/rad] - REAL(ReKi) :: k44 !< Spring rotational stiffness [Nm/rad] - REAL(ReKi) :: k45 !< Spring cross-coupling stiffness [Nm/rad] - REAL(ReKi) :: k46 !< Spring cross-coupling stiffness [Nm/rad] - REAL(ReKi) :: k55 !< Spring rotational stiffness [Nm/rad] - REAL(ReKi) :: k56 !< Spring cross-coupling stiffness [Nm/rad] - REAL(ReKi) :: k66 !< Spring rotational stiffness [Nm/rad] - REAL(R8Ki) , DIMENSION(1:3,1:3) :: DirCos !< Element direction cosine matrix [-] - END TYPE ElemPropType -! ======================= -! ========= SD_InitInputType ======= - TYPE, PUBLIC :: SD_InitInputType - CHARACTER(1024) :: SDInputFile !< Name of the input file [-] - CHARACTER(1024) :: RootName !< SubDyn rootname [-] - REAL(ReKi) :: g !< Gravity acceleration [-] - REAL(ReKi) :: WtrDpth !< Water Depth (positive valued) [-] - REAL(ReKi) , DIMENSION(1:3) :: TP_RefPoint !< global position of transition piece reference point (could also be defined in SubDyn itself) [-] - REAL(ReKi) :: SubRotateZ !< Rotation angle in degrees about global Z [-] - REAL(ReKi) , DIMENSION(:,:,:), ALLOCATABLE :: SoilStiffness !< Soil stiffness matrices from SoilDyn ['(N/m,] - TYPE(MeshType) :: SoilMesh !< Mesh for soil stiffness locations [-] - LOGICAL :: Linearize = .FALSE. !< Flag that tells this module if the glue code wants to linearize. [-] - END TYPE SD_InitInputType -! ======================= -! ========= SD_InitOutputType ======= - TYPE, PUBLIC :: SD_InitOutputType - CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: WriteOutputHdr !< Names of the output-to-file channels [-] - CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: WriteOutputUnt !< Units of the output-to-file channels [-] - TYPE(ProgDesc) :: Ver !< This module's name, version, and date [-] - CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_y !< Names of the outputs used in linearization [-] - CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_x !< Names of the continuous states used in linearization [-] - CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_u !< Names of the inputs used in linearization [-] - LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_y !< Flag that tells FAST/MBC3 if the outputs used in linearization are in the rotating frame [-] - LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_x !< Flag that tells FAST/MBC3 if the continuous states used in linearization are in the rotating frame (not used for glue) [-] - LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_u !< Flag that tells FAST/MBC3 if the inputs used in linearization are in the rotating frame [-] - LOGICAL , DIMENSION(:), ALLOCATABLE :: IsLoad_u !< Flag that tells FAST if the inputs used in linearization are loads (for preconditioning matrix) [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: DerivOrder_x !< Integer that tells FAST/MBC3 the maximum derivative order of continuous states used in linearization [-] - LOGICAL , DIMENSION(:), ALLOCATABLE :: CableCChanRqst !< flag indicating control channel for active cable tensioning is requested [-] - END TYPE SD_InitOutputType -! ======================= -! ========= SD_InitType ======= - TYPE, PUBLIC :: SD_InitType - CHARACTER(1024) :: RootName !< SubDyn rootname [-] - REAL(ReKi) , DIMENSION(1:3) :: TP_RefPoint !< global position of transition piece reference point (could also be defined in SubDyn itself) [-] - REAL(ReKi) :: SubRotateZ !< Rotation angle in degrees about global Z [-] - REAL(ReKi) :: g !< Gravity acceleration [-] - REAL(DbKi) :: DT !< Time step from Glue Code [seconds] - INTEGER(IntKi) :: NJoints !< Number of joints of the sub structure [-] - INTEGER(IntKi) :: NPropSetsX !< Number of extended property sets [-] - INTEGER(IntKi) :: NPropSetsB !< Number of property sets for beams [-] - INTEGER(IntKi) :: NPropSetsC !< Number of property sets for cables [-] - INTEGER(IntKi) :: NPropSetsR !< Number of property sets for rigid links [-] - INTEGER(IntKi) :: NPropSetsS !< Number of property sets for spring elements [-] - INTEGER(IntKi) :: NCMass !< Number of joints with concentrated mass [-] - INTEGER(IntKi) :: NCOSMs !< Number of independent cosine matrices [-] - INTEGER(IntKi) :: FEMMod !< FEM switch element model in the FEM [-] - INTEGER(IntKi) :: NDiv !< Number of divisions for each member [-] - LOGICAL :: CBMod !< Perform C-B flag [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Joints !< Joints number and coordinate values [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsB !< Property sets number and values [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsC !< Property ID and values for cables [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsR !< Property ID and values for rigid link [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsS !< Property ID and values for spring elements [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsX !< Extended property sets [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: COSMs !< Independent direction cosine matrices [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CMass !< Concentrated mass information [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: JDampings !< Damping coefficients for internal modes [-] - INTEGER(IntKi) :: GuyanDampMod !< Guyan damping [0=none, 1=Rayleigh Damping, 2= user specified 6x6 matrix] [-] - REAL(ReKi) , DIMENSION(1:2) :: RayleighDamp !< Mass and stiffness proportional damping coefficients (Rayleigh Damping) [only if GuyanDampMod=1] [-] - REAL(ReKi) , DIMENSION(1:6,1:6) :: GuyanDampMat !< Guyan Damping Matrix, see also CBB [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Members !< Member joints connection [-] - CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: SSOutList !< List of Output Channels [-] - LOGICAL :: OutCOSM !< Output Cos-matrices Flag [-] - LOGICAL :: TabDelim !< Generate a tab-delimited output file in OutJckF-Flag [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: SSIK !< SSI stiffness packed matrix elements (21 of them), for each reaction joint [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: SSIM !< SSI mass packed matrix elements (21 of them), for each reaction joint [-] - CHARACTER(1024) , DIMENSION(:), ALLOCATABLE :: SSIfile !< Soil Structure Interaction (SSI) files to associate with each reaction node [-] - REAL(ReKi) , DIMENSION(:,:,:), ALLOCATABLE :: Soil_K !< Soil stiffness (at passed at Init, not in input file) 6x6xn [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Soil_Points !< Node positions where soil stiffness will be added [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: Soil_Nodes !< Node indices where soil stiffness will be added [-] - INTEGER(IntKi) :: NElem !< Total number of elements [-] - INTEGER(IntKi) :: NPropB !< Total number of property sets for Beams [-] - INTEGER(IntKi) :: NPropC !< Total number of property sets for Cable [-] - INTEGER(IntKi) :: NPropR !< Total number of property sets for Rigid [-] - INTEGER(IntKi) :: NPropS !< Total number of property sets for Spring [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes !< Nodes number and coordinates [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsB !< Property sets and values for Beams [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsC !< Property sets and values for Cable [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsR !< Property sets and values for Rigid link [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsS !< Property sets and values for Spring [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: K !< System stiffness matrix [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: M !< System mass matrix [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: ElemProps !< Element properties(A, L, Ixx, Iyy, Jzz, Shear, Kappa, E, G, Rho, DirCos(1,1), DirCos(2, 1), ....., DirCos(3, 3) ) [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: MemberNodes !< Member number and list of nodes making up a member (>2 if subdivided) [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: NodesConnN !< Nodes that connect to a common node [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: NodesConnE !< Elements that connect to a common node [-] - LOGICAL :: SSSum !< SubDyn Summary File Flag [-] - END TYPE SD_InitType -! ======================= -! ========= SD_ContinuousStateType ======= - TYPE, PUBLIC :: SD_ContinuousStateType - REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: qm !< Virtual states, Nmod elements [-] - REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: qmdot !< Derivative of states, Nmod elements [-] - END TYPE SD_ContinuousStateType -! ======================= -! ========= SD_DiscreteStateType ======= - TYPE, PUBLIC :: SD_DiscreteStateType - REAL(ReKi) :: DummyDiscState !< Remove this variable if you have discrete states [-] - END TYPE SD_DiscreteStateType -! ======================= -! ========= SD_ConstraintStateType ======= - TYPE, PUBLIC :: SD_ConstraintStateType - REAL(ReKi) :: DummyConstrState !< Remove this variable if you have constraint states [-] - END TYPE SD_ConstraintStateType -! ======================= -! ========= SD_OtherStateType ======= - TYPE, PUBLIC :: SD_OtherStateType - TYPE(SD_ContinuousStateType) , DIMENSION(:), ALLOCATABLE :: xdot !< previous state derivs for m-step time integrator [-] - INTEGER(IntKi) :: n !< tracks time step for which OtherState was updated last [-] - END TYPE SD_OtherStateType -! ======================= -! ========= SD_MiscVarType ======= - TYPE, PUBLIC :: SD_MiscVarType - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: qmdotdot !< 2nd Derivative of states, used only for output-file purposes [-] - REAL(ReKi) , DIMENSION(1:6) :: u_TP - REAL(ReKi) , DIMENSION(1:6) :: udot_TP - REAL(ReKi) , DIMENSION(1:6) :: udotdot_TP - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: F_L !< Loads on internal DOF, size nL [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: F_L2 !< Loads on internal DOF, size nL, used for SIM and ADM4 [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar_dot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar_dotdot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL !< Internal DOFs (L) displacements [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_NS !< Internal DOFs (L) displacements, No SIM (NS) [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_dot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_dotdot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: DU_full !< Delta U used for extra moment, size nDOF [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full !< Displacement of all DOFs (full system) with SIM [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_NS !< Displacement of all DOFs (full system), No SIM (NS) [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_dot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_dotdot - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_elast !< Elastic displacements for computation of K ue (without rigid body mode for floating), includes SIM [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_red - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: FC_unit !< Cable Force vector (for varying cable load, of unit cable load) [N] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: SDWrOutput !< Data from previous step to be written to a SubDyn output file [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: AllOuts !< Data for output file [-] - REAL(DbKi) :: LastOutTime !< The time of the most recent stored output data [s] - INTEGER(IntKi) :: Decimat !< Current output decimation counter [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: Fext !< External loads on unconstrained DOFs [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: Fext_red !< External loads on constrained DOFs, Fext_red= T^t Fext [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_SIM !< UL for SIM = PhiL qL0- PhiM qm0, size nL [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_0m !< Intermediate UL term for SIM = PhiM qm0, size nL [-] - END TYPE SD_MiscVarType -! ======================= -! ========= SD_ParameterType ======= - TYPE, PUBLIC :: SD_ParameterType - REAL(DbKi) :: SDDeltaT !< Time step (for integration of continuous states) [seconds] - INTEGER(IntKi) :: IntMethod !< Integration Method (1/2/3)Length of y2 array [-] - INTEGER(IntKi) :: nDOF !< Total degree of freedom [-] - INTEGER(IntKi) :: nDOF_red !< Total degree of freedom after constraint reduction [-] - INTEGER(IntKi) :: Nmembers !< Number of members of the sub structure [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Elems !< Element nodes connections [-] - TYPE(ElemPropType) , DIMENSION(:), ALLOCATABLE :: ElemProps !< List of element properties [-] - REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: FG !< Gravity force vector (with initial cable force T0), not reduced [N] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: DP0 !< Vector from TP to a Node at t=0, used for Floating Rigid Body motion [m] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeID2JointID !< Store Joint ID for each NodeID since SubDyn re-label nodes (and add more nodes) [-] - LOGICAL :: reduced !< True if system has been reduced to account for constraints [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: T_red !< Transformation matrix performing the constraint reduction x = T. xtilde [-] - REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: T_red_T !< Transpose of T_red [-] - TYPE(IList) , DIMENSION(:), ALLOCATABLE :: NodesDOF !< DOF indices of each nodes in unconstrained assembled system [-] - TYPE(IList) , DIMENSION(:), ALLOCATABLE :: NodesDOFred !< DOF indices of each nodes in constrained assembled system [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElemsDOF !< 12 DOF indices of node 1 and 2 of a given member in unconstrained assembled system [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: DOFred2Nodes !< nDOFRed x 3, for each constrained DOF, col1 node index, col2 number of DOF, col3 DOF starting from 1 [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: CtrlElem2Channel !< nCtrlCable x 2, for each CtrlCable, Elem index, and Channel Index [-] - INTEGER(IntKi) :: nDOFM !< retained degrees of freedom (modes) [-] - INTEGER(IntKi) :: SttcSolve !< Solve dynamics about static equilibrium point (flag) [-] - LOGICAL :: GuyanLoadCorrection !< Add Extra lever arm contribution to interface reaction outputs [-] - LOGICAL :: Floating !< True if floating bottom (the 6 DOF are free at all reaction nodes) [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: KMMDiag !< Diagonal coefficients of Kmm (OmegaM squared) [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: CMMDiag !< Diagonal coefficients of Cmm (~2 Zeta OmegaM)) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MMB !< Matrix after C-B reduction (transpose of MBM [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBmmB !< MBm * MmB, used for Y1 [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C1_11 !< Coefficient of x in Y1 [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C1_12 !< Coefficient of x in Y1 [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D1_141 !< MBm PhiM^T [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D1_142 !< TI^T PhiR^T [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiM !< Coefficient of x in Y2 [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C2_61 !< Coefficient of x in Y2 (URdotdot ULdotdot) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C2_62 !< Coefficient of x in Y2 (URdotdot ULdotdot) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiRb_TI !< Coefficient of u in Y2 (Phi_R bar * TI) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D2_63 !< Coefficient of u in Y2 (URdotdot ULdotdot) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D2_64 !< Coefficient of u in Y2 (URdotdot ULdotdot) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBB !< Guyan Mass Matrix after C-B reduction [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: KBB !< Guyan Stiffness Matrix after C-B reduction [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CBB !< Guyan Damping Matrix after C-B reduction [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CMM !< CB damping matrix [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBM !< Matrix after C-B reduction [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiL_T !< Transpose of Matrix of C-B modes [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiLInvOmgL2 !< Matrix of C-B modes times the inverse of OmegaL**2 (Phi_L*(Omg**2)^-1) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: KLLm1 !< KLL^{-1}, inverse of matrix KLL, for static solve only [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: AM2Jac !< Jacobian (factored) for Adams-Boulton 2nd order Integration [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: AM2JacPiv !< Pivot array for Jacobian factorization (for Adams-Boulton 2nd order Integration) [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: TI !< Matrix to calculate TP reference point reaction at top of structure [-] - REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: TIreact !< Matrix to calculate single point reaction at base of structure [-] - INTEGER(IntKi) :: nNodes !< Total number of nodes [-] - INTEGER(IntKi) :: nNodes_I !< Number of Interface nodes [-] - INTEGER(IntKi) :: nNodes_L !< Number of Internal nodes [-] - INTEGER(IntKi) :: nNodes_C !< Number of joints with reactions [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_I !< Interface degree of freedoms [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_L !< Internal nodes (not interface nor reaction) [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_C !< React degree of freedoms [-] - INTEGER(IntKi) :: nDOFI__ !< Size of IDI__ [-] - INTEGER(IntKi) :: nDOFI_Rb !< Size of IDI_Rb [-] - INTEGER(IntKi) :: nDOFI_F !< Size of IDI_F [-] - INTEGER(IntKi) :: nDOFL_L !< Size of IDL_L [-] - INTEGER(IntKi) :: nDOFC__ !< Size of IDC__ [-] - INTEGER(IntKi) :: nDOFC_Rb !< Size of IDC_Rb [-] - INTEGER(IntKi) :: nDOFC_L !< Size of IDC_L [-] - INTEGER(IntKi) :: nDOFC_F !< Size of IDC_F [-] - INTEGER(IntKi) :: nDOFR__ !< Size of IDR__ [-] - INTEGER(IntKi) :: nDOF__Rb !< Size of ID__Rb [-] - INTEGER(IntKi) :: nDOF__L !< Size of ID__L [-] - INTEGER(IntKi) :: nDOF__F !< Size of ID__F [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI__ !< Index of all Interface DOFs [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI_Rb !< Index array of the interface (nodes connect to TP) dofs that are retained/master/follower DOFs [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI_F !< Index array of the interface (nodes connect to TP) dofs that are fixed DOF [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDL_L !< Index array of the internal dofs coming from internal nodes [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC__ !< Index of all bottom DOF [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_Rb !< Index array of the contraint dofs that are retained/master/follower DOF [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_L !< Index array of the contraint dofs that are follower/internal DOF [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_F !< Index array of the contraint dofs that are fixd DOF [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDR__ !< Index array of the interface and restraint dofs [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__Rb !< Index array of all the retained/leader/master dofs (from any nodes of the structure) [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__L !< Index array of all the follower/internal dofs (from any nodes of the structure) [-] - INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__F !< Index array of the DOF that are fixed (from any nodes of the structure) [-] - INTEGER(IntKi) :: NMOutputs !< Number of members whose output is written [-] - INTEGER(IntKi) :: NumOuts !< Number of output channels read from input file [-] - INTEGER(IntKi) :: OutSwtch !< Output Requested Channels to local or global output file [1/2/3] [-] - INTEGER(IntKi) :: UnJckF !< Unit of SD ouput file [-] - CHARACTER(1) :: Delim !< Column delimiter for output text files [-] - CHARACTER(20) :: OutFmt !< Format for Output [-] - CHARACTER(20) :: OutSFmt !< Format for Output Headers [-] - TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst !< List of user requested members and nodes [-] - TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst2 !< List of all member joint nodes and elements for output [-] - TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst3 !< List of all member joint nodes and elements for output [-] - TYPE(OutParmType) , DIMENSION(:), ALLOCATABLE :: OutParam !< An array holding names, units, and indices of all of the selected output channels. logical [-] - LOGICAL :: OutAll !< Flag to output or not all joint forces [-] - INTEGER(IntKi) :: OutCBModes !< Flag to output CB and Guyan modes to a given format [-] - INTEGER(IntKi) :: OutFEMModes !< Flag to output FEM modes to a given format [-] - LOGICAL :: OutReact !< Flag to check whether reactions are requested [-] - INTEGER(IntKi) :: OutAllInt !< Integer version of OutAll [-] - INTEGER(IntKi) :: OutAllDims !< Integer version of OutAll [-] - INTEGER(IntKi) :: OutDec !< Output Decimation for Requested Channels [-] - INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Jac_u_indx !< matrix to help fill/pack the u vector in computing the jacobian [-] - REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: du !< vector that determines size of perturbation for u (inputs) [-] - REAL(R8Ki) , DIMENSION(1:2) :: dx !< vector that determines size of perturbation for x (continuous states) [-] - INTEGER(IntKi) :: Jac_ny !< number of outputs in jacobian matrix [-] - INTEGER(IntKi) :: Jac_nx !< half the number of continuous states in jacobian matrix [-] - LOGICAL :: RotStates !< Orient states in rotating frame during linearization? (flag) [-] - END TYPE SD_ParameterType -! ======================= -! ========= SD_InputType ======= - TYPE, PUBLIC :: SD_InputType - TYPE(MeshType) :: TPMesh !< Transition piece inputs on a point mesh [-] - TYPE(MeshType) :: LMesh !< Point mesh for interior node inputs [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: CableDeltaL !< Cable tension, control input [-] - END TYPE SD_InputType -! ======================= -! ========= SD_OutputType ======= - TYPE, PUBLIC :: SD_OutputType - TYPE(MeshType) :: Y1Mesh !< Transition piece outputs on a point mesh [-] - TYPE(MeshType) :: Y2Mesh !< Interior+Interface nodes rigid body displacements + elastic velocities and accelerations on a point mesh [-] - TYPE(MeshType) :: Y3Mesh !< Interior+Interface nodes full elastic displacements/velocities and accelerations on a point mesh [-] - REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: WriteOutput !< Data to be written to an output file [-] - END TYPE SD_OutputType -! ======================= -CONTAINS - SUBROUTINE SD_CopyIList( SrcIListData, DstIListData, CtrlCode, ErrStat, ErrMsg ) - TYPE(IList), INTENT(IN) :: SrcIListData - TYPE(IList), INTENT(INOUT) :: DstIListData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyIList' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcIListData%List)) THEN - i1_l = LBOUND(SrcIListData%List,1) - i1_u = UBOUND(SrcIListData%List,1) - IF (.NOT. ALLOCATED(DstIListData%List)) THEN - ALLOCATE(DstIListData%List(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstIListData%List.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstIListData%List = SrcIListData%List -ENDIF - END SUBROUTINE SD_CopyIList - - SUBROUTINE SD_DestroyIList( IListData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(IList), INTENT(INOUT) :: IListData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyIList' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(IListData%List)) THEN - DEALLOCATE(IListData%List) -ENDIF - END SUBROUTINE SD_DestroyIList - - SUBROUTINE SD_PackIList( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(IList), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackIList' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! List allocated yes/no - IF ( ALLOCATED(InData%List) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! List upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%List) ! List - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%List) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%List,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%List,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%List,1), UBOUND(InData%List,1) - IntKiBuf(Int_Xferred) = InData%List(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackIList - - SUBROUTINE SD_UnPackIList( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(IList), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackIList' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! List not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%List)) DEALLOCATE(OutData%List) - ALLOCATE(OutData%List(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%List.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%List,1), UBOUND(OutData%List,1) - OutData%List(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackIList - - SUBROUTINE SD_CopyMeshAuxDataType( SrcMeshAuxDataTypeData, DstMeshAuxDataTypeData, CtrlCode, ErrStat, ErrMsg ) - TYPE(MeshAuxDataType), INTENT(IN) :: SrcMeshAuxDataTypeData - TYPE(MeshAuxDataType), INTENT(INOUT) :: DstMeshAuxDataTypeData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyMeshAuxDataType' -! - ErrStat = ErrID_None - ErrMsg = "" - DstMeshAuxDataTypeData%MemberID = SrcMeshAuxDataTypeData%MemberID - DstMeshAuxDataTypeData%NOutCnt = SrcMeshAuxDataTypeData%NOutCnt -IF (ALLOCATED(SrcMeshAuxDataTypeData%NodeCnt)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%NodeCnt,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%NodeCnt,1) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%NodeCnt)) THEN - ALLOCATE(DstMeshAuxDataTypeData%NodeCnt(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%NodeCnt.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%NodeCnt = SrcMeshAuxDataTypeData%NodeCnt -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%NodeIDs)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%NodeIDs,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%NodeIDs,1) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%NodeIDs)) THEN - ALLOCATE(DstMeshAuxDataTypeData%NodeIDs(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%NodeIDs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%NodeIDs = SrcMeshAuxDataTypeData%NodeIDs -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%ElmIDs)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%ElmIDs,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%ElmIDs,1) - i2_l = LBOUND(SrcMeshAuxDataTypeData%ElmIDs,2) - i2_u = UBOUND(SrcMeshAuxDataTypeData%ElmIDs,2) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%ElmIDs)) THEN - ALLOCATE(DstMeshAuxDataTypeData%ElmIDs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%ElmIDs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%ElmIDs = SrcMeshAuxDataTypeData%ElmIDs -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%ElmNds)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%ElmNds,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%ElmNds,1) - i2_l = LBOUND(SrcMeshAuxDataTypeData%ElmNds,2) - i2_u = UBOUND(SrcMeshAuxDataTypeData%ElmNds,2) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%ElmNds)) THEN - ALLOCATE(DstMeshAuxDataTypeData%ElmNds(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%ElmNds.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%ElmNds = SrcMeshAuxDataTypeData%ElmNds -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%Me)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%Me,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%Me,1) - i2_l = LBOUND(SrcMeshAuxDataTypeData%Me,2) - i2_u = UBOUND(SrcMeshAuxDataTypeData%Me,2) - i3_l = LBOUND(SrcMeshAuxDataTypeData%Me,3) - i3_u = UBOUND(SrcMeshAuxDataTypeData%Me,3) - i4_l = LBOUND(SrcMeshAuxDataTypeData%Me,4) - i4_u = UBOUND(SrcMeshAuxDataTypeData%Me,4) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Me)) THEN - ALLOCATE(DstMeshAuxDataTypeData%Me(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Me.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%Me = SrcMeshAuxDataTypeData%Me -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%Ke)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%Ke,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%Ke,1) - i2_l = LBOUND(SrcMeshAuxDataTypeData%Ke,2) - i2_u = UBOUND(SrcMeshAuxDataTypeData%Ke,2) - i3_l = LBOUND(SrcMeshAuxDataTypeData%Ke,3) - i3_u = UBOUND(SrcMeshAuxDataTypeData%Ke,3) - i4_l = LBOUND(SrcMeshAuxDataTypeData%Ke,4) - i4_u = UBOUND(SrcMeshAuxDataTypeData%Ke,4) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Ke)) THEN - ALLOCATE(DstMeshAuxDataTypeData%Ke(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Ke.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%Ke = SrcMeshAuxDataTypeData%Ke -ENDIF -IF (ALLOCATED(SrcMeshAuxDataTypeData%Fg)) THEN - i1_l = LBOUND(SrcMeshAuxDataTypeData%Fg,1) - i1_u = UBOUND(SrcMeshAuxDataTypeData%Fg,1) - i2_l = LBOUND(SrcMeshAuxDataTypeData%Fg,2) - i2_u = UBOUND(SrcMeshAuxDataTypeData%Fg,2) - i3_l = LBOUND(SrcMeshAuxDataTypeData%Fg,3) - i3_u = UBOUND(SrcMeshAuxDataTypeData%Fg,3) - IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Fg)) THEN - ALLOCATE(DstMeshAuxDataTypeData%Fg(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Fg.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMeshAuxDataTypeData%Fg = SrcMeshAuxDataTypeData%Fg -ENDIF - END SUBROUTINE SD_CopyMeshAuxDataType - - SUBROUTINE SD_DestroyMeshAuxDataType( MeshAuxDataTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(MeshAuxDataType), INTENT(INOUT) :: MeshAuxDataTypeData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyMeshAuxDataType' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(MeshAuxDataTypeData%NodeCnt)) THEN - DEALLOCATE(MeshAuxDataTypeData%NodeCnt) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%NodeIDs)) THEN - DEALLOCATE(MeshAuxDataTypeData%NodeIDs) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%ElmIDs)) THEN - DEALLOCATE(MeshAuxDataTypeData%ElmIDs) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%ElmNds)) THEN - DEALLOCATE(MeshAuxDataTypeData%ElmNds) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%Me)) THEN - DEALLOCATE(MeshAuxDataTypeData%Me) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%Ke)) THEN - DEALLOCATE(MeshAuxDataTypeData%Ke) -ENDIF -IF (ALLOCATED(MeshAuxDataTypeData%Fg)) THEN - DEALLOCATE(MeshAuxDataTypeData%Fg) -ENDIF - END SUBROUTINE SD_DestroyMeshAuxDataType - - SUBROUTINE SD_PackMeshAuxDataType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(MeshAuxDataType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackMeshAuxDataType' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! MemberID - Int_BufSz = Int_BufSz + 1 ! NOutCnt - Int_BufSz = Int_BufSz + 1 ! NodeCnt allocated yes/no - IF ( ALLOCATED(InData%NodeCnt) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! NodeCnt upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%NodeCnt) ! NodeCnt - END IF - Int_BufSz = Int_BufSz + 1 ! NodeIDs allocated yes/no - IF ( ALLOCATED(InData%NodeIDs) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! NodeIDs upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%NodeIDs) ! NodeIDs - END IF - Int_BufSz = Int_BufSz + 1 ! ElmIDs allocated yes/no - IF ( ALLOCATED(InData%ElmIDs) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! ElmIDs upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ElmIDs) ! ElmIDs - END IF - Int_BufSz = Int_BufSz + 1 ! ElmNds allocated yes/no - IF ( ALLOCATED(InData%ElmNds) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! ElmNds upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ElmNds) ! ElmNds - END IF - Int_BufSz = Int_BufSz + 1 ! Me allocated yes/no - IF ( ALLOCATED(InData%Me) ) THEN - Int_BufSz = Int_BufSz + 2*4 ! Me upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%Me) ! Me - END IF - Int_BufSz = Int_BufSz + 1 ! Ke allocated yes/no - IF ( ALLOCATED(InData%Ke) ) THEN - Int_BufSz = Int_BufSz + 2*4 ! Ke upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%Ke) ! Ke - END IF - Int_BufSz = Int_BufSz + 1 ! Fg allocated yes/no - IF ( ALLOCATED(InData%Fg) ) THEN - Int_BufSz = Int_BufSz + 2*3 ! Fg upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%Fg) ! Fg - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IntKiBuf(Int_Xferred) = InData%MemberID - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NOutCnt - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%NodeCnt) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeCnt,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeCnt,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%NodeCnt,1), UBOUND(InData%NodeCnt,1) - IntKiBuf(Int_Xferred) = InData%NodeCnt(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodeIDs) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeIDs,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeIDs,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%NodeIDs,1), UBOUND(InData%NodeIDs,1) - IntKiBuf(Int_Xferred) = InData%NodeIDs(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ElmIDs) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmIDs,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmIDs,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmIDs,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmIDs,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%ElmIDs,2), UBOUND(InData%ElmIDs,2) - DO i1 = LBOUND(InData%ElmIDs,1), UBOUND(InData%ElmIDs,1) - IntKiBuf(Int_Xferred) = InData%ElmIDs(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ElmNds) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmNds,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmNds,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmNds,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmNds,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%ElmNds,2), UBOUND(InData%ElmNds,2) - DO i1 = LBOUND(InData%ElmNds,1), UBOUND(InData%ElmNds,1) - IntKiBuf(Int_Xferred) = InData%ElmNds(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Me) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,2) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,3) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,3) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,4) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,4) - Int_Xferred = Int_Xferred + 2 - - DO i4 = LBOUND(InData%Me,4), UBOUND(InData%Me,4) - DO i3 = LBOUND(InData%Me,3), UBOUND(InData%Me,3) - DO i2 = LBOUND(InData%Me,2), UBOUND(InData%Me,2) - DO i1 = LBOUND(InData%Me,1), UBOUND(InData%Me,1) - DbKiBuf(Db_Xferred) = InData%Me(i1,i2,i3,i4) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Ke) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,2) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,3) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,3) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,4) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,4) - Int_Xferred = Int_Xferred + 2 - - DO i4 = LBOUND(InData%Ke,4), UBOUND(InData%Ke,4) - DO i3 = LBOUND(InData%Ke,3), UBOUND(InData%Ke,3) - DO i2 = LBOUND(InData%Ke,2), UBOUND(InData%Ke,2) - DO i1 = LBOUND(InData%Ke,1), UBOUND(InData%Ke,1) - DbKiBuf(Db_Xferred) = InData%Ke(i1,i2,i3,i4) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Fg) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,2) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,3) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,3) - Int_Xferred = Int_Xferred + 2 - - DO i3 = LBOUND(InData%Fg,3), UBOUND(InData%Fg,3) - DO i2 = LBOUND(InData%Fg,2), UBOUND(InData%Fg,2) - DO i1 = LBOUND(InData%Fg,1), UBOUND(InData%Fg,1) - DbKiBuf(Db_Xferred) = InData%Fg(i1,i2,i3) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END IF - END SUBROUTINE SD_PackMeshAuxDataType - - SUBROUTINE SD_UnPackMeshAuxDataType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(MeshAuxDataType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackMeshAuxDataType' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - OutData%MemberID = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NOutCnt = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeCnt not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodeCnt)) DEALLOCATE(OutData%NodeCnt) - ALLOCATE(OutData%NodeCnt(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeCnt.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%NodeCnt,1), UBOUND(OutData%NodeCnt,1) - OutData%NodeCnt(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeIDs not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodeIDs)) DEALLOCATE(OutData%NodeIDs) - ALLOCATE(OutData%NodeIDs(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeIDs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%NodeIDs,1), UBOUND(OutData%NodeIDs,1) - OutData%NodeIDs(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElmIDs not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ElmIDs)) DEALLOCATE(OutData%ElmIDs) - ALLOCATE(OutData%ElmIDs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElmIDs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%ElmIDs,2), UBOUND(OutData%ElmIDs,2) - DO i1 = LBOUND(OutData%ElmIDs,1), UBOUND(OutData%ElmIDs,1) - OutData%ElmIDs(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElmNds not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ElmNds)) DEALLOCATE(OutData%ElmNds) - ALLOCATE(OutData%ElmNds(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElmNds.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%ElmNds,2), UBOUND(OutData%ElmNds,2) - DO i1 = LBOUND(OutData%ElmNds,1), UBOUND(OutData%ElmNds,1) - OutData%ElmNds(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Me not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i3_l = IntKiBuf( Int_Xferred ) - i3_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i4_l = IntKiBuf( Int_Xferred ) - i4_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Me)) DEALLOCATE(OutData%Me) - ALLOCATE(OutData%Me(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Me.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i4 = LBOUND(OutData%Me,4), UBOUND(OutData%Me,4) - DO i3 = LBOUND(OutData%Me,3), UBOUND(OutData%Me,3) - DO i2 = LBOUND(OutData%Me,2), UBOUND(OutData%Me,2) - DO i1 = LBOUND(OutData%Me,1), UBOUND(OutData%Me,1) - OutData%Me(i1,i2,i3,i4) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Ke not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i3_l = IntKiBuf( Int_Xferred ) - i3_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i4_l = IntKiBuf( Int_Xferred ) - i4_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Ke)) DEALLOCATE(OutData%Ke) - ALLOCATE(OutData%Ke(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Ke.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i4 = LBOUND(OutData%Ke,4), UBOUND(OutData%Ke,4) - DO i3 = LBOUND(OutData%Ke,3), UBOUND(OutData%Ke,3) - DO i2 = LBOUND(OutData%Ke,2), UBOUND(OutData%Ke,2) - DO i1 = LBOUND(OutData%Ke,1), UBOUND(OutData%Ke,1) - OutData%Ke(i1,i2,i3,i4) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fg not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i3_l = IntKiBuf( Int_Xferred ) - i3_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Fg)) DEALLOCATE(OutData%Fg) - ALLOCATE(OutData%Fg(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fg.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i3 = LBOUND(OutData%Fg,3), UBOUND(OutData%Fg,3) - DO i2 = LBOUND(OutData%Fg,2), UBOUND(OutData%Fg,2) - DO i1 = LBOUND(OutData%Fg,1), UBOUND(OutData%Fg,1) - OutData%Fg(i1,i2,i3) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END DO - END IF - END SUBROUTINE SD_UnPackMeshAuxDataType - - SUBROUTINE SD_CopyCB_MatArrays( SrcCB_MatArraysData, DstCB_MatArraysData, CtrlCode, ErrStat, ErrMsg ) - TYPE(CB_MatArrays), INTENT(IN) :: SrcCB_MatArraysData - TYPE(CB_MatArrays), INTENT(INOUT) :: DstCB_MatArraysData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyCB_MatArrays' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcCB_MatArraysData%MBB)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%MBB,1) - i1_u = UBOUND(SrcCB_MatArraysData%MBB,1) - i2_l = LBOUND(SrcCB_MatArraysData%MBB,2) - i2_u = UBOUND(SrcCB_MatArraysData%MBB,2) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%MBB)) THEN - ALLOCATE(DstCB_MatArraysData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%MBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%MBB = SrcCB_MatArraysData%MBB -ENDIF -IF (ALLOCATED(SrcCB_MatArraysData%MBM)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%MBM,1) - i1_u = UBOUND(SrcCB_MatArraysData%MBM,1) - i2_l = LBOUND(SrcCB_MatArraysData%MBM,2) - i2_u = UBOUND(SrcCB_MatArraysData%MBM,2) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%MBM)) THEN - ALLOCATE(DstCB_MatArraysData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%MBM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%MBM = SrcCB_MatArraysData%MBM -ENDIF -IF (ALLOCATED(SrcCB_MatArraysData%KBB)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%KBB,1) - i1_u = UBOUND(SrcCB_MatArraysData%KBB,1) - i2_l = LBOUND(SrcCB_MatArraysData%KBB,2) - i2_u = UBOUND(SrcCB_MatArraysData%KBB,2) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%KBB)) THEN - ALLOCATE(DstCB_MatArraysData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%KBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%KBB = SrcCB_MatArraysData%KBB -ENDIF -IF (ALLOCATED(SrcCB_MatArraysData%PhiL)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%PhiL,1) - i1_u = UBOUND(SrcCB_MatArraysData%PhiL,1) - i2_l = LBOUND(SrcCB_MatArraysData%PhiL,2) - i2_u = UBOUND(SrcCB_MatArraysData%PhiL,2) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%PhiL)) THEN - ALLOCATE(DstCB_MatArraysData%PhiL(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%PhiL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%PhiL = SrcCB_MatArraysData%PhiL -ENDIF -IF (ALLOCATED(SrcCB_MatArraysData%PhiR)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%PhiR,1) - i1_u = UBOUND(SrcCB_MatArraysData%PhiR,1) - i2_l = LBOUND(SrcCB_MatArraysData%PhiR,2) - i2_u = UBOUND(SrcCB_MatArraysData%PhiR,2) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%PhiR)) THEN - ALLOCATE(DstCB_MatArraysData%PhiR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%PhiR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%PhiR = SrcCB_MatArraysData%PhiR -ENDIF -IF (ALLOCATED(SrcCB_MatArraysData%OmegaL)) THEN - i1_l = LBOUND(SrcCB_MatArraysData%OmegaL,1) - i1_u = UBOUND(SrcCB_MatArraysData%OmegaL,1) - IF (.NOT. ALLOCATED(DstCB_MatArraysData%OmegaL)) THEN - ALLOCATE(DstCB_MatArraysData%OmegaL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%OmegaL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstCB_MatArraysData%OmegaL = SrcCB_MatArraysData%OmegaL -ENDIF - END SUBROUTINE SD_CopyCB_MatArrays - - SUBROUTINE SD_DestroyCB_MatArrays( CB_MatArraysData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(CB_MatArrays), INTENT(INOUT) :: CB_MatArraysData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyCB_MatArrays' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(CB_MatArraysData%MBB)) THEN - DEALLOCATE(CB_MatArraysData%MBB) -ENDIF -IF (ALLOCATED(CB_MatArraysData%MBM)) THEN - DEALLOCATE(CB_MatArraysData%MBM) -ENDIF -IF (ALLOCATED(CB_MatArraysData%KBB)) THEN - DEALLOCATE(CB_MatArraysData%KBB) -ENDIF -IF (ALLOCATED(CB_MatArraysData%PhiL)) THEN - DEALLOCATE(CB_MatArraysData%PhiL) -ENDIF -IF (ALLOCATED(CB_MatArraysData%PhiR)) THEN - DEALLOCATE(CB_MatArraysData%PhiR) -ENDIF -IF (ALLOCATED(CB_MatArraysData%OmegaL)) THEN - DEALLOCATE(CB_MatArraysData%OmegaL) -ENDIF - END SUBROUTINE SD_DestroyCB_MatArrays - - SUBROUTINE SD_PackCB_MatArrays( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(CB_MatArrays), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackCB_MatArrays' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! MBB allocated yes/no - IF ( ALLOCATED(InData%MBB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MBB upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%MBB) ! MBB - END IF - Int_BufSz = Int_BufSz + 1 ! MBM allocated yes/no - IF ( ALLOCATED(InData%MBM) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MBM upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%MBM) ! MBM - END IF - Int_BufSz = Int_BufSz + 1 ! KBB allocated yes/no - IF ( ALLOCATED(InData%KBB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! KBB upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%KBB) ! KBB - END IF - Int_BufSz = Int_BufSz + 1 ! PhiL allocated yes/no - IF ( ALLOCATED(InData%PhiL) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiL upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%PhiL) ! PhiL - END IF - Int_BufSz = Int_BufSz + 1 ! PhiR allocated yes/no - IF ( ALLOCATED(InData%PhiR) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiR upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%PhiR) ! PhiR - END IF - Int_BufSz = Int_BufSz + 1 ! OmegaL allocated yes/no - IF ( ALLOCATED(InData%OmegaL) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! OmegaL upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%OmegaL) ! OmegaL - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%MBB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MBB,2), UBOUND(InData%MBB,2) - DO i1 = LBOUND(InData%MBB,1), UBOUND(InData%MBB,1) - DbKiBuf(Db_Xferred) = InData%MBB(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MBM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MBM,2), UBOUND(InData%MBM,2) - DO i1 = LBOUND(InData%MBM,1), UBOUND(InData%MBM,1) - DbKiBuf(Db_Xferred) = InData%MBM(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%KBB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%KBB,2), UBOUND(InData%KBB,2) - DO i1 = LBOUND(InData%KBB,1), UBOUND(InData%KBB,1) - DbKiBuf(Db_Xferred) = InData%KBB(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiL) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiL,2), UBOUND(InData%PhiL,2) - DO i1 = LBOUND(InData%PhiL,1), UBOUND(InData%PhiL,1) - DbKiBuf(Db_Xferred) = InData%PhiL(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiR) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiR,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiR,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiR,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiR,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiR,2), UBOUND(InData%PhiR,2) - DO i1 = LBOUND(InData%PhiR,1), UBOUND(InData%PhiR,1) - DbKiBuf(Db_Xferred) = InData%PhiR(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%OmegaL) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%OmegaL,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%OmegaL,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%OmegaL,1), UBOUND(InData%OmegaL,1) - DbKiBuf(Db_Xferred) = InData%OmegaL(i1) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackCB_MatArrays - - SUBROUTINE SD_UnPackCB_MatArrays( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(CB_MatArrays), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackCB_MatArrays' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MBB)) DEALLOCATE(OutData%MBB) - ALLOCATE(OutData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MBB,2), UBOUND(OutData%MBB,2) - DO i1 = LBOUND(OutData%MBB,1), UBOUND(OutData%MBB,1) - OutData%MBB(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MBM)) DEALLOCATE(OutData%MBM) - ALLOCATE(OutData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MBM,2), UBOUND(OutData%MBM,2) - DO i1 = LBOUND(OutData%MBM,1), UBOUND(OutData%MBM,1) - OutData%MBM(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KBB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%KBB)) DEALLOCATE(OutData%KBB) - ALLOCATE(OutData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%KBB,2), UBOUND(OutData%KBB,2) - DO i1 = LBOUND(OutData%KBB,1), UBOUND(OutData%KBB,1) - OutData%KBB(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiL not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiL)) DEALLOCATE(OutData%PhiL) - ALLOCATE(OutData%PhiL(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiL,2), UBOUND(OutData%PhiL,2) - DO i1 = LBOUND(OutData%PhiL,1), UBOUND(OutData%PhiL,1) - OutData%PhiL(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiR not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiR)) DEALLOCATE(OutData%PhiR) - ALLOCATE(OutData%PhiR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiR,2), UBOUND(OutData%PhiR,2) - DO i1 = LBOUND(OutData%PhiR,1), UBOUND(OutData%PhiR,1) - OutData%PhiR(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! OmegaL not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%OmegaL)) DEALLOCATE(OutData%OmegaL) - ALLOCATE(OutData%OmegaL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%OmegaL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%OmegaL,1), UBOUND(OutData%OmegaL,1) - OutData%OmegaL(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackCB_MatArrays - - SUBROUTINE SD_CopyElemPropType( SrcElemPropTypeData, DstElemPropTypeData, CtrlCode, ErrStat, ErrMsg ) - TYPE(ElemPropType), INTENT(IN) :: SrcElemPropTypeData - TYPE(ElemPropType), INTENT(INOUT) :: DstElemPropTypeData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyElemPropType' -! - ErrStat = ErrID_None - ErrMsg = "" - DstElemPropTypeData%eType = SrcElemPropTypeData%eType - DstElemPropTypeData%Length = SrcElemPropTypeData%Length - DstElemPropTypeData%Ixx = SrcElemPropTypeData%Ixx - DstElemPropTypeData%Iyy = SrcElemPropTypeData%Iyy - DstElemPropTypeData%Jzz = SrcElemPropTypeData%Jzz - DstElemPropTypeData%Shear = SrcElemPropTypeData%Shear - DstElemPropTypeData%Kappa_x = SrcElemPropTypeData%Kappa_x - DstElemPropTypeData%Kappa_y = SrcElemPropTypeData%Kappa_y - DstElemPropTypeData%YoungE = SrcElemPropTypeData%YoungE - DstElemPropTypeData%ShearG = SrcElemPropTypeData%ShearG - DstElemPropTypeData%D = SrcElemPropTypeData%D - DstElemPropTypeData%Area = SrcElemPropTypeData%Area - DstElemPropTypeData%Rho = SrcElemPropTypeData%Rho - DstElemPropTypeData%T0 = SrcElemPropTypeData%T0 - DstElemPropTypeData%k11 = SrcElemPropTypeData%k11 - DstElemPropTypeData%k12 = SrcElemPropTypeData%k12 - DstElemPropTypeData%k13 = SrcElemPropTypeData%k13 - DstElemPropTypeData%k14 = SrcElemPropTypeData%k14 - DstElemPropTypeData%k15 = SrcElemPropTypeData%k15 - DstElemPropTypeData%k16 = SrcElemPropTypeData%k16 - DstElemPropTypeData%k22 = SrcElemPropTypeData%k22 - DstElemPropTypeData%k23 = SrcElemPropTypeData%k23 - DstElemPropTypeData%k24 = SrcElemPropTypeData%k24 - DstElemPropTypeData%k25 = SrcElemPropTypeData%k25 - DstElemPropTypeData%k26 = SrcElemPropTypeData%k26 - DstElemPropTypeData%k33 = SrcElemPropTypeData%k33 - DstElemPropTypeData%k34 = SrcElemPropTypeData%k34 - DstElemPropTypeData%k35 = SrcElemPropTypeData%k35 - DstElemPropTypeData%k36 = SrcElemPropTypeData%k36 - DstElemPropTypeData%k44 = SrcElemPropTypeData%k44 - DstElemPropTypeData%k45 = SrcElemPropTypeData%k45 - DstElemPropTypeData%k46 = SrcElemPropTypeData%k46 - DstElemPropTypeData%k55 = SrcElemPropTypeData%k55 - DstElemPropTypeData%k56 = SrcElemPropTypeData%k56 - DstElemPropTypeData%k66 = SrcElemPropTypeData%k66 - DstElemPropTypeData%DirCos = SrcElemPropTypeData%DirCos - END SUBROUTINE SD_CopyElemPropType - - SUBROUTINE SD_DestroyElemPropType( ElemPropTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(ElemPropType), INTENT(INOUT) :: ElemPropTypeData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyElemPropType' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - - END SUBROUTINE SD_DestroyElemPropType - - SUBROUTINE SD_PackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(ElemPropType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackElemPropType' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! eType - Re_BufSz = Re_BufSz + 1 ! Length - Re_BufSz = Re_BufSz + 1 ! Ixx - Re_BufSz = Re_BufSz + 1 ! Iyy - Re_BufSz = Re_BufSz + 1 ! Jzz - Int_BufSz = Int_BufSz + 1 ! Shear - Re_BufSz = Re_BufSz + 1 ! Kappa_x - Re_BufSz = Re_BufSz + 1 ! Kappa_y - Re_BufSz = Re_BufSz + 1 ! YoungE - Re_BufSz = Re_BufSz + 1 ! ShearG - Re_BufSz = Re_BufSz + SIZE(InData%D) ! D - Re_BufSz = Re_BufSz + 1 ! Area - Re_BufSz = Re_BufSz + 1 ! Rho - Re_BufSz = Re_BufSz + 1 ! T0 - Re_BufSz = Re_BufSz + 1 ! k11 - Re_BufSz = Re_BufSz + 1 ! k12 - Re_BufSz = Re_BufSz + 1 ! k13 - Re_BufSz = Re_BufSz + 1 ! k14 - Re_BufSz = Re_BufSz + 1 ! k15 - Re_BufSz = Re_BufSz + 1 ! k16 - Re_BufSz = Re_BufSz + 1 ! k22 - Re_BufSz = Re_BufSz + 1 ! k23 - Re_BufSz = Re_BufSz + 1 ! k24 - Re_BufSz = Re_BufSz + 1 ! k25 - Re_BufSz = Re_BufSz + 1 ! k26 - Re_BufSz = Re_BufSz + 1 ! k33 - Re_BufSz = Re_BufSz + 1 ! k34 - Re_BufSz = Re_BufSz + 1 ! k35 - Re_BufSz = Re_BufSz + 1 ! k36 - Re_BufSz = Re_BufSz + 1 ! k44 - Re_BufSz = Re_BufSz + 1 ! k45 - Re_BufSz = Re_BufSz + 1 ! k46 - Re_BufSz = Re_BufSz + 1 ! k55 - Re_BufSz = Re_BufSz + 1 ! k56 - Re_BufSz = Re_BufSz + 1 ! k66 - Db_BufSz = Db_BufSz + SIZE(InData%DirCos) ! DirCos - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IntKiBuf(Int_Xferred) = InData%eType - Int_Xferred = Int_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Length - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Ixx - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Iyy - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Jzz - Re_Xferred = Re_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%Shear, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Kappa_x - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Kappa_y - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%YoungE - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%ShearG - Re_Xferred = Re_Xferred + 1 - DO i1 = LBOUND(InData%D,1), UBOUND(InData%D,1) - ReKiBuf(Re_Xferred) = InData%D(i1) - Re_Xferred = Re_Xferred + 1 - END DO - ReKiBuf(Re_Xferred) = InData%Area - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%Rho - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%T0 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k11 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k12 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k13 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k14 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k15 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k16 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k22 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k23 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k24 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k25 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k26 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k33 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k34 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k35 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k36 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k44 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k45 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k46 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k55 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k56 - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%k66 - Re_Xferred = Re_Xferred + 1 - DO i2 = LBOUND(InData%DirCos,2), UBOUND(InData%DirCos,2) - DO i1 = LBOUND(InData%DirCos,1), UBOUND(InData%DirCos,1) - DbKiBuf(Db_Xferred) = InData%DirCos(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END SUBROUTINE SD_PackElemPropType - - SUBROUTINE SD_UnPackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(ElemPropType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackElemPropType' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - OutData%eType = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%Length = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Ixx = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Iyy = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Jzz = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Shear = TRANSFER(IntKiBuf(Int_Xferred), OutData%Shear) - Int_Xferred = Int_Xferred + 1 - OutData%Kappa_x = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Kappa_y = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%YoungE = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%ShearG = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - i1_l = LBOUND(OutData%D,1) - i1_u = UBOUND(OutData%D,1) - DO i1 = LBOUND(OutData%D,1), UBOUND(OutData%D,1) - OutData%D(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - OutData%Area = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%Rho = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%T0 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k11 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k12 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k13 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k14 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k15 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k16 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k22 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k23 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k24 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k25 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k26 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k33 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k34 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k35 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k36 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k44 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k45 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k46 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k55 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k56 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%k66 = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - i1_l = LBOUND(OutData%DirCos,1) - i1_u = UBOUND(OutData%DirCos,1) - i2_l = LBOUND(OutData%DirCos,2) - i2_u = UBOUND(OutData%DirCos,2) - DO i2 = LBOUND(OutData%DirCos,2), UBOUND(OutData%DirCos,2) - DO i1 = LBOUND(OutData%DirCos,1), UBOUND(OutData%DirCos,1) - OutData%DirCos(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END SUBROUTINE SD_UnPackElemPropType - - SUBROUTINE SD_CopyInitInput( SrcInitInputData, DstInitInputData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_InitInputType), INTENT(INOUT) :: SrcInitInputData - TYPE(SD_InitInputType), INTENT(INOUT) :: DstInitInputData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitInput' -! - ErrStat = ErrID_None - ErrMsg = "" - DstInitInputData%SDInputFile = SrcInitInputData%SDInputFile - DstInitInputData%RootName = SrcInitInputData%RootName - DstInitInputData%g = SrcInitInputData%g - DstInitInputData%WtrDpth = SrcInitInputData%WtrDpth - DstInitInputData%TP_RefPoint = SrcInitInputData%TP_RefPoint - DstInitInputData%SubRotateZ = SrcInitInputData%SubRotateZ -IF (ALLOCATED(SrcInitInputData%SoilStiffness)) THEN - i1_l = LBOUND(SrcInitInputData%SoilStiffness,1) - i1_u = UBOUND(SrcInitInputData%SoilStiffness,1) - i2_l = LBOUND(SrcInitInputData%SoilStiffness,2) - i2_u = UBOUND(SrcInitInputData%SoilStiffness,2) - i3_l = LBOUND(SrcInitInputData%SoilStiffness,3) - i3_u = UBOUND(SrcInitInputData%SoilStiffness,3) - IF (.NOT. ALLOCATED(DstInitInputData%SoilStiffness)) THEN - ALLOCATE(DstInitInputData%SoilStiffness(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%SoilStiffness.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitInputData%SoilStiffness = SrcInitInputData%SoilStiffness -ENDIF - CALL MeshCopy( SrcInitInputData%SoilMesh, DstInitInputData%SoilMesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - DstInitInputData%Linearize = SrcInitInputData%Linearize - END SUBROUTINE SD_CopyInitInput - - SUBROUTINE SD_DestroyInitInput( InitInputData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_InitInputType), INTENT(INOUT) :: InitInputData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitInput' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(InitInputData%SoilStiffness)) THEN - DEALLOCATE(InitInputData%SoilStiffness) -ENDIF - CALL MeshDestroy( InitInputData%SoilMesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - END SUBROUTINE SD_DestroyInitInput - - SUBROUTINE SD_PackInitInput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_InitInputType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitInput' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1*LEN(InData%SDInputFile) ! SDInputFile - Int_BufSz = Int_BufSz + 1*LEN(InData%RootName) ! RootName - Re_BufSz = Re_BufSz + 1 ! g - Re_BufSz = Re_BufSz + 1 ! WtrDpth - Re_BufSz = Re_BufSz + SIZE(InData%TP_RefPoint) ! TP_RefPoint - Re_BufSz = Re_BufSz + 1 ! SubRotateZ - Int_BufSz = Int_BufSz + 1 ! SoilStiffness allocated yes/no - IF ( ALLOCATED(InData%SoilStiffness) ) THEN - Int_BufSz = Int_BufSz + 2*3 ! SoilStiffness upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%SoilStiffness) ! SoilStiffness - END IF - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - Int_BufSz = Int_BufSz + 3 ! SoilMesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! SoilMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! SoilMesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! SoilMesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! SoilMesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 1 ! Linearize - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - DO I = 1, LEN(InData%SDInputFile) - IntKiBuf(Int_Xferred) = ICHAR(InData%SDInputFile(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(InData%RootName) - IntKiBuf(Int_Xferred) = ICHAR(InData%RootName(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - ReKiBuf(Re_Xferred) = InData%g - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%WtrDpth - Re_Xferred = Re_Xferred + 1 - DO i1 = LBOUND(InData%TP_RefPoint,1), UBOUND(InData%TP_RefPoint,1) - ReKiBuf(Re_Xferred) = InData%TP_RefPoint(i1) - Re_Xferred = Re_Xferred + 1 - END DO - ReKiBuf(Re_Xferred) = InData%SubRotateZ - Re_Xferred = Re_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%SoilStiffness) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,2) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,3) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,3) - Int_Xferred = Int_Xferred + 2 - - DO i3 = LBOUND(InData%SoilStiffness,3), UBOUND(InData%SoilStiffness,3) - DO i2 = LBOUND(InData%SoilStiffness,2), UBOUND(InData%SoilStiffness,2) - DO i1 = LBOUND(InData%SoilStiffness,1), UBOUND(InData%SoilStiffness,1) - ReKiBuf(Re_Xferred) = InData%SoilStiffness(i1,i2,i3) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END DO - END IF - CALL MeshPack( InData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! SoilMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IntKiBuf(Int_Xferred) = TRANSFER(InData%Linearize, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_PackInitInput - - SUBROUTINE SD_UnPackInitInput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_InitInputType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitInput' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - DO I = 1, LEN(OutData%SDInputFile) - OutData%SDInputFile(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(OutData%RootName) - OutData%RootName(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - OutData%g = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%WtrDpth = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - i1_l = LBOUND(OutData%TP_RefPoint,1) - i1_u = UBOUND(OutData%TP_RefPoint,1) - DO i1 = LBOUND(OutData%TP_RefPoint,1), UBOUND(OutData%TP_RefPoint,1) - OutData%TP_RefPoint(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - OutData%SubRotateZ = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SoilStiffness not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i3_l = IntKiBuf( Int_Xferred ) - i3_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SoilStiffness)) DEALLOCATE(OutData%SoilStiffness) - ALLOCATE(OutData%SoilStiffness(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SoilStiffness.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i3 = LBOUND(OutData%SoilStiffness,3), UBOUND(OutData%SoilStiffness,3) - DO i2 = LBOUND(OutData%SoilStiffness,2), UBOUND(OutData%SoilStiffness,2) - DO i1 = LBOUND(OutData%SoilStiffness,1), UBOUND(OutData%SoilStiffness,1) - OutData%SoilStiffness(i1,i2,i3) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END DO - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! SoilMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - OutData%Linearize = TRANSFER(IntKiBuf(Int_Xferred), OutData%Linearize) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_UnPackInitInput - - SUBROUTINE SD_CopyInitOutput( SrcInitOutputData, DstInitOutputData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_InitOutputType), INTENT(IN) :: SrcInitOutputData - TYPE(SD_InitOutputType), INTENT(INOUT) :: DstInitOutputData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitOutput' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcInitOutputData%WriteOutputHdr)) THEN - i1_l = LBOUND(SrcInitOutputData%WriteOutputHdr,1) - i1_u = UBOUND(SrcInitOutputData%WriteOutputHdr,1) - IF (.NOT. ALLOCATED(DstInitOutputData%WriteOutputHdr)) THEN - ALLOCATE(DstInitOutputData%WriteOutputHdr(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%WriteOutputHdr.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%WriteOutputHdr = SrcInitOutputData%WriteOutputHdr -ENDIF -IF (ALLOCATED(SrcInitOutputData%WriteOutputUnt)) THEN - i1_l = LBOUND(SrcInitOutputData%WriteOutputUnt,1) - i1_u = UBOUND(SrcInitOutputData%WriteOutputUnt,1) - IF (.NOT. ALLOCATED(DstInitOutputData%WriteOutputUnt)) THEN - ALLOCATE(DstInitOutputData%WriteOutputUnt(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%WriteOutputUnt.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%WriteOutputUnt = SrcInitOutputData%WriteOutputUnt -ENDIF - CALL NWTC_Library_Copyprogdesc( SrcInitOutputData%Ver, DstInitOutputData%Ver, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN -IF (ALLOCATED(SrcInitOutputData%LinNames_y)) THEN - i1_l = LBOUND(SrcInitOutputData%LinNames_y,1) - i1_u = UBOUND(SrcInitOutputData%LinNames_y,1) - IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_y)) THEN - ALLOCATE(DstInitOutputData%LinNames_y(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_y.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%LinNames_y = SrcInitOutputData%LinNames_y -ENDIF -IF (ALLOCATED(SrcInitOutputData%LinNames_x)) THEN - i1_l = LBOUND(SrcInitOutputData%LinNames_x,1) - i1_u = UBOUND(SrcInitOutputData%LinNames_x,1) - IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_x)) THEN - ALLOCATE(DstInitOutputData%LinNames_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%LinNames_x = SrcInitOutputData%LinNames_x -ENDIF -IF (ALLOCATED(SrcInitOutputData%LinNames_u)) THEN - i1_l = LBOUND(SrcInitOutputData%LinNames_u,1) - i1_u = UBOUND(SrcInitOutputData%LinNames_u,1) - IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_u)) THEN - ALLOCATE(DstInitOutputData%LinNames_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%LinNames_u = SrcInitOutputData%LinNames_u -ENDIF -IF (ALLOCATED(SrcInitOutputData%RotFrame_y)) THEN - i1_l = LBOUND(SrcInitOutputData%RotFrame_y,1) - i1_u = UBOUND(SrcInitOutputData%RotFrame_y,1) - IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_y)) THEN - ALLOCATE(DstInitOutputData%RotFrame_y(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_y.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%RotFrame_y = SrcInitOutputData%RotFrame_y -ENDIF -IF (ALLOCATED(SrcInitOutputData%RotFrame_x)) THEN - i1_l = LBOUND(SrcInitOutputData%RotFrame_x,1) - i1_u = UBOUND(SrcInitOutputData%RotFrame_x,1) - IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_x)) THEN - ALLOCATE(DstInitOutputData%RotFrame_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%RotFrame_x = SrcInitOutputData%RotFrame_x -ENDIF -IF (ALLOCATED(SrcInitOutputData%RotFrame_u)) THEN - i1_l = LBOUND(SrcInitOutputData%RotFrame_u,1) - i1_u = UBOUND(SrcInitOutputData%RotFrame_u,1) - IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_u)) THEN - ALLOCATE(DstInitOutputData%RotFrame_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%RotFrame_u = SrcInitOutputData%RotFrame_u -ENDIF -IF (ALLOCATED(SrcInitOutputData%IsLoad_u)) THEN - i1_l = LBOUND(SrcInitOutputData%IsLoad_u,1) - i1_u = UBOUND(SrcInitOutputData%IsLoad_u,1) - IF (.NOT. ALLOCATED(DstInitOutputData%IsLoad_u)) THEN - ALLOCATE(DstInitOutputData%IsLoad_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%IsLoad_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%IsLoad_u = SrcInitOutputData%IsLoad_u -ENDIF -IF (ALLOCATED(SrcInitOutputData%DerivOrder_x)) THEN - i1_l = LBOUND(SrcInitOutputData%DerivOrder_x,1) - i1_u = UBOUND(SrcInitOutputData%DerivOrder_x,1) - IF (.NOT. ALLOCATED(DstInitOutputData%DerivOrder_x)) THEN - ALLOCATE(DstInitOutputData%DerivOrder_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%DerivOrder_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%DerivOrder_x = SrcInitOutputData%DerivOrder_x -ENDIF -IF (ALLOCATED(SrcInitOutputData%CableCChanRqst)) THEN - i1_l = LBOUND(SrcInitOutputData%CableCChanRqst,1) - i1_u = UBOUND(SrcInitOutputData%CableCChanRqst,1) - IF (.NOT. ALLOCATED(DstInitOutputData%CableCChanRqst)) THEN - ALLOCATE(DstInitOutputData%CableCChanRqst(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%CableCChanRqst.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitOutputData%CableCChanRqst = SrcInitOutputData%CableCChanRqst -ENDIF - END SUBROUTINE SD_CopyInitOutput - - SUBROUTINE SD_DestroyInitOutput( InitOutputData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_InitOutputType), INTENT(INOUT) :: InitOutputData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitOutput' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(InitOutputData%WriteOutputHdr)) THEN - DEALLOCATE(InitOutputData%WriteOutputHdr) -ENDIF -IF (ALLOCATED(InitOutputData%WriteOutputUnt)) THEN - DEALLOCATE(InitOutputData%WriteOutputUnt) -ENDIF - CALL NWTC_Library_Destroyprogdesc( InitOutputData%Ver, ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -IF (ALLOCATED(InitOutputData%LinNames_y)) THEN - DEALLOCATE(InitOutputData%LinNames_y) -ENDIF -IF (ALLOCATED(InitOutputData%LinNames_x)) THEN - DEALLOCATE(InitOutputData%LinNames_x) -ENDIF -IF (ALLOCATED(InitOutputData%LinNames_u)) THEN - DEALLOCATE(InitOutputData%LinNames_u) -ENDIF -IF (ALLOCATED(InitOutputData%RotFrame_y)) THEN - DEALLOCATE(InitOutputData%RotFrame_y) -ENDIF -IF (ALLOCATED(InitOutputData%RotFrame_x)) THEN - DEALLOCATE(InitOutputData%RotFrame_x) -ENDIF -IF (ALLOCATED(InitOutputData%RotFrame_u)) THEN - DEALLOCATE(InitOutputData%RotFrame_u) -ENDIF -IF (ALLOCATED(InitOutputData%IsLoad_u)) THEN - DEALLOCATE(InitOutputData%IsLoad_u) -ENDIF -IF (ALLOCATED(InitOutputData%DerivOrder_x)) THEN - DEALLOCATE(InitOutputData%DerivOrder_x) -ENDIF -IF (ALLOCATED(InitOutputData%CableCChanRqst)) THEN - DEALLOCATE(InitOutputData%CableCChanRqst) -ENDIF - END SUBROUTINE SD_DestroyInitOutput - - SUBROUTINE SD_PackInitOutput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_InitOutputType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitOutput' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! WriteOutputHdr allocated yes/no - IF ( ALLOCATED(InData%WriteOutputHdr) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! WriteOutputHdr upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%WriteOutputHdr)*LEN(InData%WriteOutputHdr) ! WriteOutputHdr - END IF - Int_BufSz = Int_BufSz + 1 ! WriteOutputUnt allocated yes/no - IF ( ALLOCATED(InData%WriteOutputUnt) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! WriteOutputUnt upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%WriteOutputUnt)*LEN(InData%WriteOutputUnt) ! WriteOutputUnt - END IF - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - Int_BufSz = Int_BufSz + 3 ! Ver: size of buffers for each call to pack subtype - CALL NWTC_Library_Packprogdesc( Re_Buf, Db_Buf, Int_Buf, InData%Ver, ErrStat2, ErrMsg2, .TRUE. ) ! Ver - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! Ver - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! Ver - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! Ver - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 1 ! LinNames_y allocated yes/no - IF ( ALLOCATED(InData%LinNames_y) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! LinNames_y upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%LinNames_y)*LEN(InData%LinNames_y) ! LinNames_y - END IF - Int_BufSz = Int_BufSz + 1 ! LinNames_x allocated yes/no - IF ( ALLOCATED(InData%LinNames_x) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! LinNames_x upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%LinNames_x)*LEN(InData%LinNames_x) ! LinNames_x - END IF - Int_BufSz = Int_BufSz + 1 ! LinNames_u allocated yes/no - IF ( ALLOCATED(InData%LinNames_u) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! LinNames_u upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%LinNames_u)*LEN(InData%LinNames_u) ! LinNames_u - END IF - Int_BufSz = Int_BufSz + 1 ! RotFrame_y allocated yes/no - IF ( ALLOCATED(InData%RotFrame_y) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! RotFrame_y upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_y) ! RotFrame_y - END IF - Int_BufSz = Int_BufSz + 1 ! RotFrame_x allocated yes/no - IF ( ALLOCATED(InData%RotFrame_x) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! RotFrame_x upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_x) ! RotFrame_x - END IF - Int_BufSz = Int_BufSz + 1 ! RotFrame_u allocated yes/no - IF ( ALLOCATED(InData%RotFrame_u) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! RotFrame_u upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_u) ! RotFrame_u - END IF - Int_BufSz = Int_BufSz + 1 ! IsLoad_u allocated yes/no - IF ( ALLOCATED(InData%IsLoad_u) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IsLoad_u upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IsLoad_u) ! IsLoad_u - END IF - Int_BufSz = Int_BufSz + 1 ! DerivOrder_x allocated yes/no - IF ( ALLOCATED(InData%DerivOrder_x) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! DerivOrder_x upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%DerivOrder_x) ! DerivOrder_x - END IF - Int_BufSz = Int_BufSz + 1 ! CableCChanRqst allocated yes/no - IF ( ALLOCATED(InData%CableCChanRqst) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! CableCChanRqst upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%CableCChanRqst) ! CableCChanRqst - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%WriteOutputHdr) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutputHdr,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutputHdr,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%WriteOutputHdr,1), UBOUND(InData%WriteOutputHdr,1) - DO I = 1, LEN(InData%WriteOutputHdr) - IntKiBuf(Int_Xferred) = ICHAR(InData%WriteOutputHdr(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( .NOT. ALLOCATED(InData%WriteOutputUnt) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutputUnt,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutputUnt,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%WriteOutputUnt,1), UBOUND(InData%WriteOutputUnt,1) - DO I = 1, LEN(InData%WriteOutputUnt) - IntKiBuf(Int_Xferred) = ICHAR(InData%WriteOutputUnt(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - CALL NWTC_Library_Packprogdesc( Re_Buf, Db_Buf, Int_Buf, InData%Ver, ErrStat2, ErrMsg2, OnlySize ) ! Ver - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF ( .NOT. ALLOCATED(InData%LinNames_y) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_y,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_y,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%LinNames_y,1), UBOUND(InData%LinNames_y,1) - DO I = 1, LEN(InData%LinNames_y) - IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_y(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( .NOT. ALLOCATED(InData%LinNames_x) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_x,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_x,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%LinNames_x,1), UBOUND(InData%LinNames_x,1) - DO I = 1, LEN(InData%LinNames_x) - IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_x(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( .NOT. ALLOCATED(InData%LinNames_u) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_u,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_u,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%LinNames_u,1), UBOUND(InData%LinNames_u,1) - DO I = 1, LEN(InData%LinNames_u) - IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_u(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( .NOT. ALLOCATED(InData%RotFrame_y) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_y,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_y,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%RotFrame_y,1), UBOUND(InData%RotFrame_y,1) - IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_y(i1), IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%RotFrame_x) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_x,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_x,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%RotFrame_x,1), UBOUND(InData%RotFrame_x,1) - IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_x(i1), IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%RotFrame_u) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_u,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_u,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%RotFrame_u,1), UBOUND(InData%RotFrame_u,1) - IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_u(i1), IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IsLoad_u) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IsLoad_u,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IsLoad_u,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IsLoad_u,1), UBOUND(InData%IsLoad_u,1) - IntKiBuf(Int_Xferred) = TRANSFER(InData%IsLoad_u(i1), IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%DerivOrder_x) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DerivOrder_x,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DerivOrder_x,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%DerivOrder_x,1), UBOUND(InData%DerivOrder_x,1) - IntKiBuf(Int_Xferred) = InData%DerivOrder_x(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CableCChanRqst) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CableCChanRqst,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CableCChanRqst,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%CableCChanRqst,1), UBOUND(InData%CableCChanRqst,1) - IntKiBuf(Int_Xferred) = TRANSFER(InData%CableCChanRqst(i1), IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackInitOutput - - SUBROUTINE SD_UnPackInitOutput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_InitOutputType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitOutput' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutputHdr not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%WriteOutputHdr)) DEALLOCATE(OutData%WriteOutputHdr) - ALLOCATE(OutData%WriteOutputHdr(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutputHdr.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%WriteOutputHdr,1), UBOUND(OutData%WriteOutputHdr,1) - DO I = 1, LEN(OutData%WriteOutputHdr) - OutData%WriteOutputHdr(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutputUnt not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%WriteOutputUnt)) DEALLOCATE(OutData%WriteOutputUnt) - ALLOCATE(OutData%WriteOutputUnt(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutputUnt.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%WriteOutputUnt,1), UBOUND(OutData%WriteOutputUnt,1) - DO I = 1, LEN(OutData%WriteOutputUnt) - OutData%WriteOutputUnt(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL NWTC_Library_Unpackprogdesc( Re_Buf, Db_Buf, Int_Buf, OutData%Ver, ErrStat2, ErrMsg2 ) ! Ver - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_y not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%LinNames_y)) DEALLOCATE(OutData%LinNames_y) - ALLOCATE(OutData%LinNames_y(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_y.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%LinNames_y,1), UBOUND(OutData%LinNames_y,1) - DO I = 1, LEN(OutData%LinNames_y) - OutData%LinNames_y(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_x not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%LinNames_x)) DEALLOCATE(OutData%LinNames_x) - ALLOCATE(OutData%LinNames_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%LinNames_x,1), UBOUND(OutData%LinNames_x,1) - DO I = 1, LEN(OutData%LinNames_x) - OutData%LinNames_x(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_u not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%LinNames_u)) DEALLOCATE(OutData%LinNames_u) - ALLOCATE(OutData%LinNames_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%LinNames_u,1), UBOUND(OutData%LinNames_u,1) - DO I = 1, LEN(OutData%LinNames_u) - OutData%LinNames_u(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_y not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%RotFrame_y)) DEALLOCATE(OutData%RotFrame_y) - ALLOCATE(OutData%RotFrame_y(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_y.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%RotFrame_y,1), UBOUND(OutData%RotFrame_y,1) - OutData%RotFrame_y(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_y(i1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_x not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%RotFrame_x)) DEALLOCATE(OutData%RotFrame_x) - ALLOCATE(OutData%RotFrame_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%RotFrame_x,1), UBOUND(OutData%RotFrame_x,1) - OutData%RotFrame_x(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_x(i1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_u not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%RotFrame_u)) DEALLOCATE(OutData%RotFrame_u) - ALLOCATE(OutData%RotFrame_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%RotFrame_u,1), UBOUND(OutData%RotFrame_u,1) - OutData%RotFrame_u(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_u(i1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IsLoad_u not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IsLoad_u)) DEALLOCATE(OutData%IsLoad_u) - ALLOCATE(OutData%IsLoad_u(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IsLoad_u.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IsLoad_u,1), UBOUND(OutData%IsLoad_u,1) - OutData%IsLoad_u(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%IsLoad_u(i1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DerivOrder_x not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%DerivOrder_x)) DEALLOCATE(OutData%DerivOrder_x) - ALLOCATE(OutData%DerivOrder_x(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DerivOrder_x.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%DerivOrder_x,1), UBOUND(OutData%DerivOrder_x,1) - OutData%DerivOrder_x(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CableCChanRqst not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CableCChanRqst)) DEALLOCATE(OutData%CableCChanRqst) - ALLOCATE(OutData%CableCChanRqst(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CableCChanRqst.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%CableCChanRqst,1), UBOUND(OutData%CableCChanRqst,1) - OutData%CableCChanRqst(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%CableCChanRqst(i1)) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackInitOutput - - SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_InitType), INTENT(IN) :: SrcInitTypeData - TYPE(SD_InitType), INTENT(INOUT) :: DstInitTypeData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitType' -! - ErrStat = ErrID_None - ErrMsg = "" - DstInitTypeData%RootName = SrcInitTypeData%RootName - DstInitTypeData%TP_RefPoint = SrcInitTypeData%TP_RefPoint - DstInitTypeData%SubRotateZ = SrcInitTypeData%SubRotateZ - DstInitTypeData%g = SrcInitTypeData%g - DstInitTypeData%DT = SrcInitTypeData%DT - DstInitTypeData%NJoints = SrcInitTypeData%NJoints - DstInitTypeData%NPropSetsX = SrcInitTypeData%NPropSetsX - DstInitTypeData%NPropSetsB = SrcInitTypeData%NPropSetsB - DstInitTypeData%NPropSetsC = SrcInitTypeData%NPropSetsC - DstInitTypeData%NPropSetsR = SrcInitTypeData%NPropSetsR - DstInitTypeData%NPropSetsS = SrcInitTypeData%NPropSetsS - DstInitTypeData%NCMass = SrcInitTypeData%NCMass - DstInitTypeData%NCOSMs = SrcInitTypeData%NCOSMs - DstInitTypeData%FEMMod = SrcInitTypeData%FEMMod - DstInitTypeData%NDiv = SrcInitTypeData%NDiv - DstInitTypeData%CBMod = SrcInitTypeData%CBMod -IF (ALLOCATED(SrcInitTypeData%Joints)) THEN - i1_l = LBOUND(SrcInitTypeData%Joints,1) - i1_u = UBOUND(SrcInitTypeData%Joints,1) - i2_l = LBOUND(SrcInitTypeData%Joints,2) - i2_u = UBOUND(SrcInitTypeData%Joints,2) - IF (.NOT. ALLOCATED(DstInitTypeData%Joints)) THEN - ALLOCATE(DstInitTypeData%Joints(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Joints.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Joints = SrcInitTypeData%Joints -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropSetsB)) THEN - i1_l = LBOUND(SrcInitTypeData%PropSetsB,1) - i1_u = UBOUND(SrcInitTypeData%PropSetsB,1) - i2_l = LBOUND(SrcInitTypeData%PropSetsB,2) - i2_u = UBOUND(SrcInitTypeData%PropSetsB,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsB)) THEN - ALLOCATE(DstInitTypeData%PropSetsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropSetsB = SrcInitTypeData%PropSetsB -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropSetsC)) THEN - i1_l = LBOUND(SrcInitTypeData%PropSetsC,1) - i1_u = UBOUND(SrcInitTypeData%PropSetsC,1) - i2_l = LBOUND(SrcInitTypeData%PropSetsC,2) - i2_u = UBOUND(SrcInitTypeData%PropSetsC,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsC)) THEN - ALLOCATE(DstInitTypeData%PropSetsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsC.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropSetsC = SrcInitTypeData%PropSetsC -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropSetsR)) THEN - i1_l = LBOUND(SrcInitTypeData%PropSetsR,1) - i1_u = UBOUND(SrcInitTypeData%PropSetsR,1) - i2_l = LBOUND(SrcInitTypeData%PropSetsR,2) - i2_u = UBOUND(SrcInitTypeData%PropSetsR,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsR)) THEN - ALLOCATE(DstInitTypeData%PropSetsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropSetsR = SrcInitTypeData%PropSetsR -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropSetsS)) THEN - i1_l = LBOUND(SrcInitTypeData%PropSetsS,1) - i1_u = UBOUND(SrcInitTypeData%PropSetsS,1) - i2_l = LBOUND(SrcInitTypeData%PropSetsS,2) - i2_u = UBOUND(SrcInitTypeData%PropSetsS,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsS)) THEN - ALLOCATE(DstInitTypeData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropSetsS = SrcInitTypeData%PropSetsS -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropSetsX)) THEN - i1_l = LBOUND(SrcInitTypeData%PropSetsX,1) - i1_u = UBOUND(SrcInitTypeData%PropSetsX,1) - i2_l = LBOUND(SrcInitTypeData%PropSetsX,2) - i2_u = UBOUND(SrcInitTypeData%PropSetsX,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsX)) THEN - ALLOCATE(DstInitTypeData%PropSetsX(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsX.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropSetsX = SrcInitTypeData%PropSetsX -ENDIF -IF (ALLOCATED(SrcInitTypeData%COSMs)) THEN - i1_l = LBOUND(SrcInitTypeData%COSMs,1) - i1_u = UBOUND(SrcInitTypeData%COSMs,1) - i2_l = LBOUND(SrcInitTypeData%COSMs,2) - i2_u = UBOUND(SrcInitTypeData%COSMs,2) - IF (.NOT. ALLOCATED(DstInitTypeData%COSMs)) THEN - ALLOCATE(DstInitTypeData%COSMs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%COSMs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%COSMs = SrcInitTypeData%COSMs -ENDIF -IF (ALLOCATED(SrcInitTypeData%CMass)) THEN - i1_l = LBOUND(SrcInitTypeData%CMass,1) - i1_u = UBOUND(SrcInitTypeData%CMass,1) - i2_l = LBOUND(SrcInitTypeData%CMass,2) - i2_u = UBOUND(SrcInitTypeData%CMass,2) - IF (.NOT. ALLOCATED(DstInitTypeData%CMass)) THEN - ALLOCATE(DstInitTypeData%CMass(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%CMass.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%CMass = SrcInitTypeData%CMass -ENDIF -IF (ALLOCATED(SrcInitTypeData%JDampings)) THEN - i1_l = LBOUND(SrcInitTypeData%JDampings,1) - i1_u = UBOUND(SrcInitTypeData%JDampings,1) - IF (.NOT. ALLOCATED(DstInitTypeData%JDampings)) THEN - ALLOCATE(DstInitTypeData%JDampings(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%JDampings.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%JDampings = SrcInitTypeData%JDampings -ENDIF - DstInitTypeData%GuyanDampMod = SrcInitTypeData%GuyanDampMod - DstInitTypeData%RayleighDamp = SrcInitTypeData%RayleighDamp - DstInitTypeData%GuyanDampMat = SrcInitTypeData%GuyanDampMat -IF (ALLOCATED(SrcInitTypeData%Members)) THEN - i1_l = LBOUND(SrcInitTypeData%Members,1) - i1_u = UBOUND(SrcInitTypeData%Members,1) - i2_l = LBOUND(SrcInitTypeData%Members,2) - i2_u = UBOUND(SrcInitTypeData%Members,2) - IF (.NOT. ALLOCATED(DstInitTypeData%Members)) THEN - ALLOCATE(DstInitTypeData%Members(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Members.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Members = SrcInitTypeData%Members -ENDIF -IF (ALLOCATED(SrcInitTypeData%SSOutList)) THEN - i1_l = LBOUND(SrcInitTypeData%SSOutList,1) - i1_u = UBOUND(SrcInitTypeData%SSOutList,1) - IF (.NOT. ALLOCATED(DstInitTypeData%SSOutList)) THEN - ALLOCATE(DstInitTypeData%SSOutList(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSOutList.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%SSOutList = SrcInitTypeData%SSOutList -ENDIF - DstInitTypeData%OutCOSM = SrcInitTypeData%OutCOSM - DstInitTypeData%TabDelim = SrcInitTypeData%TabDelim -IF (ALLOCATED(SrcInitTypeData%SSIK)) THEN - i1_l = LBOUND(SrcInitTypeData%SSIK,1) - i1_u = UBOUND(SrcInitTypeData%SSIK,1) - i2_l = LBOUND(SrcInitTypeData%SSIK,2) - i2_u = UBOUND(SrcInitTypeData%SSIK,2) - IF (.NOT. ALLOCATED(DstInitTypeData%SSIK)) THEN - ALLOCATE(DstInitTypeData%SSIK(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIK.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%SSIK = SrcInitTypeData%SSIK -ENDIF -IF (ALLOCATED(SrcInitTypeData%SSIM)) THEN - i1_l = LBOUND(SrcInitTypeData%SSIM,1) - i1_u = UBOUND(SrcInitTypeData%SSIM,1) - i2_l = LBOUND(SrcInitTypeData%SSIM,2) - i2_u = UBOUND(SrcInitTypeData%SSIM,2) - IF (.NOT. ALLOCATED(DstInitTypeData%SSIM)) THEN - ALLOCATE(DstInitTypeData%SSIM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%SSIM = SrcInitTypeData%SSIM -ENDIF -IF (ALLOCATED(SrcInitTypeData%SSIfile)) THEN - i1_l = LBOUND(SrcInitTypeData%SSIfile,1) - i1_u = UBOUND(SrcInitTypeData%SSIfile,1) - IF (.NOT. ALLOCATED(DstInitTypeData%SSIfile)) THEN - ALLOCATE(DstInitTypeData%SSIfile(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIfile.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%SSIfile = SrcInitTypeData%SSIfile -ENDIF -IF (ALLOCATED(SrcInitTypeData%Soil_K)) THEN - i1_l = LBOUND(SrcInitTypeData%Soil_K,1) - i1_u = UBOUND(SrcInitTypeData%Soil_K,1) - i2_l = LBOUND(SrcInitTypeData%Soil_K,2) - i2_u = UBOUND(SrcInitTypeData%Soil_K,2) - i3_l = LBOUND(SrcInitTypeData%Soil_K,3) - i3_u = UBOUND(SrcInitTypeData%Soil_K,3) - IF (.NOT. ALLOCATED(DstInitTypeData%Soil_K)) THEN - ALLOCATE(DstInitTypeData%Soil_K(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_K.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Soil_K = SrcInitTypeData%Soil_K -ENDIF -IF (ALLOCATED(SrcInitTypeData%Soil_Points)) THEN - i1_l = LBOUND(SrcInitTypeData%Soil_Points,1) - i1_u = UBOUND(SrcInitTypeData%Soil_Points,1) - i2_l = LBOUND(SrcInitTypeData%Soil_Points,2) - i2_u = UBOUND(SrcInitTypeData%Soil_Points,2) - IF (.NOT. ALLOCATED(DstInitTypeData%Soil_Points)) THEN - ALLOCATE(DstInitTypeData%Soil_Points(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_Points.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Soil_Points = SrcInitTypeData%Soil_Points -ENDIF -IF (ALLOCATED(SrcInitTypeData%Soil_Nodes)) THEN - i1_l = LBOUND(SrcInitTypeData%Soil_Nodes,1) - i1_u = UBOUND(SrcInitTypeData%Soil_Nodes,1) - IF (.NOT. ALLOCATED(DstInitTypeData%Soil_Nodes)) THEN - ALLOCATE(DstInitTypeData%Soil_Nodes(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Soil_Nodes = SrcInitTypeData%Soil_Nodes -ENDIF - DstInitTypeData%NElem = SrcInitTypeData%NElem - DstInitTypeData%NPropB = SrcInitTypeData%NPropB - DstInitTypeData%NPropC = SrcInitTypeData%NPropC - DstInitTypeData%NPropR = SrcInitTypeData%NPropR - DstInitTypeData%NPropS = SrcInitTypeData%NPropS -IF (ALLOCATED(SrcInitTypeData%Nodes)) THEN - i1_l = LBOUND(SrcInitTypeData%Nodes,1) - i1_u = UBOUND(SrcInitTypeData%Nodes,1) - i2_l = LBOUND(SrcInitTypeData%Nodes,2) - i2_u = UBOUND(SrcInitTypeData%Nodes,2) - IF (.NOT. ALLOCATED(DstInitTypeData%Nodes)) THEN - ALLOCATE(DstInitTypeData%Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%Nodes = SrcInitTypeData%Nodes -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropsB)) THEN - i1_l = LBOUND(SrcInitTypeData%PropsB,1) - i1_u = UBOUND(SrcInitTypeData%PropsB,1) - i2_l = LBOUND(SrcInitTypeData%PropsB,2) - i2_u = UBOUND(SrcInitTypeData%PropsB,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropsB)) THEN - ALLOCATE(DstInitTypeData%PropsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropsB = SrcInitTypeData%PropsB -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropsC)) THEN - i1_l = LBOUND(SrcInitTypeData%PropsC,1) - i1_u = UBOUND(SrcInitTypeData%PropsC,1) - i2_l = LBOUND(SrcInitTypeData%PropsC,2) - i2_u = UBOUND(SrcInitTypeData%PropsC,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropsC)) THEN - ALLOCATE(DstInitTypeData%PropsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsC.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropsC = SrcInitTypeData%PropsC -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropsR)) THEN - i1_l = LBOUND(SrcInitTypeData%PropsR,1) - i1_u = UBOUND(SrcInitTypeData%PropsR,1) - i2_l = LBOUND(SrcInitTypeData%PropsR,2) - i2_u = UBOUND(SrcInitTypeData%PropsR,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropsR)) THEN - ALLOCATE(DstInitTypeData%PropsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropsR = SrcInitTypeData%PropsR -ENDIF -IF (ALLOCATED(SrcInitTypeData%PropsS)) THEN - i1_l = LBOUND(SrcInitTypeData%PropsR,1) - i1_u = UBOUND(SrcInitTypeData%PropsR,1) - i2_l = LBOUND(SrcInitTypeData%PropsR,2) - i2_u = UBOUND(SrcInitTypeData%PropsR,2) - IF (.NOT. ALLOCATED(DstInitTypeData%PropsS)) THEN - ALLOCATE(DstInitTypeData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%PropsS = SrcInitTypeData%PropsS -ENDIF -IF (ALLOCATED(SrcInitTypeData%K)) THEN - i1_l = LBOUND(SrcInitTypeData%K,1) - i1_u = UBOUND(SrcInitTypeData%K,1) - i2_l = LBOUND(SrcInitTypeData%K,2) - i2_u = UBOUND(SrcInitTypeData%K,2) - IF (.NOT. ALLOCATED(DstInitTypeData%K)) THEN - ALLOCATE(DstInitTypeData%K(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%K.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%K = SrcInitTypeData%K -ENDIF -IF (ALLOCATED(SrcInitTypeData%M)) THEN - i1_l = LBOUND(SrcInitTypeData%M,1) - i1_u = UBOUND(SrcInitTypeData%M,1) - i2_l = LBOUND(SrcInitTypeData%M,2) - i2_u = UBOUND(SrcInitTypeData%M,2) - IF (.NOT. ALLOCATED(DstInitTypeData%M)) THEN - ALLOCATE(DstInitTypeData%M(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%M.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%M = SrcInitTypeData%M -ENDIF -IF (ALLOCATED(SrcInitTypeData%ElemProps)) THEN - i1_l = LBOUND(SrcInitTypeData%ElemProps,1) - i1_u = UBOUND(SrcInitTypeData%ElemProps,1) - i2_l = LBOUND(SrcInitTypeData%ElemProps,2) - i2_u = UBOUND(SrcInitTypeData%ElemProps,2) - IF (.NOT. ALLOCATED(DstInitTypeData%ElemProps)) THEN - ALLOCATE(DstInitTypeData%ElemProps(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%ElemProps.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%ElemProps = SrcInitTypeData%ElemProps -ENDIF -IF (ALLOCATED(SrcInitTypeData%MemberNodes)) THEN - i1_l = LBOUND(SrcInitTypeData%MemberNodes,1) - i1_u = UBOUND(SrcInitTypeData%MemberNodes,1) - i2_l = LBOUND(SrcInitTypeData%MemberNodes,2) - i2_u = UBOUND(SrcInitTypeData%MemberNodes,2) - IF (.NOT. ALLOCATED(DstInitTypeData%MemberNodes)) THEN - ALLOCATE(DstInitTypeData%MemberNodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%MemberNodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%MemberNodes = SrcInitTypeData%MemberNodes -ENDIF -IF (ALLOCATED(SrcInitTypeData%NodesConnN)) THEN - i1_l = LBOUND(SrcInitTypeData%NodesConnN,1) - i1_u = UBOUND(SrcInitTypeData%NodesConnN,1) - i2_l = LBOUND(SrcInitTypeData%NodesConnN,2) - i2_u = UBOUND(SrcInitTypeData%NodesConnN,2) - IF (.NOT. ALLOCATED(DstInitTypeData%NodesConnN)) THEN - ALLOCATE(DstInitTypeData%NodesConnN(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%NodesConnN.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%NodesConnN = SrcInitTypeData%NodesConnN -ENDIF -IF (ALLOCATED(SrcInitTypeData%NodesConnE)) THEN - i1_l = LBOUND(SrcInitTypeData%NodesConnE,1) - i1_u = UBOUND(SrcInitTypeData%NodesConnE,1) - i2_l = LBOUND(SrcInitTypeData%NodesConnE,2) - i2_u = UBOUND(SrcInitTypeData%NodesConnE,2) - IF (.NOT. ALLOCATED(DstInitTypeData%NodesConnE)) THEN - ALLOCATE(DstInitTypeData%NodesConnE(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%NodesConnE.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInitTypeData%NodesConnE = SrcInitTypeData%NodesConnE -ENDIF - DstInitTypeData%SSSum = SrcInitTypeData%SSSum - END SUBROUTINE SD_CopyInitType - - SUBROUTINE SD_DestroyInitType( InitTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_InitType), INTENT(INOUT) :: InitTypeData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitType' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(InitTypeData%Joints)) THEN - DEALLOCATE(InitTypeData%Joints) -ENDIF -IF (ALLOCATED(InitTypeData%PropSetsB)) THEN - DEALLOCATE(InitTypeData%PropSetsB) -ENDIF -IF (ALLOCATED(InitTypeData%PropSetsC)) THEN - DEALLOCATE(InitTypeData%PropSetsC) -ENDIF -IF (ALLOCATED(InitTypeData%PropSetsR)) THEN - DEALLOCATE(InitTypeData%PropSetsR) -ENDIF -IF (ALLOCATED(InitTypeData%PropSetsS)) THEN - DEALLOCATE(InitTypeData%PropSetsS) -ENDIF -IF (ALLOCATED(InitTypeData%PropSetsX)) THEN - DEALLOCATE(InitTypeData%PropSetsX) -ENDIF -IF (ALLOCATED(InitTypeData%COSMs)) THEN - DEALLOCATE(InitTypeData%COSMs) -ENDIF -IF (ALLOCATED(InitTypeData%CMass)) THEN - DEALLOCATE(InitTypeData%CMass) -ENDIF -IF (ALLOCATED(InitTypeData%JDampings)) THEN - DEALLOCATE(InitTypeData%JDampings) -ENDIF -IF (ALLOCATED(InitTypeData%Members)) THEN - DEALLOCATE(InitTypeData%Members) -ENDIF -IF (ALLOCATED(InitTypeData%SSOutList)) THEN - DEALLOCATE(InitTypeData%SSOutList) -ENDIF -IF (ALLOCATED(InitTypeData%SSIK)) THEN - DEALLOCATE(InitTypeData%SSIK) -ENDIF -IF (ALLOCATED(InitTypeData%SSIM)) THEN - DEALLOCATE(InitTypeData%SSIM) -ENDIF -IF (ALLOCATED(InitTypeData%SSIfile)) THEN - DEALLOCATE(InitTypeData%SSIfile) -ENDIF -IF (ALLOCATED(InitTypeData%Soil_K)) THEN - DEALLOCATE(InitTypeData%Soil_K) -ENDIF -IF (ALLOCATED(InitTypeData%Soil_Points)) THEN - DEALLOCATE(InitTypeData%Soil_Points) -ENDIF -IF (ALLOCATED(InitTypeData%Soil_Nodes)) THEN - DEALLOCATE(InitTypeData%Soil_Nodes) -ENDIF -IF (ALLOCATED(InitTypeData%Nodes)) THEN - DEALLOCATE(InitTypeData%Nodes) -ENDIF -IF (ALLOCATED(InitTypeData%PropsB)) THEN - DEALLOCATE(InitTypeData%PropsB) -ENDIF -IF (ALLOCATED(InitTypeData%PropsC)) THEN - DEALLOCATE(InitTypeData%PropsC) -ENDIF -IF (ALLOCATED(InitTypeData%PropsR)) THEN - DEALLOCATE(InitTypeData%PropsR) -ENDIF -IF (ALLOCATED(InitTypeData%PropsS)) THEN - DEALLOCATE(InitTypeData%PropsS) -ENDIF -IF (ALLOCATED(InitTypeData%K)) THEN - DEALLOCATE(InitTypeData%K) -ENDIF -IF (ALLOCATED(InitTypeData%M)) THEN - DEALLOCATE(InitTypeData%M) -ENDIF -IF (ALLOCATED(InitTypeData%ElemProps)) THEN - DEALLOCATE(InitTypeData%ElemProps) -ENDIF -IF (ALLOCATED(InitTypeData%MemberNodes)) THEN - DEALLOCATE(InitTypeData%MemberNodes) -ENDIF -IF (ALLOCATED(InitTypeData%NodesConnN)) THEN - DEALLOCATE(InitTypeData%NodesConnN) -ENDIF -IF (ALLOCATED(InitTypeData%NodesConnE)) THEN - DEALLOCATE(InitTypeData%NodesConnE) -ENDIF - END SUBROUTINE SD_DestroyInitType - - SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_InitType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitType' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1*LEN(InData%RootName) ! RootName - Re_BufSz = Re_BufSz + SIZE(InData%TP_RefPoint) ! TP_RefPoint - Re_BufSz = Re_BufSz + 1 ! SubRotateZ - Re_BufSz = Re_BufSz + 1 ! g - Db_BufSz = Db_BufSz + 1 ! DT - Int_BufSz = Int_BufSz + 1 ! NJoints - Int_BufSz = Int_BufSz + 1 ! NPropSetsX - Int_BufSz = Int_BufSz + 1 ! NPropSetsB - Int_BufSz = Int_BufSz + 1 ! NPropSetsC - Int_BufSz = Int_BufSz + 1 ! NPropSetsR - Int_BufSz = Int_BufSz + 1 ! NPropSetsS - Int_BufSz = Int_BufSz + 1 ! NCMass - Int_BufSz = Int_BufSz + 1 ! NCOSMs - Int_BufSz = Int_BufSz + 1 ! FEMMod - Int_BufSz = Int_BufSz + 1 ! NDiv - Int_BufSz = Int_BufSz + 1 ! CBMod - Int_BufSz = Int_BufSz + 1 ! Joints allocated yes/no - IF ( ALLOCATED(InData%Joints) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Joints upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Joints) ! Joints - END IF - Int_BufSz = Int_BufSz + 1 ! PropSetsB allocated yes/no - IF ( ALLOCATED(InData%PropSetsB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropSetsB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropSetsB) ! PropSetsB - END IF - Int_BufSz = Int_BufSz + 1 ! PropSetsC allocated yes/no - IF ( ALLOCATED(InData%PropSetsC) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropSetsC upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropSetsC) ! PropSetsC - END IF - Int_BufSz = Int_BufSz + 1 ! PropSetsR allocated yes/no - IF ( ALLOCATED(InData%PropSetsR) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropSetsR upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropSetsR) ! PropSetsR - END IF - Int_BufSz = Int_BufSz + 1 ! PropSetsS allocated yes/no - IF ( ALLOCATED(InData%PropSetsS) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropSetsS upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropSetsS) ! PropSetsS - END IF - Int_BufSz = Int_BufSz + 1 ! PropSetsX allocated yes/no - IF ( ALLOCATED(InData%PropSetsX) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropSetsX upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropSetsX) ! PropSetsX - END IF - Int_BufSz = Int_BufSz + 1 ! COSMs allocated yes/no - IF ( ALLOCATED(InData%COSMs) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! COSMs upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%COSMs) ! COSMs - END IF - Int_BufSz = Int_BufSz + 1 ! CMass allocated yes/no - IF ( ALLOCATED(InData%CMass) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! CMass upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%CMass) ! CMass - END IF - Int_BufSz = Int_BufSz + 1 ! JDampings allocated yes/no - IF ( ALLOCATED(InData%JDampings) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! JDampings upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%JDampings) ! JDampings - END IF - Int_BufSz = Int_BufSz + 1 ! GuyanDampMod - Re_BufSz = Re_BufSz + SIZE(InData%RayleighDamp) ! RayleighDamp - Re_BufSz = Re_BufSz + SIZE(InData%GuyanDampMat) ! GuyanDampMat - Int_BufSz = Int_BufSz + 1 ! Members allocated yes/no - IF ( ALLOCATED(InData%Members) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Members upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Members) ! Members - END IF - Int_BufSz = Int_BufSz + 1 ! SSOutList allocated yes/no - IF ( ALLOCATED(InData%SSOutList) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! SSOutList upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%SSOutList)*LEN(InData%SSOutList) ! SSOutList - END IF - Int_BufSz = Int_BufSz + 1 ! OutCOSM - Int_BufSz = Int_BufSz + 1 ! TabDelim - Int_BufSz = Int_BufSz + 1 ! SSIK allocated yes/no - IF ( ALLOCATED(InData%SSIK) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! SSIK upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%SSIK) ! SSIK - END IF - Int_BufSz = Int_BufSz + 1 ! SSIM allocated yes/no - IF ( ALLOCATED(InData%SSIM) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! SSIM upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%SSIM) ! SSIM - END IF - Int_BufSz = Int_BufSz + 1 ! SSIfile allocated yes/no - IF ( ALLOCATED(InData%SSIfile) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! SSIfile upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%SSIfile)*LEN(InData%SSIfile) ! SSIfile - END IF - Int_BufSz = Int_BufSz + 1 ! Soil_K allocated yes/no - IF ( ALLOCATED(InData%Soil_K) ) THEN - Int_BufSz = Int_BufSz + 2*3 ! Soil_K upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Soil_K) ! Soil_K - END IF - Int_BufSz = Int_BufSz + 1 ! Soil_Points allocated yes/no - IF ( ALLOCATED(InData%Soil_Points) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Soil_Points upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Soil_Points) ! Soil_Points - END IF - Int_BufSz = Int_BufSz + 1 ! Soil_Nodes allocated yes/no - IF ( ALLOCATED(InData%Soil_Nodes) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! Soil_Nodes upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Soil_Nodes) ! Soil_Nodes - END IF - Int_BufSz = Int_BufSz + 1 ! NElem - Int_BufSz = Int_BufSz + 1 ! NPropB - Int_BufSz = Int_BufSz + 1 ! NPropC - Int_BufSz = Int_BufSz + 1 ! NPropR - Int_BufSz = Int_BufSz + 1 ! NPropS - Int_BufSz = Int_BufSz + 1 ! Nodes allocated yes/no - IF ( ALLOCATED(InData%Nodes) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Nodes upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Nodes) ! Nodes - END IF - Int_BufSz = Int_BufSz + 1 ! PropsB allocated yes/no - IF ( ALLOCATED(InData%PropsB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropsB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropsB) ! PropsB - END IF - Int_BufSz = Int_BufSz + 1 ! PropsC allocated yes/no - IF ( ALLOCATED(InData%PropsC) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropsC upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropsC) ! PropsC - END IF - Int_BufSz = Int_BufSz + 1 ! PropsR allocated yes/no - IF ( ALLOCATED(InData%PropsR) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropsR upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropsR) ! PropsR - END IF - Int_BufSz = Int_BufSz + 1 ! PropsS allocated yes/no - IF ( ALLOCATED(InData%PropsS) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PropsS upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PropsS) ! PropsS - END IF - Int_BufSz = Int_BufSz + 1 ! K allocated yes/no - IF ( ALLOCATED(InData%K) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! K upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%K) ! K - END IF - Int_BufSz = Int_BufSz + 1 ! M allocated yes/no - IF ( ALLOCATED(InData%M) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! M upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%M) ! M - END IF - Int_BufSz = Int_BufSz + 1 ! ElemProps allocated yes/no - IF ( ALLOCATED(InData%ElemProps) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! ElemProps upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%ElemProps) ! ElemProps - END IF - Int_BufSz = Int_BufSz + 1 ! MemberNodes allocated yes/no - IF ( ALLOCATED(InData%MemberNodes) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MemberNodes upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%MemberNodes) ! MemberNodes - END IF - Int_BufSz = Int_BufSz + 1 ! NodesConnN allocated yes/no - IF ( ALLOCATED(InData%NodesConnN) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! NodesConnN upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%NodesConnN) ! NodesConnN - END IF - Int_BufSz = Int_BufSz + 1 ! NodesConnE allocated yes/no - IF ( ALLOCATED(InData%NodesConnE) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! NodesConnE upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%NodesConnE) ! NodesConnE - END IF - Int_BufSz = Int_BufSz + 1 ! SSSum - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - DO I = 1, LEN(InData%RootName) - IntKiBuf(Int_Xferred) = ICHAR(InData%RootName(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO i1 = LBOUND(InData%TP_RefPoint,1), UBOUND(InData%TP_RefPoint,1) - ReKiBuf(Re_Xferred) = InData%TP_RefPoint(i1) - Re_Xferred = Re_Xferred + 1 - END DO - ReKiBuf(Re_Xferred) = InData%SubRotateZ - Re_Xferred = Re_Xferred + 1 - ReKiBuf(Re_Xferred) = InData%g - Re_Xferred = Re_Xferred + 1 - DbKiBuf(Db_Xferred) = InData%DT - Db_Xferred = Db_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NJoints - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropSetsX - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropSetsB - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropSetsC - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropSetsR - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropSetsS - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NCMass - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NCOSMs - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%FEMMod - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NDiv - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%CBMod, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Joints) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Joints,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Joints,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Joints,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Joints,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Joints,2), UBOUND(InData%Joints,2) - DO i1 = LBOUND(InData%Joints,1), UBOUND(InData%Joints,1) - ReKiBuf(Re_Xferred) = InData%Joints(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropSetsB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropSetsB,2), UBOUND(InData%PropSetsB,2) - DO i1 = LBOUND(InData%PropSetsB,1), UBOUND(InData%PropSetsB,1) - ReKiBuf(Re_Xferred) = InData%PropSetsB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropSetsC) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsC,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsC,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsC,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsC,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropSetsC,2), UBOUND(InData%PropSetsC,2) - DO i1 = LBOUND(InData%PropSetsC,1), UBOUND(InData%PropSetsC,1) - ReKiBuf(Re_Xferred) = InData%PropSetsC(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropSetsR) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsR,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsR,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsR,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsR,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropSetsR,2), UBOUND(InData%PropSetsR,2) - DO i1 = LBOUND(InData%PropSetsR,1), UBOUND(InData%PropSetsR,1) - ReKiBuf(Re_Xferred) = InData%PropSetsR(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropSetsS) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropSetsS,2), UBOUND(InData%PropSetsS,2) - DO i1 = LBOUND(InData%PropSetsS,1), UBOUND(InData%PropSetsS,1) - ReKiBuf(Re_Xferred) = InData%PropSetsS(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropSetsX) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsX,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsX,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsX,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsX,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropSetsX,2), UBOUND(InData%PropSetsX,2) - DO i1 = LBOUND(InData%PropSetsX,1), UBOUND(InData%PropSetsX,1) - ReKiBuf(Re_Xferred) = InData%PropSetsX(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%COSMs) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%COSMs,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%COSMs,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%COSMs,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%COSMs,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%COSMs,2), UBOUND(InData%COSMs,2) - DO i1 = LBOUND(InData%COSMs,1), UBOUND(InData%COSMs,1) - DbKiBuf(Db_Xferred) = InData%COSMs(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CMass) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CMass,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMass,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CMass,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMass,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%CMass,2), UBOUND(InData%CMass,2) - DO i1 = LBOUND(InData%CMass,1), UBOUND(InData%CMass,1) - ReKiBuf(Re_Xferred) = InData%CMass(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%JDampings) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%JDampings,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%JDampings,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%JDampings,1), UBOUND(InData%JDampings,1) - ReKiBuf(Re_Xferred) = InData%JDampings(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IntKiBuf(Int_Xferred) = InData%GuyanDampMod - Int_Xferred = Int_Xferred + 1 - DO i1 = LBOUND(InData%RayleighDamp,1), UBOUND(InData%RayleighDamp,1) - ReKiBuf(Re_Xferred) = InData%RayleighDamp(i1) - Re_Xferred = Re_Xferred + 1 - END DO - DO i2 = LBOUND(InData%GuyanDampMat,2), UBOUND(InData%GuyanDampMat,2) - DO i1 = LBOUND(InData%GuyanDampMat,1), UBOUND(InData%GuyanDampMat,1) - ReKiBuf(Re_Xferred) = InData%GuyanDampMat(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - IF ( .NOT. ALLOCATED(InData%Members) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Members,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Members,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Members,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Members,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Members,2), UBOUND(InData%Members,2) - DO i1 = LBOUND(InData%Members,1), UBOUND(InData%Members,1) - IntKiBuf(Int_Xferred) = InData%Members(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%SSOutList) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSOutList,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSOutList,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%SSOutList,1), UBOUND(InData%SSOutList,1) - DO I = 1, LEN(InData%SSOutList) - IntKiBuf(Int_Xferred) = ICHAR(InData%SSOutList(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IntKiBuf(Int_Xferred) = TRANSFER(InData%OutCOSM, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%TabDelim, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%SSIK) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIK,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIK,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIK,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIK,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%SSIK,2), UBOUND(InData%SSIK,2) - DO i1 = LBOUND(InData%SSIK,1), UBOUND(InData%SSIK,1) - DbKiBuf(Db_Xferred) = InData%SSIK(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%SSIM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIM,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIM,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIM,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%SSIM,2), UBOUND(InData%SSIM,2) - DO i1 = LBOUND(InData%SSIM,1), UBOUND(InData%SSIM,1) - DbKiBuf(Db_Xferred) = InData%SSIM(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%SSIfile) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIfile,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIfile,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%SSIfile,1), UBOUND(InData%SSIfile,1) - DO I = 1, LEN(InData%SSIfile) - IntKiBuf(Int_Xferred) = ICHAR(InData%SSIfile(i1)(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Soil_K) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,2) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,3) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,3) - Int_Xferred = Int_Xferred + 2 - - DO i3 = LBOUND(InData%Soil_K,3), UBOUND(InData%Soil_K,3) - DO i2 = LBOUND(InData%Soil_K,2), UBOUND(InData%Soil_K,2) - DO i1 = LBOUND(InData%Soil_K,1), UBOUND(InData%Soil_K,1) - ReKiBuf(Re_Xferred) = InData%Soil_K(i1,i2,i3) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Soil_Points) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Points,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Points,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Points,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Points,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Soil_Points,2), UBOUND(InData%Soil_Points,2) - DO i1 = LBOUND(InData%Soil_Points,1), UBOUND(InData%Soil_Points,1) - ReKiBuf(Re_Xferred) = InData%Soil_Points(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Soil_Nodes) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Nodes,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Nodes,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%Soil_Nodes,1), UBOUND(InData%Soil_Nodes,1) - IntKiBuf(Int_Xferred) = InData%Soil_Nodes(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IntKiBuf(Int_Xferred) = InData%NElem - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropB - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropC - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropR - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NPropS - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Nodes) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Nodes,2), UBOUND(InData%Nodes,2) - DO i1 = LBOUND(InData%Nodes,1), UBOUND(InData%Nodes,1) - ReKiBuf(Re_Xferred) = InData%Nodes(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropsB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropsB,2), UBOUND(InData%PropsB,2) - DO i1 = LBOUND(InData%PropsB,1), UBOUND(InData%PropsB,1) - ReKiBuf(Re_Xferred) = InData%PropsB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropsC) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsC,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsC,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsC,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsC,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropsC,2), UBOUND(InData%PropsC,2) - DO i1 = LBOUND(InData%PropsC,1), UBOUND(InData%PropsC,1) - ReKiBuf(Re_Xferred) = InData%PropsC(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropsR) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsR,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsR,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsR,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsR,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropsR,2), UBOUND(InData%PropsR,2) - DO i1 = LBOUND(InData%PropsR,1), UBOUND(InData%PropsR,1) - ReKiBuf(Re_Xferred) = InData%PropsR(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PropsS) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PropsS,2), UBOUND(InData%PropsS,2) - DO i1 = LBOUND(InData%PropsS,1), UBOUND(InData%PropsS,1) - ReKiBuf(Re_Xferred) = InData%PropsS(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%K) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%K,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%K,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%K,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%K,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%K,2), UBOUND(InData%K,2) - DO i1 = LBOUND(InData%K,1), UBOUND(InData%K,1) - DbKiBuf(Db_Xferred) = InData%K(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%M) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%M,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%M,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%M,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%M,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%M,2), UBOUND(InData%M,2) - DO i1 = LBOUND(InData%M,1), UBOUND(InData%M,1) - DbKiBuf(Db_Xferred) = InData%M(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ElemProps) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%ElemProps,2), UBOUND(InData%ElemProps,2) - DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) - ReKiBuf(Re_Xferred) = InData%ElemProps(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MemberNodes) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MemberNodes,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MemberNodes,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MemberNodes,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MemberNodes,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MemberNodes,2), UBOUND(InData%MemberNodes,2) - DO i1 = LBOUND(InData%MemberNodes,1), UBOUND(InData%MemberNodes,1) - IntKiBuf(Int_Xferred) = InData%MemberNodes(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodesConnN) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnN,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnN,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnN,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnN,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%NodesConnN,2), UBOUND(InData%NodesConnN,2) - DO i1 = LBOUND(InData%NodesConnN,1), UBOUND(InData%NodesConnN,1) - IntKiBuf(Int_Xferred) = InData%NodesConnN(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodesConnE) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnE,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnE,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnE,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnE,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%NodesConnE,2), UBOUND(InData%NodesConnE,2) - DO i1 = LBOUND(InData%NodesConnE,1), UBOUND(InData%NodesConnE,1) - IntKiBuf(Int_Xferred) = InData%NodesConnE(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IntKiBuf(Int_Xferred) = TRANSFER(InData%SSSum, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_PackInitType - - SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_InitType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitType' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - DO I = 1, LEN(OutData%RootName) - OutData%RootName(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - i1_l = LBOUND(OutData%TP_RefPoint,1) - i1_u = UBOUND(OutData%TP_RefPoint,1) - DO i1 = LBOUND(OutData%TP_RefPoint,1), UBOUND(OutData%TP_RefPoint,1) - OutData%TP_RefPoint(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - OutData%SubRotateZ = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%g = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - OutData%DT = DbKiBuf(Db_Xferred) - Db_Xferred = Db_Xferred + 1 - OutData%NJoints = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropSetsX = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropSetsB = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropSetsC = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropSetsR = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropSetsS = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NCMass = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NCOSMs = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%FEMMod = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NDiv = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%CBMod = TRANSFER(IntKiBuf(Int_Xferred), OutData%CBMod) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Joints not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Joints)) DEALLOCATE(OutData%Joints) - ALLOCATE(OutData%Joints(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Joints.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Joints,2), UBOUND(OutData%Joints,2) - DO i1 = LBOUND(OutData%Joints,1), UBOUND(OutData%Joints,1) - OutData%Joints(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropSetsB)) DEALLOCATE(OutData%PropSetsB) - ALLOCATE(OutData%PropSetsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropSetsB,2), UBOUND(OutData%PropSetsB,2) - DO i1 = LBOUND(OutData%PropSetsB,1), UBOUND(OutData%PropSetsB,1) - OutData%PropSetsB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsC not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropSetsC)) DEALLOCATE(OutData%PropSetsC) - ALLOCATE(OutData%PropSetsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsC.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropSetsC,2), UBOUND(OutData%PropSetsC,2) - DO i1 = LBOUND(OutData%PropSetsC,1), UBOUND(OutData%PropSetsC,1) - OutData%PropSetsC(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsR not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropSetsR)) DEALLOCATE(OutData%PropSetsR) - ALLOCATE(OutData%PropSetsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropSetsR,2), UBOUND(OutData%PropSetsR,2) - DO i1 = LBOUND(OutData%PropSetsR,1), UBOUND(OutData%PropSetsR,1) - OutData%PropSetsR(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsS not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropSetsS)) DEALLOCATE(OutData%PropSetsS) - ALLOCATE(OutData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropSetsS,2), UBOUND(OutData%PropSetsS,2) - DO i1 = LBOUND(OutData%PropSetsS,1), UBOUND(OutData%PropSetsS,1) - OutData%PropSetsS(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsX not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropSetsX)) DEALLOCATE(OutData%PropSetsX) - ALLOCATE(OutData%PropSetsX(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsX.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropSetsX,2), UBOUND(OutData%PropSetsX,2) - DO i1 = LBOUND(OutData%PropSetsX,1), UBOUND(OutData%PropSetsX,1) - OutData%PropSetsX(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! COSMs not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%COSMs)) DEALLOCATE(OutData%COSMs) - ALLOCATE(OutData%COSMs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%COSMs.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%COSMs,2), UBOUND(OutData%COSMs,2) - DO i1 = LBOUND(OutData%COSMs,1), UBOUND(OutData%COSMs,1) - OutData%COSMs(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMass not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CMass)) DEALLOCATE(OutData%CMass) - ALLOCATE(OutData%CMass(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMass.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%CMass,2), UBOUND(OutData%CMass,2) - DO i1 = LBOUND(OutData%CMass,1), UBOUND(OutData%CMass,1) - OutData%CMass(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! JDampings not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%JDampings)) DEALLOCATE(OutData%JDampings) - ALLOCATE(OutData%JDampings(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%JDampings.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%JDampings,1), UBOUND(OutData%JDampings,1) - OutData%JDampings(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - OutData%GuyanDampMod = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - i1_l = LBOUND(OutData%RayleighDamp,1) - i1_u = UBOUND(OutData%RayleighDamp,1) - DO i1 = LBOUND(OutData%RayleighDamp,1), UBOUND(OutData%RayleighDamp,1) - OutData%RayleighDamp(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - i1_l = LBOUND(OutData%GuyanDampMat,1) - i1_u = UBOUND(OutData%GuyanDampMat,1) - i2_l = LBOUND(OutData%GuyanDampMat,2) - i2_u = UBOUND(OutData%GuyanDampMat,2) - DO i2 = LBOUND(OutData%GuyanDampMat,2), UBOUND(OutData%GuyanDampMat,2) - DO i1 = LBOUND(OutData%GuyanDampMat,1), UBOUND(OutData%GuyanDampMat,1) - OutData%GuyanDampMat(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Members not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Members)) DEALLOCATE(OutData%Members) - ALLOCATE(OutData%Members(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Members.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Members,2), UBOUND(OutData%Members,2) - DO i1 = LBOUND(OutData%Members,1), UBOUND(OutData%Members,1) - OutData%Members(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSOutList not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SSOutList)) DEALLOCATE(OutData%SSOutList) - ALLOCATE(OutData%SSOutList(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSOutList.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%SSOutList,1), UBOUND(OutData%SSOutList,1) - DO I = 1, LEN(OutData%SSOutList) - OutData%SSOutList(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - OutData%OutCOSM = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutCOSM) - Int_Xferred = Int_Xferred + 1 - OutData%TabDelim = TRANSFER(IntKiBuf(Int_Xferred), OutData%TabDelim) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIK not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SSIK)) DEALLOCATE(OutData%SSIK) - ALLOCATE(OutData%SSIK(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIK.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%SSIK,2), UBOUND(OutData%SSIK,2) - DO i1 = LBOUND(OutData%SSIK,1), UBOUND(OutData%SSIK,1) - OutData%SSIK(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SSIM)) DEALLOCATE(OutData%SSIM) - ALLOCATE(OutData%SSIM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%SSIM,2), UBOUND(OutData%SSIM,2) - DO i1 = LBOUND(OutData%SSIM,1), UBOUND(OutData%SSIM,1) - OutData%SSIM(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIfile not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SSIfile)) DEALLOCATE(OutData%SSIfile) - ALLOCATE(OutData%SSIfile(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIfile.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%SSIfile,1), UBOUND(OutData%SSIfile,1) - DO I = 1, LEN(OutData%SSIfile) - OutData%SSIfile(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_K not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i3_l = IntKiBuf( Int_Xferred ) - i3_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Soil_K)) DEALLOCATE(OutData%Soil_K) - ALLOCATE(OutData%Soil_K(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_K.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i3 = LBOUND(OutData%Soil_K,3), UBOUND(OutData%Soil_K,3) - DO i2 = LBOUND(OutData%Soil_K,2), UBOUND(OutData%Soil_K,2) - DO i1 = LBOUND(OutData%Soil_K,1), UBOUND(OutData%Soil_K,1) - OutData%Soil_K(i1,i2,i3) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_Points not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Soil_Points)) DEALLOCATE(OutData%Soil_Points) - ALLOCATE(OutData%Soil_Points(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_Points.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Soil_Points,2), UBOUND(OutData%Soil_Points,2) - DO i1 = LBOUND(OutData%Soil_Points,1), UBOUND(OutData%Soil_Points,1) - OutData%Soil_Points(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_Nodes not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Soil_Nodes)) DEALLOCATE(OutData%Soil_Nodes) - ALLOCATE(OutData%Soil_Nodes(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%Soil_Nodes,1), UBOUND(OutData%Soil_Nodes,1) - OutData%Soil_Nodes(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - OutData%NElem = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropB = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropC = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropR = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NPropS = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Nodes)) DEALLOCATE(OutData%Nodes) - ALLOCATE(OutData%Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Nodes,2), UBOUND(OutData%Nodes,2) - DO i1 = LBOUND(OutData%Nodes,1), UBOUND(OutData%Nodes,1) - OutData%Nodes(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropsB)) DEALLOCATE(OutData%PropsB) - ALLOCATE(OutData%PropsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropsB,2), UBOUND(OutData%PropsB,2) - DO i1 = LBOUND(OutData%PropsB,1), UBOUND(OutData%PropsB,1) - OutData%PropsB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsC not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropsC)) DEALLOCATE(OutData%PropsC) - ALLOCATE(OutData%PropsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsC.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropsC,2), UBOUND(OutData%PropsC,2) - DO i1 = LBOUND(OutData%PropsC,1), UBOUND(OutData%PropsC,1) - OutData%PropsC(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsR not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropsR)) DEALLOCATE(OutData%PropsR) - ALLOCATE(OutData%PropsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsR.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropsR,2), UBOUND(OutData%PropsR,2) - DO i1 = LBOUND(OutData%PropsR,1), UBOUND(OutData%PropsR,1) - OutData%PropsR(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsS not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PropsS)) DEALLOCATE(OutData%PropsS) - ALLOCATE(OutData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PropsS,2), UBOUND(OutData%PropsS,2) - DO i1 = LBOUND(OutData%PropsS,1), UBOUND(OutData%PropsS,1) - OutData%PropsS(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! K not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%K)) DEALLOCATE(OutData%K) - ALLOCATE(OutData%K(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%K.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%K,2), UBOUND(OutData%K,2) - DO i1 = LBOUND(OutData%K,1), UBOUND(OutData%K,1) - OutData%K(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! M not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%M)) DEALLOCATE(OutData%M) - ALLOCATE(OutData%M(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%M.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%M,2), UBOUND(OutData%M,2) - DO i1 = LBOUND(OutData%M,1), UBOUND(OutData%M,1) - OutData%M(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemProps not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ElemProps)) DEALLOCATE(OutData%ElemProps) - ALLOCATE(OutData%ElemProps(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemProps.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%ElemProps,2), UBOUND(OutData%ElemProps,2) - DO i1 = LBOUND(OutData%ElemProps,1), UBOUND(OutData%ElemProps,1) - OutData%ElemProps(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MemberNodes not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MemberNodes)) DEALLOCATE(OutData%MemberNodes) - ALLOCATE(OutData%MemberNodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MemberNodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MemberNodes,2), UBOUND(OutData%MemberNodes,2) - DO i1 = LBOUND(OutData%MemberNodes,1), UBOUND(OutData%MemberNodes,1) - OutData%MemberNodes(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesConnN not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodesConnN)) DEALLOCATE(OutData%NodesConnN) - ALLOCATE(OutData%NodesConnN(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesConnN.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%NodesConnN,2), UBOUND(OutData%NodesConnN,2) - DO i1 = LBOUND(OutData%NodesConnN,1), UBOUND(OutData%NodesConnN,1) - OutData%NodesConnN(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesConnE not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodesConnE)) DEALLOCATE(OutData%NodesConnE) - ALLOCATE(OutData%NodesConnE(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesConnE.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%NodesConnE,2), UBOUND(OutData%NodesConnE,2) - DO i1 = LBOUND(OutData%NodesConnE,1), UBOUND(OutData%NodesConnE,1) - OutData%NodesConnE(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - OutData%SSSum = TRANSFER(IntKiBuf(Int_Xferred), OutData%SSSum) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_UnPackInitType - - SUBROUTINE SD_CopyContState( SrcContStateData, DstContStateData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_ContinuousStateType), INTENT(IN) :: SrcContStateData - TYPE(SD_ContinuousStateType), INTENT(INOUT) :: DstContStateData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyContState' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcContStateData%qm)) THEN - i1_l = LBOUND(SrcContStateData%qm,1) - i1_u = UBOUND(SrcContStateData%qm,1) - IF (.NOT. ALLOCATED(DstContStateData%qm)) THEN - ALLOCATE(DstContStateData%qm(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstContStateData%qm.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstContStateData%qm = SrcContStateData%qm -ENDIF -IF (ALLOCATED(SrcContStateData%qmdot)) THEN - i1_l = LBOUND(SrcContStateData%qmdot,1) - i1_u = UBOUND(SrcContStateData%qmdot,1) - IF (.NOT. ALLOCATED(DstContStateData%qmdot)) THEN - ALLOCATE(DstContStateData%qmdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstContStateData%qmdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstContStateData%qmdot = SrcContStateData%qmdot -ENDIF - END SUBROUTINE SD_CopyContState - - SUBROUTINE SD_DestroyContState( ContStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_ContinuousStateType), INTENT(INOUT) :: ContStateData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyContState' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(ContStateData%qm)) THEN - DEALLOCATE(ContStateData%qm) -ENDIF -IF (ALLOCATED(ContStateData%qmdot)) THEN - DEALLOCATE(ContStateData%qmdot) -ENDIF - END SUBROUTINE SD_DestroyContState - - SUBROUTINE SD_PackContState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_ContinuousStateType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackContState' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! qm allocated yes/no - IF ( ALLOCATED(InData%qm) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! qm upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%qm) ! qm - END IF - Int_BufSz = Int_BufSz + 1 ! qmdot allocated yes/no - IF ( ALLOCATED(InData%qmdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! qmdot upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%qmdot) ! qmdot - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%qm) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%qm,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qm,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%qm,1), UBOUND(InData%qm,1) - DbKiBuf(Db_Xferred) = InData%qm(i1) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%qmdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%qmdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qmdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%qmdot,1), UBOUND(InData%qmdot,1) - DbKiBuf(Db_Xferred) = InData%qmdot(i1) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackContState - - SUBROUTINE SD_UnPackContState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_ContinuousStateType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackContState' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qm not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%qm)) DEALLOCATE(OutData%qm) - ALLOCATE(OutData%qm(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qm.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%qm,1), UBOUND(OutData%qm,1) - OutData%qm(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qmdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%qmdot)) DEALLOCATE(OutData%qmdot) - ALLOCATE(OutData%qmdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qmdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%qmdot,1), UBOUND(OutData%qmdot,1) - OutData%qmdot(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackContState - - SUBROUTINE SD_CopyDiscState( SrcDiscStateData, DstDiscStateData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_DiscreteStateType), INTENT(IN) :: SrcDiscStateData - TYPE(SD_DiscreteStateType), INTENT(INOUT) :: DstDiscStateData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyDiscState' -! - ErrStat = ErrID_None - ErrMsg = "" - DstDiscStateData%DummyDiscState = SrcDiscStateData%DummyDiscState - END SUBROUTINE SD_CopyDiscState - - SUBROUTINE SD_DestroyDiscState( DiscStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_DiscreteStateType), INTENT(INOUT) :: DiscStateData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyDiscState' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - - END SUBROUTINE SD_DestroyDiscState - - SUBROUTINE SD_PackDiscState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_DiscreteStateType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackDiscState' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Re_BufSz = Re_BufSz + 1 ! DummyDiscState - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - ReKiBuf(Re_Xferred) = InData%DummyDiscState - Re_Xferred = Re_Xferred + 1 - END SUBROUTINE SD_PackDiscState - - SUBROUTINE SD_UnPackDiscState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_DiscreteStateType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackDiscState' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - OutData%DummyDiscState = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END SUBROUTINE SD_UnPackDiscState - - SUBROUTINE SD_CopyConstrState( SrcConstrStateData, DstConstrStateData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_ConstraintStateType), INTENT(IN) :: SrcConstrStateData - TYPE(SD_ConstraintStateType), INTENT(INOUT) :: DstConstrStateData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyConstrState' -! - ErrStat = ErrID_None - ErrMsg = "" - DstConstrStateData%DummyConstrState = SrcConstrStateData%DummyConstrState - END SUBROUTINE SD_CopyConstrState - - SUBROUTINE SD_DestroyConstrState( ConstrStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_ConstraintStateType), INTENT(INOUT) :: ConstrStateData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyConstrState' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - - END SUBROUTINE SD_DestroyConstrState - - SUBROUTINE SD_PackConstrState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_ConstraintStateType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackConstrState' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Re_BufSz = Re_BufSz + 1 ! DummyConstrState - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - ReKiBuf(Re_Xferred) = InData%DummyConstrState - Re_Xferred = Re_Xferred + 1 - END SUBROUTINE SD_PackConstrState - - SUBROUTINE SD_UnPackConstrState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_ConstraintStateType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackConstrState' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - OutData%DummyConstrState = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END SUBROUTINE SD_UnPackConstrState - - SUBROUTINE SD_CopyOtherState( SrcOtherStateData, DstOtherStateData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_OtherStateType), INTENT(IN) :: SrcOtherStateData - TYPE(SD_OtherStateType), INTENT(INOUT) :: DstOtherStateData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyOtherState' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcOtherStateData%xdot)) THEN - i1_l = LBOUND(SrcOtherStateData%xdot,1) - i1_u = UBOUND(SrcOtherStateData%xdot,1) - IF (.NOT. ALLOCATED(DstOtherStateData%xdot)) THEN - ALLOCATE(DstOtherStateData%xdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstOtherStateData%xdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcOtherStateData%xdot,1), UBOUND(SrcOtherStateData%xdot,1) - CALL SD_CopyContState( SrcOtherStateData%xdot(i1), DstOtherStateData%xdot(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF - DstOtherStateData%n = SrcOtherStateData%n - END SUBROUTINE SD_CopyOtherState - - SUBROUTINE SD_DestroyOtherState( OtherStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_OtherStateType), INTENT(INOUT) :: OtherStateData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyOtherState' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(OtherStateData%xdot)) THEN -DO i1 = LBOUND(OtherStateData%xdot,1), UBOUND(OtherStateData%xdot,1) - CALL SD_DestroyContState( OtherStateData%xdot(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(OtherStateData%xdot) -ENDIF - END SUBROUTINE SD_DestroyOtherState - - SUBROUTINE SD_PackOtherState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_OtherStateType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackOtherState' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! xdot allocated yes/no - IF ( ALLOCATED(InData%xdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! xdot upper/lower bounds for each dimension - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - DO i1 = LBOUND(InData%xdot,1), UBOUND(InData%xdot,1) - Int_BufSz = Int_BufSz + 3 ! xdot: size of buffers for each call to pack subtype - CALL SD_PackContState( Re_Buf, Db_Buf, Int_Buf, InData%xdot(i1), ErrStat2, ErrMsg2, .TRUE. ) ! xdot - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! xdot - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! xdot - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! xdot - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! n - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%xdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%xdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%xdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%xdot,1), UBOUND(InData%xdot,1) - CALL SD_PackContState( Re_Buf, Db_Buf, Int_Buf, InData%xdot(i1), ErrStat2, ErrMsg2, OnlySize ) ! xdot - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IntKiBuf(Int_Xferred) = InData%n - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_PackOtherState - - SUBROUTINE SD_UnPackOtherState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_OtherStateType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackOtherState' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! xdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%xdot)) DEALLOCATE(OutData%xdot) - ALLOCATE(OutData%xdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%xdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%xdot,1), UBOUND(OutData%xdot,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_UnpackContState( Re_Buf, Db_Buf, Int_Buf, OutData%xdot(i1), ErrStat2, ErrMsg2 ) ! xdot - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - OutData%n = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_UnPackOtherState - - SUBROUTINE SD_CopyMisc( SrcMiscData, DstMiscData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_MiscVarType), INTENT(IN) :: SrcMiscData - TYPE(SD_MiscVarType), INTENT(INOUT) :: DstMiscData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyMisc' -! - ErrStat = ErrID_None - ErrMsg = "" -IF (ALLOCATED(SrcMiscData%qmdotdot)) THEN - i1_l = LBOUND(SrcMiscData%qmdotdot,1) - i1_u = UBOUND(SrcMiscData%qmdotdot,1) - IF (.NOT. ALLOCATED(DstMiscData%qmdotdot)) THEN - ALLOCATE(DstMiscData%qmdotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%qmdotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%qmdotdot = SrcMiscData%qmdotdot -ENDIF - DstMiscData%u_TP = SrcMiscData%u_TP - DstMiscData%udot_TP = SrcMiscData%udot_TP - DstMiscData%udotdot_TP = SrcMiscData%udotdot_TP -IF (ALLOCATED(SrcMiscData%F_L)) THEN - i1_l = LBOUND(SrcMiscData%F_L,1) - i1_u = UBOUND(SrcMiscData%F_L,1) - IF (.NOT. ALLOCATED(DstMiscData%F_L)) THEN - ALLOCATE(DstMiscData%F_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%F_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%F_L = SrcMiscData%F_L -ENDIF -IF (ALLOCATED(SrcMiscData%F_L2)) THEN - i1_l = LBOUND(SrcMiscData%F_L2,1) - i1_u = UBOUND(SrcMiscData%F_L2,1) - IF (.NOT. ALLOCATED(DstMiscData%F_L2)) THEN - ALLOCATE(DstMiscData%F_L2(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%F_L2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%F_L2 = SrcMiscData%F_L2 -ENDIF -IF (ALLOCATED(SrcMiscData%UR_bar)) THEN - i1_l = LBOUND(SrcMiscData%UR_bar,1) - i1_u = UBOUND(SrcMiscData%UR_bar,1) - IF (.NOT. ALLOCATED(DstMiscData%UR_bar)) THEN - ALLOCATE(DstMiscData%UR_bar(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UR_bar = SrcMiscData%UR_bar -ENDIF -IF (ALLOCATED(SrcMiscData%UR_bar_dot)) THEN - i1_l = LBOUND(SrcMiscData%UR_bar_dot,1) - i1_u = UBOUND(SrcMiscData%UR_bar_dot,1) - IF (.NOT. ALLOCATED(DstMiscData%UR_bar_dot)) THEN - ALLOCATE(DstMiscData%UR_bar_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UR_bar_dot = SrcMiscData%UR_bar_dot -ENDIF -IF (ALLOCATED(SrcMiscData%UR_bar_dotdot)) THEN - i1_l = LBOUND(SrcMiscData%UR_bar_dotdot,1) - i1_u = UBOUND(SrcMiscData%UR_bar_dotdot,1) - IF (.NOT. ALLOCATED(DstMiscData%UR_bar_dotdot)) THEN - ALLOCATE(DstMiscData%UR_bar_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UR_bar_dotdot = SrcMiscData%UR_bar_dotdot -ENDIF -IF (ALLOCATED(SrcMiscData%UL)) THEN - i1_l = LBOUND(SrcMiscData%UL,1) - i1_u = UBOUND(SrcMiscData%UL,1) - IF (.NOT. ALLOCATED(DstMiscData%UL)) THEN - ALLOCATE(DstMiscData%UL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL = SrcMiscData%UL -ENDIF -IF (ALLOCATED(SrcMiscData%UL_NS)) THEN - i1_l = LBOUND(SrcMiscData%UL_NS,1) - i1_u = UBOUND(SrcMiscData%UL_NS,1) - IF (.NOT. ALLOCATED(DstMiscData%UL_NS)) THEN - ALLOCATE(DstMiscData%UL_NS(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_NS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL_NS = SrcMiscData%UL_NS -ENDIF -IF (ALLOCATED(SrcMiscData%UL_dot)) THEN - i1_l = LBOUND(SrcMiscData%UL_dot,1) - i1_u = UBOUND(SrcMiscData%UL_dot,1) - IF (.NOT. ALLOCATED(DstMiscData%UL_dot)) THEN - ALLOCATE(DstMiscData%UL_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL_dot = SrcMiscData%UL_dot -ENDIF -IF (ALLOCATED(SrcMiscData%UL_dotdot)) THEN - i1_l = LBOUND(SrcMiscData%UL_dotdot,1) - i1_u = UBOUND(SrcMiscData%UL_dotdot,1) - IF (.NOT. ALLOCATED(DstMiscData%UL_dotdot)) THEN - ALLOCATE(DstMiscData%UL_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL_dotdot = SrcMiscData%UL_dotdot -ENDIF -IF (ALLOCATED(SrcMiscData%DU_full)) THEN - i1_l = LBOUND(SrcMiscData%DU_full,1) - i1_u = UBOUND(SrcMiscData%DU_full,1) - IF (.NOT. ALLOCATED(DstMiscData%DU_full)) THEN - ALLOCATE(DstMiscData%DU_full(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%DU_full.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%DU_full = SrcMiscData%DU_full -ENDIF -IF (ALLOCATED(SrcMiscData%U_full)) THEN - i1_l = LBOUND(SrcMiscData%U_full,1) - i1_u = UBOUND(SrcMiscData%U_full,1) - IF (.NOT. ALLOCATED(DstMiscData%U_full)) THEN - ALLOCATE(DstMiscData%U_full(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_full = SrcMiscData%U_full -ENDIF -IF (ALLOCATED(SrcMiscData%U_full_NS)) THEN - i1_l = LBOUND(SrcMiscData%U_full_NS,1) - i1_u = UBOUND(SrcMiscData%U_full_NS,1) - IF (.NOT. ALLOCATED(DstMiscData%U_full_NS)) THEN - ALLOCATE(DstMiscData%U_full_NS(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_NS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_full_NS = SrcMiscData%U_full_NS -ENDIF -IF (ALLOCATED(SrcMiscData%U_full_dot)) THEN - i1_l = LBOUND(SrcMiscData%U_full_dot,1) - i1_u = UBOUND(SrcMiscData%U_full_dot,1) - IF (.NOT. ALLOCATED(DstMiscData%U_full_dot)) THEN - ALLOCATE(DstMiscData%U_full_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_full_dot = SrcMiscData%U_full_dot -ENDIF -IF (ALLOCATED(SrcMiscData%U_full_dotdot)) THEN - i1_l = LBOUND(SrcMiscData%U_full_dotdot,1) - i1_u = UBOUND(SrcMiscData%U_full_dotdot,1) - IF (.NOT. ALLOCATED(DstMiscData%U_full_dotdot)) THEN - ALLOCATE(DstMiscData%U_full_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_full_dotdot = SrcMiscData%U_full_dotdot -ENDIF -IF (ALLOCATED(SrcMiscData%U_full_elast)) THEN - i1_l = LBOUND(SrcMiscData%U_full_elast,1) - i1_u = UBOUND(SrcMiscData%U_full_elast,1) - IF (.NOT. ALLOCATED(DstMiscData%U_full_elast)) THEN - ALLOCATE(DstMiscData%U_full_elast(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_elast.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_full_elast = SrcMiscData%U_full_elast -ENDIF -IF (ALLOCATED(SrcMiscData%U_red)) THEN - i1_l = LBOUND(SrcMiscData%U_red,1) - i1_u = UBOUND(SrcMiscData%U_red,1) - IF (.NOT. ALLOCATED(DstMiscData%U_red)) THEN - ALLOCATE(DstMiscData%U_red(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%U_red = SrcMiscData%U_red -ENDIF -IF (ALLOCATED(SrcMiscData%FC_unit)) THEN - i1_l = LBOUND(SrcMiscData%FC_unit,1) - i1_u = UBOUND(SrcMiscData%FC_unit,1) - IF (.NOT. ALLOCATED(DstMiscData%FC_unit)) THEN - ALLOCATE(DstMiscData%FC_unit(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%FC_unit.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%FC_unit = SrcMiscData%FC_unit -ENDIF -IF (ALLOCATED(SrcMiscData%SDWrOutput)) THEN - i1_l = LBOUND(SrcMiscData%SDWrOutput,1) - i1_u = UBOUND(SrcMiscData%SDWrOutput,1) - IF (.NOT. ALLOCATED(DstMiscData%SDWrOutput)) THEN - ALLOCATE(DstMiscData%SDWrOutput(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%SDWrOutput.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%SDWrOutput = SrcMiscData%SDWrOutput -ENDIF -IF (ALLOCATED(SrcMiscData%AllOuts)) THEN - i1_l = LBOUND(SrcMiscData%AllOuts,1) - i1_u = UBOUND(SrcMiscData%AllOuts,1) - IF (.NOT. ALLOCATED(DstMiscData%AllOuts)) THEN - ALLOCATE(DstMiscData%AllOuts(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%AllOuts.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%AllOuts = SrcMiscData%AllOuts -ENDIF - DstMiscData%LastOutTime = SrcMiscData%LastOutTime - DstMiscData%Decimat = SrcMiscData%Decimat -IF (ALLOCATED(SrcMiscData%Fext)) THEN - i1_l = LBOUND(SrcMiscData%Fext,1) - i1_u = UBOUND(SrcMiscData%Fext,1) - IF (.NOT. ALLOCATED(DstMiscData%Fext)) THEN - ALLOCATE(DstMiscData%Fext(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%Fext.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%Fext = SrcMiscData%Fext -ENDIF -IF (ALLOCATED(SrcMiscData%Fext_red)) THEN - i1_l = LBOUND(SrcMiscData%Fext_red,1) - i1_u = UBOUND(SrcMiscData%Fext_red,1) - IF (.NOT. ALLOCATED(DstMiscData%Fext_red)) THEN - ALLOCATE(DstMiscData%Fext_red(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%Fext_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%Fext_red = SrcMiscData%Fext_red -ENDIF -IF (ALLOCATED(SrcMiscData%UL_SIM)) THEN - i1_l = LBOUND(SrcMiscData%UL_SIM,1) - i1_u = UBOUND(SrcMiscData%UL_SIM,1) - IF (.NOT. ALLOCATED(DstMiscData%UL_SIM)) THEN - ALLOCATE(DstMiscData%UL_SIM(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_SIM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL_SIM = SrcMiscData%UL_SIM -ENDIF -IF (ALLOCATED(SrcMiscData%UL_0m)) THEN - i1_l = LBOUND(SrcMiscData%UL_0m,1) - i1_u = UBOUND(SrcMiscData%UL_0m,1) - IF (.NOT. ALLOCATED(DstMiscData%UL_0m)) THEN - ALLOCATE(DstMiscData%UL_0m(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_0m.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstMiscData%UL_0m = SrcMiscData%UL_0m -ENDIF - END SUBROUTINE SD_CopyMisc - - SUBROUTINE SD_DestroyMisc( MiscData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_MiscVarType), INTENT(INOUT) :: MiscData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyMisc' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(MiscData%qmdotdot)) THEN - DEALLOCATE(MiscData%qmdotdot) -ENDIF -IF (ALLOCATED(MiscData%F_L)) THEN - DEALLOCATE(MiscData%F_L) -ENDIF -IF (ALLOCATED(MiscData%F_L2)) THEN - DEALLOCATE(MiscData%F_L2) -ENDIF -IF (ALLOCATED(MiscData%UR_bar)) THEN - DEALLOCATE(MiscData%UR_bar) -ENDIF -IF (ALLOCATED(MiscData%UR_bar_dot)) THEN - DEALLOCATE(MiscData%UR_bar_dot) -ENDIF -IF (ALLOCATED(MiscData%UR_bar_dotdot)) THEN - DEALLOCATE(MiscData%UR_bar_dotdot) -ENDIF -IF (ALLOCATED(MiscData%UL)) THEN - DEALLOCATE(MiscData%UL) -ENDIF -IF (ALLOCATED(MiscData%UL_NS)) THEN - DEALLOCATE(MiscData%UL_NS) -ENDIF -IF (ALLOCATED(MiscData%UL_dot)) THEN - DEALLOCATE(MiscData%UL_dot) -ENDIF -IF (ALLOCATED(MiscData%UL_dotdot)) THEN - DEALLOCATE(MiscData%UL_dotdot) -ENDIF -IF (ALLOCATED(MiscData%DU_full)) THEN - DEALLOCATE(MiscData%DU_full) -ENDIF -IF (ALLOCATED(MiscData%U_full)) THEN - DEALLOCATE(MiscData%U_full) -ENDIF -IF (ALLOCATED(MiscData%U_full_NS)) THEN - DEALLOCATE(MiscData%U_full_NS) -ENDIF -IF (ALLOCATED(MiscData%U_full_dot)) THEN - DEALLOCATE(MiscData%U_full_dot) -ENDIF -IF (ALLOCATED(MiscData%U_full_dotdot)) THEN - DEALLOCATE(MiscData%U_full_dotdot) -ENDIF -IF (ALLOCATED(MiscData%U_full_elast)) THEN - DEALLOCATE(MiscData%U_full_elast) -ENDIF -IF (ALLOCATED(MiscData%U_red)) THEN - DEALLOCATE(MiscData%U_red) -ENDIF -IF (ALLOCATED(MiscData%FC_unit)) THEN - DEALLOCATE(MiscData%FC_unit) -ENDIF -IF (ALLOCATED(MiscData%SDWrOutput)) THEN - DEALLOCATE(MiscData%SDWrOutput) -ENDIF -IF (ALLOCATED(MiscData%AllOuts)) THEN - DEALLOCATE(MiscData%AllOuts) -ENDIF -IF (ALLOCATED(MiscData%Fext)) THEN - DEALLOCATE(MiscData%Fext) -ENDIF -IF (ALLOCATED(MiscData%Fext_red)) THEN - DEALLOCATE(MiscData%Fext_red) -ENDIF -IF (ALLOCATED(MiscData%UL_SIM)) THEN - DEALLOCATE(MiscData%UL_SIM) -ENDIF -IF (ALLOCATED(MiscData%UL_0m)) THEN - DEALLOCATE(MiscData%UL_0m) -ENDIF - END SUBROUTINE SD_DestroyMisc - - SUBROUTINE SD_PackMisc( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_MiscVarType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackMisc' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Int_BufSz = Int_BufSz + 1 ! qmdotdot allocated yes/no - IF ( ALLOCATED(InData%qmdotdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! qmdotdot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%qmdotdot) ! qmdotdot - END IF - Re_BufSz = Re_BufSz + SIZE(InData%u_TP) ! u_TP - Re_BufSz = Re_BufSz + SIZE(InData%udot_TP) ! udot_TP - Re_BufSz = Re_BufSz + SIZE(InData%udotdot_TP) ! udotdot_TP - Int_BufSz = Int_BufSz + 1 ! F_L allocated yes/no - IF ( ALLOCATED(InData%F_L) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! F_L upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%F_L) ! F_L - END IF - Int_BufSz = Int_BufSz + 1 ! F_L2 allocated yes/no - IF ( ALLOCATED(InData%F_L2) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! F_L2 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%F_L2) ! F_L2 - END IF - Int_BufSz = Int_BufSz + 1 ! UR_bar allocated yes/no - IF ( ALLOCATED(InData%UR_bar) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UR_bar upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UR_bar) ! UR_bar - END IF - Int_BufSz = Int_BufSz + 1 ! UR_bar_dot allocated yes/no - IF ( ALLOCATED(InData%UR_bar_dot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UR_bar_dot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UR_bar_dot) ! UR_bar_dot - END IF - Int_BufSz = Int_BufSz + 1 ! UR_bar_dotdot allocated yes/no - IF ( ALLOCATED(InData%UR_bar_dotdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UR_bar_dotdot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UR_bar_dotdot) ! UR_bar_dotdot - END IF - Int_BufSz = Int_BufSz + 1 ! UL allocated yes/no - IF ( ALLOCATED(InData%UL) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL) ! UL - END IF - Int_BufSz = Int_BufSz + 1 ! UL_NS allocated yes/no - IF ( ALLOCATED(InData%UL_NS) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL_NS upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL_NS) ! UL_NS - END IF - Int_BufSz = Int_BufSz + 1 ! UL_dot allocated yes/no - IF ( ALLOCATED(InData%UL_dot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL_dot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL_dot) ! UL_dot - END IF - Int_BufSz = Int_BufSz + 1 ! UL_dotdot allocated yes/no - IF ( ALLOCATED(InData%UL_dotdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL_dotdot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL_dotdot) ! UL_dotdot - END IF - Int_BufSz = Int_BufSz + 1 ! DU_full allocated yes/no - IF ( ALLOCATED(InData%DU_full) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! DU_full upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%DU_full) ! DU_full - END IF - Int_BufSz = Int_BufSz + 1 ! U_full allocated yes/no - IF ( ALLOCATED(InData%U_full) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_full upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_full) ! U_full - END IF - Int_BufSz = Int_BufSz + 1 ! U_full_NS allocated yes/no - IF ( ALLOCATED(InData%U_full_NS) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_full_NS upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_full_NS) ! U_full_NS - END IF - Int_BufSz = Int_BufSz + 1 ! U_full_dot allocated yes/no - IF ( ALLOCATED(InData%U_full_dot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_full_dot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_full_dot) ! U_full_dot - END IF - Int_BufSz = Int_BufSz + 1 ! U_full_dotdot allocated yes/no - IF ( ALLOCATED(InData%U_full_dotdot) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_full_dotdot upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_full_dotdot) ! U_full_dotdot - END IF - Int_BufSz = Int_BufSz + 1 ! U_full_elast allocated yes/no - IF ( ALLOCATED(InData%U_full_elast) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_full_elast upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_full_elast) ! U_full_elast - END IF - Int_BufSz = Int_BufSz + 1 ! U_red allocated yes/no - IF ( ALLOCATED(InData%U_red) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! U_red upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%U_red) ! U_red - END IF - Int_BufSz = Int_BufSz + 1 ! FC_unit allocated yes/no - IF ( ALLOCATED(InData%FC_unit) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! FC_unit upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%FC_unit) ! FC_unit - END IF - Int_BufSz = Int_BufSz + 1 ! SDWrOutput allocated yes/no - IF ( ALLOCATED(InData%SDWrOutput) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! SDWrOutput upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%SDWrOutput) ! SDWrOutput - END IF - Int_BufSz = Int_BufSz + 1 ! AllOuts allocated yes/no - IF ( ALLOCATED(InData%AllOuts) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! AllOuts upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%AllOuts) ! AllOuts - END IF - Db_BufSz = Db_BufSz + 1 ! LastOutTime - Int_BufSz = Int_BufSz + 1 ! Decimat - Int_BufSz = Int_BufSz + 1 ! Fext allocated yes/no - IF ( ALLOCATED(InData%Fext) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! Fext upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Fext) ! Fext - END IF - Int_BufSz = Int_BufSz + 1 ! Fext_red allocated yes/no - IF ( ALLOCATED(InData%Fext_red) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! Fext_red upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%Fext_red) ! Fext_red - END IF - Int_BufSz = Int_BufSz + 1 ! UL_SIM allocated yes/no - IF ( ALLOCATED(InData%UL_SIM) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL_SIM upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL_SIM) ! UL_SIM - END IF - Int_BufSz = Int_BufSz + 1 ! UL_0m allocated yes/no - IF ( ALLOCATED(InData%UL_0m) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! UL_0m upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%UL_0m) ! UL_0m - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - IF ( .NOT. ALLOCATED(InData%qmdotdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%qmdotdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qmdotdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%qmdotdot,1), UBOUND(InData%qmdotdot,1) - ReKiBuf(Re_Xferred) = InData%qmdotdot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - DO i1 = LBOUND(InData%u_TP,1), UBOUND(InData%u_TP,1) - ReKiBuf(Re_Xferred) = InData%u_TP(i1) - Re_Xferred = Re_Xferred + 1 - END DO - DO i1 = LBOUND(InData%udot_TP,1), UBOUND(InData%udot_TP,1) - ReKiBuf(Re_Xferred) = InData%udot_TP(i1) - Re_Xferred = Re_Xferred + 1 - END DO - DO i1 = LBOUND(InData%udotdot_TP,1), UBOUND(InData%udotdot_TP,1) - ReKiBuf(Re_Xferred) = InData%udotdot_TP(i1) - Re_Xferred = Re_Xferred + 1 - END DO - IF ( .NOT. ALLOCATED(InData%F_L) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%F_L,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%F_L,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%F_L,1), UBOUND(InData%F_L,1) - ReKiBuf(Re_Xferred) = InData%F_L(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%F_L2) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%F_L2,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%F_L2,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%F_L2,1), UBOUND(InData%F_L2,1) - ReKiBuf(Re_Xferred) = InData%F_L2(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UR_bar) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UR_bar,1), UBOUND(InData%UR_bar,1) - ReKiBuf(Re_Xferred) = InData%UR_bar(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UR_bar_dot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar_dot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar_dot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UR_bar_dot,1), UBOUND(InData%UR_bar_dot,1) - ReKiBuf(Re_Xferred) = InData%UR_bar_dot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UR_bar_dotdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar_dotdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar_dotdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UR_bar_dotdot,1), UBOUND(InData%UR_bar_dotdot,1) - ReKiBuf(Re_Xferred) = InData%UR_bar_dotdot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL,1), UBOUND(InData%UL,1) - ReKiBuf(Re_Xferred) = InData%UL(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL_NS) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_NS,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_NS,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL_NS,1), UBOUND(InData%UL_NS,1) - ReKiBuf(Re_Xferred) = InData%UL_NS(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL_dot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_dot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_dot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL_dot,1), UBOUND(InData%UL_dot,1) - ReKiBuf(Re_Xferred) = InData%UL_dot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL_dotdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_dotdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_dotdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL_dotdot,1), UBOUND(InData%UL_dotdot,1) - ReKiBuf(Re_Xferred) = InData%UL_dotdot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%DU_full) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DU_full,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DU_full,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%DU_full,1), UBOUND(InData%DU_full,1) - ReKiBuf(Re_Xferred) = InData%DU_full(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_full) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_full,1), UBOUND(InData%U_full,1) - ReKiBuf(Re_Xferred) = InData%U_full(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_full_NS) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_NS,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_NS,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_full_NS,1), UBOUND(InData%U_full_NS,1) - ReKiBuf(Re_Xferred) = InData%U_full_NS(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_full_dot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_dot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_dot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_full_dot,1), UBOUND(InData%U_full_dot,1) - ReKiBuf(Re_Xferred) = InData%U_full_dot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_full_dotdot) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_dotdot,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_dotdot,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_full_dotdot,1), UBOUND(InData%U_full_dotdot,1) - ReKiBuf(Re_Xferred) = InData%U_full_dotdot(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_full_elast) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_elast,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_elast,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_full_elast,1), UBOUND(InData%U_full_elast,1) - ReKiBuf(Re_Xferred) = InData%U_full_elast(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%U_red) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%U_red,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_red,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%U_red,1), UBOUND(InData%U_red,1) - ReKiBuf(Re_Xferred) = InData%U_red(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%FC_unit) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%FC_unit,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%FC_unit,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%FC_unit,1), UBOUND(InData%FC_unit,1) - ReKiBuf(Re_Xferred) = InData%FC_unit(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%SDWrOutput) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%SDWrOutput,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SDWrOutput,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%SDWrOutput,1), UBOUND(InData%SDWrOutput,1) - ReKiBuf(Re_Xferred) = InData%SDWrOutput(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%AllOuts) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%AllOuts,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AllOuts,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%AllOuts,1), UBOUND(InData%AllOuts,1) - ReKiBuf(Re_Xferred) = InData%AllOuts(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - DbKiBuf(Db_Xferred) = InData%LastOutTime - Db_Xferred = Db_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%Decimat - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Fext) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Fext,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fext,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%Fext,1), UBOUND(InData%Fext,1) - ReKiBuf(Re_Xferred) = InData%Fext(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Fext_red) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Fext_red,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fext_red,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%Fext_red,1), UBOUND(InData%Fext_red,1) - ReKiBuf(Re_Xferred) = InData%Fext_red(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL_SIM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_SIM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_SIM,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL_SIM,1), UBOUND(InData%UL_SIM,1) - ReKiBuf(Re_Xferred) = InData%UL_SIM(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%UL_0m) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_0m,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_0m,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%UL_0m,1), UBOUND(InData%UL_0m,1) - ReKiBuf(Re_Xferred) = InData%UL_0m(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackMisc - - SUBROUTINE SD_UnPackMisc( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_MiscVarType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackMisc' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qmdotdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%qmdotdot)) DEALLOCATE(OutData%qmdotdot) - ALLOCATE(OutData%qmdotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qmdotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%qmdotdot,1), UBOUND(OutData%qmdotdot,1) - OutData%qmdotdot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - i1_l = LBOUND(OutData%u_TP,1) - i1_u = UBOUND(OutData%u_TP,1) - DO i1 = LBOUND(OutData%u_TP,1), UBOUND(OutData%u_TP,1) - OutData%u_TP(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - i1_l = LBOUND(OutData%udot_TP,1) - i1_u = UBOUND(OutData%udot_TP,1) - DO i1 = LBOUND(OutData%udot_TP,1), UBOUND(OutData%udot_TP,1) - OutData%udot_TP(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - i1_l = LBOUND(OutData%udotdot_TP,1) - i1_u = UBOUND(OutData%udotdot_TP,1) - DO i1 = LBOUND(OutData%udotdot_TP,1), UBOUND(OutData%udotdot_TP,1) - OutData%udotdot_TP(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! F_L not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%F_L)) DEALLOCATE(OutData%F_L) - ALLOCATE(OutData%F_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%F_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%F_L,1), UBOUND(OutData%F_L,1) - OutData%F_L(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! F_L2 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%F_L2)) DEALLOCATE(OutData%F_L2) - ALLOCATE(OutData%F_L2(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%F_L2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%F_L2,1), UBOUND(OutData%F_L2,1) - OutData%F_L2(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UR_bar)) DEALLOCATE(OutData%UR_bar) - ALLOCATE(OutData%UR_bar(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UR_bar,1), UBOUND(OutData%UR_bar,1) - OutData%UR_bar(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar_dot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UR_bar_dot)) DEALLOCATE(OutData%UR_bar_dot) - ALLOCATE(OutData%UR_bar_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UR_bar_dot,1), UBOUND(OutData%UR_bar_dot,1) - OutData%UR_bar_dot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar_dotdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UR_bar_dotdot)) DEALLOCATE(OutData%UR_bar_dotdot) - ALLOCATE(OutData%UR_bar_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UR_bar_dotdot,1), UBOUND(OutData%UR_bar_dotdot,1) - OutData%UR_bar_dotdot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL)) DEALLOCATE(OutData%UL) - ALLOCATE(OutData%UL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL,1), UBOUND(OutData%UL,1) - OutData%UL(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_NS not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL_NS)) DEALLOCATE(OutData%UL_NS) - ALLOCATE(OutData%UL_NS(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_NS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL_NS,1), UBOUND(OutData%UL_NS,1) - OutData%UL_NS(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_dot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL_dot)) DEALLOCATE(OutData%UL_dot) - ALLOCATE(OutData%UL_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL_dot,1), UBOUND(OutData%UL_dot,1) - OutData%UL_dot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_dotdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL_dotdot)) DEALLOCATE(OutData%UL_dotdot) - ALLOCATE(OutData%UL_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL_dotdot,1), UBOUND(OutData%UL_dotdot,1) - OutData%UL_dotdot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DU_full not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%DU_full)) DEALLOCATE(OutData%DU_full) - ALLOCATE(OutData%DU_full(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DU_full.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%DU_full,1), UBOUND(OutData%DU_full,1) - OutData%DU_full(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_full)) DEALLOCATE(OutData%U_full) - ALLOCATE(OutData%U_full(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_full,1), UBOUND(OutData%U_full,1) - OutData%U_full(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_NS not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_full_NS)) DEALLOCATE(OutData%U_full_NS) - ALLOCATE(OutData%U_full_NS(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_NS.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_full_NS,1), UBOUND(OutData%U_full_NS,1) - OutData%U_full_NS(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_dot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_full_dot)) DEALLOCATE(OutData%U_full_dot) - ALLOCATE(OutData%U_full_dot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_dot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_full_dot,1), UBOUND(OutData%U_full_dot,1) - OutData%U_full_dot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_dotdot not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_full_dotdot)) DEALLOCATE(OutData%U_full_dotdot) - ALLOCATE(OutData%U_full_dotdot(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_dotdot.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_full_dotdot,1), UBOUND(OutData%U_full_dotdot,1) - OutData%U_full_dotdot(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_elast not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_full_elast)) DEALLOCATE(OutData%U_full_elast) - ALLOCATE(OutData%U_full_elast(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_elast.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_full_elast,1), UBOUND(OutData%U_full_elast,1) - OutData%U_full_elast(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_red not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%U_red)) DEALLOCATE(OutData%U_red) - ALLOCATE(OutData%U_red(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%U_red,1), UBOUND(OutData%U_red,1) - OutData%U_red(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! FC_unit not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%FC_unit)) DEALLOCATE(OutData%FC_unit) - ALLOCATE(OutData%FC_unit(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%FC_unit.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%FC_unit,1), UBOUND(OutData%FC_unit,1) - OutData%FC_unit(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SDWrOutput not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%SDWrOutput)) DEALLOCATE(OutData%SDWrOutput) - ALLOCATE(OutData%SDWrOutput(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SDWrOutput.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%SDWrOutput,1), UBOUND(OutData%SDWrOutput,1) - OutData%SDWrOutput(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AllOuts not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%AllOuts)) DEALLOCATE(OutData%AllOuts) - ALLOCATE(OutData%AllOuts(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AllOuts.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%AllOuts,1), UBOUND(OutData%AllOuts,1) - OutData%AllOuts(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - OutData%LastOutTime = DbKiBuf(Db_Xferred) - Db_Xferred = Db_Xferred + 1 - OutData%Decimat = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fext not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Fext)) DEALLOCATE(OutData%Fext) - ALLOCATE(OutData%Fext(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fext.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%Fext,1), UBOUND(OutData%Fext,1) - OutData%Fext(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fext_red not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Fext_red)) DEALLOCATE(OutData%Fext_red) - ALLOCATE(OutData%Fext_red(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fext_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%Fext_red,1), UBOUND(OutData%Fext_red,1) - OutData%Fext_red(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_SIM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL_SIM)) DEALLOCATE(OutData%UL_SIM) - ALLOCATE(OutData%UL_SIM(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_SIM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL_SIM,1), UBOUND(OutData%UL_SIM,1) - OutData%UL_SIM(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_0m not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%UL_0m)) DEALLOCATE(OutData%UL_0m) - ALLOCATE(OutData%UL_0m(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_0m.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%UL_0m,1), UBOUND(OutData%UL_0m,1) - OutData%UL_0m(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackMisc - - SUBROUTINE SD_CopyParam( SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_ParameterType), INTENT(IN) :: SrcParamData - TYPE(SD_ParameterType), INTENT(INOUT) :: DstParamData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyParam' -! - ErrStat = ErrID_None - ErrMsg = "" - DstParamData%SDDeltaT = SrcParamData%SDDeltaT - DstParamData%IntMethod = SrcParamData%IntMethod - DstParamData%nDOF = SrcParamData%nDOF - DstParamData%nDOF_red = SrcParamData%nDOF_red - DstParamData%Nmembers = SrcParamData%Nmembers -IF (ALLOCATED(SrcParamData%Elems)) THEN - i1_l = LBOUND(SrcParamData%Elems,1) - i1_u = UBOUND(SrcParamData%Elems,1) - i2_l = LBOUND(SrcParamData%Elems,2) - i2_u = UBOUND(SrcParamData%Elems,2) - IF (.NOT. ALLOCATED(DstParamData%Elems)) THEN - ALLOCATE(DstParamData%Elems(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Elems.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%Elems = SrcParamData%Elems -ENDIF -IF (ALLOCATED(SrcParamData%ElemProps)) THEN - i1_l = LBOUND(SrcParamData%ElemProps,1) - i1_u = UBOUND(SrcParamData%ElemProps,1) - IF (.NOT. ALLOCATED(DstParamData%ElemProps)) THEN - ALLOCATE(DstParamData%ElemProps(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ElemProps.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%ElemProps,1), UBOUND(SrcParamData%ElemProps,1) - CALL SD_Copyelemproptype( SrcParamData%ElemProps(i1), DstParamData%ElemProps(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%FG)) THEN - i1_l = LBOUND(SrcParamData%FG,1) - i1_u = UBOUND(SrcParamData%FG,1) - IF (.NOT. ALLOCATED(DstParamData%FG)) THEN - ALLOCATE(DstParamData%FG(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%FG.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%FG = SrcParamData%FG -ENDIF -IF (ALLOCATED(SrcParamData%DP0)) THEN - i1_l = LBOUND(SrcParamData%DP0,1) - i1_u = UBOUND(SrcParamData%DP0,1) - i2_l = LBOUND(SrcParamData%DP0,2) - i2_u = UBOUND(SrcParamData%DP0,2) - IF (.NOT. ALLOCATED(DstParamData%DP0)) THEN - ALLOCATE(DstParamData%DP0(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%DP0.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%DP0 = SrcParamData%DP0 -ENDIF -IF (ALLOCATED(SrcParamData%NodeID2JointID)) THEN - i1_l = LBOUND(SrcParamData%NodeID2JointID,1) - i1_u = UBOUND(SrcParamData%NodeID2JointID,1) - IF (.NOT. ALLOCATED(DstParamData%NodeID2JointID)) THEN - ALLOCATE(DstParamData%NodeID2JointID(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodeID2JointID.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%NodeID2JointID = SrcParamData%NodeID2JointID -ENDIF - DstParamData%reduced = SrcParamData%reduced -IF (ALLOCATED(SrcParamData%T_red)) THEN - i1_l = LBOUND(SrcParamData%T_red,1) - i1_u = UBOUND(SrcParamData%T_red,1) - i2_l = LBOUND(SrcParamData%T_red,2) - i2_u = UBOUND(SrcParamData%T_red,2) - IF (.NOT. ALLOCATED(DstParamData%T_red)) THEN - ALLOCATE(DstParamData%T_red(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%T_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%T_red = SrcParamData%T_red -ENDIF -IF (ALLOCATED(SrcParamData%T_red_T)) THEN - i1_l = LBOUND(SrcParamData%T_red_T,1) - i1_u = UBOUND(SrcParamData%T_red_T,1) - i2_l = LBOUND(SrcParamData%T_red_T,2) - i2_u = UBOUND(SrcParamData%T_red_T,2) - IF (.NOT. ALLOCATED(DstParamData%T_red_T)) THEN - ALLOCATE(DstParamData%T_red_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%T_red_T.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%T_red_T = SrcParamData%T_red_T -ENDIF -IF (ALLOCATED(SrcParamData%NodesDOF)) THEN - i1_l = LBOUND(SrcParamData%NodesDOF,1) - i1_u = UBOUND(SrcParamData%NodesDOF,1) - IF (.NOT. ALLOCATED(DstParamData%NodesDOF)) THEN - ALLOCATE(DstParamData%NodesDOF(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodesDOF.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%NodesDOF,1), UBOUND(SrcParamData%NodesDOF,1) - CALL SD_Copyilist( SrcParamData%NodesDOF(i1), DstParamData%NodesDOF(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%NodesDOFred)) THEN - i1_l = LBOUND(SrcParamData%NodesDOFred,1) - i1_u = UBOUND(SrcParamData%NodesDOFred,1) - IF (.NOT. ALLOCATED(DstParamData%NodesDOFred)) THEN - ALLOCATE(DstParamData%NodesDOFred(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodesDOFred.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%NodesDOFred,1), UBOUND(SrcParamData%NodesDOFred,1) - CALL SD_Copyilist( SrcParamData%NodesDOFred(i1), DstParamData%NodesDOFred(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%ElemsDOF)) THEN - i1_l = LBOUND(SrcParamData%ElemsDOF,1) - i1_u = UBOUND(SrcParamData%ElemsDOF,1) - i2_l = LBOUND(SrcParamData%ElemsDOF,2) - i2_u = UBOUND(SrcParamData%ElemsDOF,2) - IF (.NOT. ALLOCATED(DstParamData%ElemsDOF)) THEN - ALLOCATE(DstParamData%ElemsDOF(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ElemsDOF.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%ElemsDOF = SrcParamData%ElemsDOF -ENDIF -IF (ALLOCATED(SrcParamData%DOFred2Nodes)) THEN - i1_l = LBOUND(SrcParamData%DOFred2Nodes,1) - i1_u = UBOUND(SrcParamData%DOFred2Nodes,1) - i2_l = LBOUND(SrcParamData%DOFred2Nodes,2) - i2_u = UBOUND(SrcParamData%DOFred2Nodes,2) - IF (.NOT. ALLOCATED(DstParamData%DOFred2Nodes)) THEN - ALLOCATE(DstParamData%DOFred2Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%DOFred2Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%DOFred2Nodes = SrcParamData%DOFred2Nodes -ENDIF -IF (ALLOCATED(SrcParamData%CtrlElem2Channel)) THEN - i1_l = LBOUND(SrcParamData%CtrlElem2Channel,1) - i1_u = UBOUND(SrcParamData%CtrlElem2Channel,1) - i2_l = LBOUND(SrcParamData%CtrlElem2Channel,2) - i2_u = UBOUND(SrcParamData%CtrlElem2Channel,2) - IF (.NOT. ALLOCATED(DstParamData%CtrlElem2Channel)) THEN - ALLOCATE(DstParamData%CtrlElem2Channel(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CtrlElem2Channel.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%CtrlElem2Channel = SrcParamData%CtrlElem2Channel -ENDIF - DstParamData%nDOFM = SrcParamData%nDOFM - DstParamData%SttcSolve = SrcParamData%SttcSolve - DstParamData%GuyanLoadCorrection = SrcParamData%GuyanLoadCorrection - DstParamData%Floating = SrcParamData%Floating -IF (ALLOCATED(SrcParamData%KMMDiag)) THEN - i1_l = LBOUND(SrcParamData%KMMDiag,1) - i1_u = UBOUND(SrcParamData%KMMDiag,1) - IF (.NOT. ALLOCATED(DstParamData%KMMDiag)) THEN - ALLOCATE(DstParamData%KMMDiag(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KMMDiag.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%KMMDiag = SrcParamData%KMMDiag -ENDIF -IF (ALLOCATED(SrcParamData%CMMDiag)) THEN - i1_l = LBOUND(SrcParamData%CMMDiag,1) - i1_u = UBOUND(SrcParamData%CMMDiag,1) - IF (.NOT. ALLOCATED(DstParamData%CMMDiag)) THEN - ALLOCATE(DstParamData%CMMDiag(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CMMDiag.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%CMMDiag = SrcParamData%CMMDiag -ENDIF -IF (ALLOCATED(SrcParamData%MMB)) THEN - i1_l = LBOUND(SrcParamData%MMB,1) - i1_u = UBOUND(SrcParamData%MMB,1) - i2_l = LBOUND(SrcParamData%MMB,2) - i2_u = UBOUND(SrcParamData%MMB,2) - IF (.NOT. ALLOCATED(DstParamData%MMB)) THEN - ALLOCATE(DstParamData%MMB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MMB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%MMB = SrcParamData%MMB -ENDIF -IF (ALLOCATED(SrcParamData%MBmmB)) THEN - i1_l = LBOUND(SrcParamData%MBmmB,1) - i1_u = UBOUND(SrcParamData%MBmmB,1) - i2_l = LBOUND(SrcParamData%MBmmB,2) - i2_u = UBOUND(SrcParamData%MBmmB,2) - IF (.NOT. ALLOCATED(DstParamData%MBmmB)) THEN - ALLOCATE(DstParamData%MBmmB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBmmB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%MBmmB = SrcParamData%MBmmB -ENDIF -IF (ALLOCATED(SrcParamData%C1_11)) THEN - i1_l = LBOUND(SrcParamData%C1_11,1) - i1_u = UBOUND(SrcParamData%C1_11,1) - i2_l = LBOUND(SrcParamData%C1_11,2) - i2_u = UBOUND(SrcParamData%C1_11,2) - IF (.NOT. ALLOCATED(DstParamData%C1_11)) THEN - ALLOCATE(DstParamData%C1_11(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C1_11.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%C1_11 = SrcParamData%C1_11 -ENDIF -IF (ALLOCATED(SrcParamData%C1_12)) THEN - i1_l = LBOUND(SrcParamData%C1_12,1) - i1_u = UBOUND(SrcParamData%C1_12,1) - i2_l = LBOUND(SrcParamData%C1_12,2) - i2_u = UBOUND(SrcParamData%C1_12,2) - IF (.NOT. ALLOCATED(DstParamData%C1_12)) THEN - ALLOCATE(DstParamData%C1_12(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C1_12.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%C1_12 = SrcParamData%C1_12 -ENDIF -IF (ALLOCATED(SrcParamData%D1_141)) THEN - i1_l = LBOUND(SrcParamData%D1_141,1) - i1_u = UBOUND(SrcParamData%D1_141,1) - i2_l = LBOUND(SrcParamData%D1_141,2) - i2_u = UBOUND(SrcParamData%D1_141,2) - IF (.NOT. ALLOCATED(DstParamData%D1_141)) THEN - ALLOCATE(DstParamData%D1_141(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D1_141.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%D1_141 = SrcParamData%D1_141 -ENDIF -IF (ALLOCATED(SrcParamData%D1_142)) THEN - i1_l = LBOUND(SrcParamData%D1_142,1) - i1_u = UBOUND(SrcParamData%D1_142,1) - i2_l = LBOUND(SrcParamData%D1_142,2) - i2_u = UBOUND(SrcParamData%D1_142,2) - IF (.NOT. ALLOCATED(DstParamData%D1_142)) THEN - ALLOCATE(DstParamData%D1_142(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D1_142.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%D1_142 = SrcParamData%D1_142 -ENDIF -IF (ALLOCATED(SrcParamData%PhiM)) THEN - i1_l = LBOUND(SrcParamData%PhiM,1) - i1_u = UBOUND(SrcParamData%PhiM,1) - i2_l = LBOUND(SrcParamData%PhiM,2) - i2_u = UBOUND(SrcParamData%PhiM,2) - IF (.NOT. ALLOCATED(DstParamData%PhiM)) THEN - ALLOCATE(DstParamData%PhiM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%PhiM = SrcParamData%PhiM -ENDIF -IF (ALLOCATED(SrcParamData%C2_61)) THEN - i1_l = LBOUND(SrcParamData%C2_61,1) - i1_u = UBOUND(SrcParamData%C2_61,1) - i2_l = LBOUND(SrcParamData%C2_61,2) - i2_u = UBOUND(SrcParamData%C2_61,2) - IF (.NOT. ALLOCATED(DstParamData%C2_61)) THEN - ALLOCATE(DstParamData%C2_61(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C2_61.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%C2_61 = SrcParamData%C2_61 -ENDIF -IF (ALLOCATED(SrcParamData%C2_62)) THEN - i1_l = LBOUND(SrcParamData%C2_62,1) - i1_u = UBOUND(SrcParamData%C2_62,1) - i2_l = LBOUND(SrcParamData%C2_62,2) - i2_u = UBOUND(SrcParamData%C2_62,2) - IF (.NOT. ALLOCATED(DstParamData%C2_62)) THEN - ALLOCATE(DstParamData%C2_62(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C2_62.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%C2_62 = SrcParamData%C2_62 -ENDIF -IF (ALLOCATED(SrcParamData%PhiRb_TI)) THEN - i1_l = LBOUND(SrcParamData%PhiRb_TI,1) - i1_u = UBOUND(SrcParamData%PhiRb_TI,1) - i2_l = LBOUND(SrcParamData%PhiRb_TI,2) - i2_u = UBOUND(SrcParamData%PhiRb_TI,2) - IF (.NOT. ALLOCATED(DstParamData%PhiRb_TI)) THEN - ALLOCATE(DstParamData%PhiRb_TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiRb_TI.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%PhiRb_TI = SrcParamData%PhiRb_TI -ENDIF -IF (ALLOCATED(SrcParamData%D2_63)) THEN - i1_l = LBOUND(SrcParamData%D2_63,1) - i1_u = UBOUND(SrcParamData%D2_63,1) - i2_l = LBOUND(SrcParamData%D2_63,2) - i2_u = UBOUND(SrcParamData%D2_63,2) - IF (.NOT. ALLOCATED(DstParamData%D2_63)) THEN - ALLOCATE(DstParamData%D2_63(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D2_63.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%D2_63 = SrcParamData%D2_63 -ENDIF -IF (ALLOCATED(SrcParamData%D2_64)) THEN - i1_l = LBOUND(SrcParamData%D2_64,1) - i1_u = UBOUND(SrcParamData%D2_64,1) - i2_l = LBOUND(SrcParamData%D2_64,2) - i2_u = UBOUND(SrcParamData%D2_64,2) - IF (.NOT. ALLOCATED(DstParamData%D2_64)) THEN - ALLOCATE(DstParamData%D2_64(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D2_64.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%D2_64 = SrcParamData%D2_64 -ENDIF -IF (ALLOCATED(SrcParamData%MBB)) THEN - i1_l = LBOUND(SrcParamData%MBB,1) - i1_u = UBOUND(SrcParamData%MBB,1) - i2_l = LBOUND(SrcParamData%MBB,2) - i2_u = UBOUND(SrcParamData%MBB,2) - IF (.NOT. ALLOCATED(DstParamData%MBB)) THEN - ALLOCATE(DstParamData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%MBB = SrcParamData%MBB -ENDIF -IF (ALLOCATED(SrcParamData%KBB)) THEN - i1_l = LBOUND(SrcParamData%KBB,1) - i1_u = UBOUND(SrcParamData%KBB,1) - i2_l = LBOUND(SrcParamData%KBB,2) - i2_u = UBOUND(SrcParamData%KBB,2) - IF (.NOT. ALLOCATED(DstParamData%KBB)) THEN - ALLOCATE(DstParamData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%KBB = SrcParamData%KBB -ENDIF -IF (ALLOCATED(SrcParamData%CBB)) THEN - i1_l = LBOUND(SrcParamData%CBB,1) - i1_u = UBOUND(SrcParamData%CBB,1) - i2_l = LBOUND(SrcParamData%CBB,2) - i2_u = UBOUND(SrcParamData%CBB,2) - IF (.NOT. ALLOCATED(DstParamData%CBB)) THEN - ALLOCATE(DstParamData%CBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%CBB = SrcParamData%CBB -ENDIF -IF (ALLOCATED(SrcParamData%CMM)) THEN - i1_l = LBOUND(SrcParamData%CMM,1) - i1_u = UBOUND(SrcParamData%CMM,1) - i2_l = LBOUND(SrcParamData%CMM,2) - i2_u = UBOUND(SrcParamData%CMM,2) - IF (.NOT. ALLOCATED(DstParamData%CMM)) THEN - ALLOCATE(DstParamData%CMM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CMM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%CMM = SrcParamData%CMM -ENDIF -IF (ALLOCATED(SrcParamData%MBM)) THEN - i1_l = LBOUND(SrcParamData%MBM,1) - i1_u = UBOUND(SrcParamData%MBM,1) - i2_l = LBOUND(SrcParamData%MBM,2) - i2_u = UBOUND(SrcParamData%MBM,2) - IF (.NOT. ALLOCATED(DstParamData%MBM)) THEN - ALLOCATE(DstParamData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%MBM = SrcParamData%MBM -ENDIF -IF (ALLOCATED(SrcParamData%PhiL_T)) THEN - i1_l = LBOUND(SrcParamData%PhiL_T,1) - i1_u = UBOUND(SrcParamData%PhiL_T,1) - i2_l = LBOUND(SrcParamData%PhiL_T,2) - i2_u = UBOUND(SrcParamData%PhiL_T,2) - IF (.NOT. ALLOCATED(DstParamData%PhiL_T)) THEN - ALLOCATE(DstParamData%PhiL_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiL_T.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%PhiL_T = SrcParamData%PhiL_T -ENDIF -IF (ALLOCATED(SrcParamData%PhiLInvOmgL2)) THEN - i1_l = LBOUND(SrcParamData%PhiLInvOmgL2,1) - i1_u = UBOUND(SrcParamData%PhiLInvOmgL2,1) - i2_l = LBOUND(SrcParamData%PhiLInvOmgL2,2) - i2_u = UBOUND(SrcParamData%PhiLInvOmgL2,2) - IF (.NOT. ALLOCATED(DstParamData%PhiLInvOmgL2)) THEN - ALLOCATE(DstParamData%PhiLInvOmgL2(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiLInvOmgL2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%PhiLInvOmgL2 = SrcParamData%PhiLInvOmgL2 -ENDIF -IF (ALLOCATED(SrcParamData%KLLm1)) THEN - i1_l = LBOUND(SrcParamData%KLLm1,1) - i1_u = UBOUND(SrcParamData%KLLm1,1) - i2_l = LBOUND(SrcParamData%KLLm1,2) - i2_u = UBOUND(SrcParamData%KLLm1,2) - IF (.NOT. ALLOCATED(DstParamData%KLLm1)) THEN - ALLOCATE(DstParamData%KLLm1(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KLLm1.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%KLLm1 = SrcParamData%KLLm1 -ENDIF -IF (ALLOCATED(SrcParamData%AM2Jac)) THEN - i1_l = LBOUND(SrcParamData%AM2Jac,1) - i1_u = UBOUND(SrcParamData%AM2Jac,1) - i2_l = LBOUND(SrcParamData%AM2Jac,2) - i2_u = UBOUND(SrcParamData%AM2Jac,2) - IF (.NOT. ALLOCATED(DstParamData%AM2Jac)) THEN - ALLOCATE(DstParamData%AM2Jac(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%AM2Jac.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%AM2Jac = SrcParamData%AM2Jac -ENDIF -IF (ALLOCATED(SrcParamData%AM2JacPiv)) THEN - i1_l = LBOUND(SrcParamData%AM2JacPiv,1) - i1_u = UBOUND(SrcParamData%AM2JacPiv,1) - IF (.NOT. ALLOCATED(DstParamData%AM2JacPiv)) THEN - ALLOCATE(DstParamData%AM2JacPiv(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%AM2JacPiv.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%AM2JacPiv = SrcParamData%AM2JacPiv -ENDIF -IF (ALLOCATED(SrcParamData%TI)) THEN - i1_l = LBOUND(SrcParamData%TI,1) - i1_u = UBOUND(SrcParamData%TI,1) - i2_l = LBOUND(SrcParamData%TI,2) - i2_u = UBOUND(SrcParamData%TI,2) - IF (.NOT. ALLOCATED(DstParamData%TI)) THEN - ALLOCATE(DstParamData%TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%TI.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%TI = SrcParamData%TI -ENDIF -IF (ALLOCATED(SrcParamData%TIreact)) THEN - i1_l = LBOUND(SrcParamData%TIreact,1) - i1_u = UBOUND(SrcParamData%TIreact,1) - i2_l = LBOUND(SrcParamData%TIreact,2) - i2_u = UBOUND(SrcParamData%TIreact,2) - IF (.NOT. ALLOCATED(DstParamData%TIreact)) THEN - ALLOCATE(DstParamData%TIreact(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%TIreact.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%TIreact = SrcParamData%TIreact -ENDIF - DstParamData%nNodes = SrcParamData%nNodes - DstParamData%nNodes_I = SrcParamData%nNodes_I - DstParamData%nNodes_L = SrcParamData%nNodes_L - DstParamData%nNodes_C = SrcParamData%nNodes_C -IF (ALLOCATED(SrcParamData%Nodes_I)) THEN - i1_l = LBOUND(SrcParamData%Nodes_I,1) - i1_u = UBOUND(SrcParamData%Nodes_I,1) - i2_l = LBOUND(SrcParamData%Nodes_I,2) - i2_u = UBOUND(SrcParamData%Nodes_I,2) - IF (.NOT. ALLOCATED(DstParamData%Nodes_I)) THEN - ALLOCATE(DstParamData%Nodes_I(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_I.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%Nodes_I = SrcParamData%Nodes_I -ENDIF -IF (ALLOCATED(SrcParamData%Nodes_L)) THEN - i1_l = LBOUND(SrcParamData%Nodes_L,1) - i1_u = UBOUND(SrcParamData%Nodes_L,1) - i2_l = LBOUND(SrcParamData%Nodes_L,2) - i2_u = UBOUND(SrcParamData%Nodes_L,2) - IF (.NOT. ALLOCATED(DstParamData%Nodes_L)) THEN - ALLOCATE(DstParamData%Nodes_L(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%Nodes_L = SrcParamData%Nodes_L -ENDIF -IF (ALLOCATED(SrcParamData%Nodes_C)) THEN - i1_l = LBOUND(SrcParamData%Nodes_C,1) - i1_u = UBOUND(SrcParamData%Nodes_C,1) - i2_l = LBOUND(SrcParamData%Nodes_C,2) - i2_u = UBOUND(SrcParamData%Nodes_C,2) - IF (.NOT. ALLOCATED(DstParamData%Nodes_C)) THEN - ALLOCATE(DstParamData%Nodes_C(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_C.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%Nodes_C = SrcParamData%Nodes_C -ENDIF - DstParamData%nDOFI__ = SrcParamData%nDOFI__ - DstParamData%nDOFI_Rb = SrcParamData%nDOFI_Rb - DstParamData%nDOFI_F = SrcParamData%nDOFI_F - DstParamData%nDOFL_L = SrcParamData%nDOFL_L - DstParamData%nDOFC__ = SrcParamData%nDOFC__ - DstParamData%nDOFC_Rb = SrcParamData%nDOFC_Rb - DstParamData%nDOFC_L = SrcParamData%nDOFC_L - DstParamData%nDOFC_F = SrcParamData%nDOFC_F - DstParamData%nDOFR__ = SrcParamData%nDOFR__ - DstParamData%nDOF__Rb = SrcParamData%nDOF__Rb - DstParamData%nDOF__L = SrcParamData%nDOF__L - DstParamData%nDOF__F = SrcParamData%nDOF__F -IF (ALLOCATED(SrcParamData%IDI__)) THEN - i1_l = LBOUND(SrcParamData%IDI__,1) - i1_u = UBOUND(SrcParamData%IDI__,1) - IF (.NOT. ALLOCATED(DstParamData%IDI__)) THEN - ALLOCATE(DstParamData%IDI__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDI__ = SrcParamData%IDI__ -ENDIF -IF (ALLOCATED(SrcParamData%IDI_Rb)) THEN - i1_l = LBOUND(SrcParamData%IDI_Rb,1) - i1_u = UBOUND(SrcParamData%IDI_Rb,1) - IF (.NOT. ALLOCATED(DstParamData%IDI_Rb)) THEN - ALLOCATE(DstParamData%IDI_Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI_Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDI_Rb = SrcParamData%IDI_Rb -ENDIF -IF (ALLOCATED(SrcParamData%IDI_F)) THEN - i1_l = LBOUND(SrcParamData%IDI_F,1) - i1_u = UBOUND(SrcParamData%IDI_F,1) - IF (.NOT. ALLOCATED(DstParamData%IDI_F)) THEN - ALLOCATE(DstParamData%IDI_F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI_F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDI_F = SrcParamData%IDI_F -ENDIF -IF (ALLOCATED(SrcParamData%IDL_L)) THEN - i1_l = LBOUND(SrcParamData%IDL_L,1) - i1_u = UBOUND(SrcParamData%IDL_L,1) - IF (.NOT. ALLOCATED(DstParamData%IDL_L)) THEN - ALLOCATE(DstParamData%IDL_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDL_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDL_L = SrcParamData%IDL_L -ENDIF -IF (ALLOCATED(SrcParamData%IDC__)) THEN - i1_l = LBOUND(SrcParamData%IDC__,1) - i1_u = UBOUND(SrcParamData%IDC__,1) - IF (.NOT. ALLOCATED(DstParamData%IDC__)) THEN - ALLOCATE(DstParamData%IDC__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDC__ = SrcParamData%IDC__ -ENDIF -IF (ALLOCATED(SrcParamData%IDC_Rb)) THEN - i1_l = LBOUND(SrcParamData%IDC_Rb,1) - i1_u = UBOUND(SrcParamData%IDC_Rb,1) - IF (.NOT. ALLOCATED(DstParamData%IDC_Rb)) THEN - ALLOCATE(DstParamData%IDC_Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDC_Rb = SrcParamData%IDC_Rb -ENDIF -IF (ALLOCATED(SrcParamData%IDC_L)) THEN - i1_l = LBOUND(SrcParamData%IDC_L,1) - i1_u = UBOUND(SrcParamData%IDC_L,1) - IF (.NOT. ALLOCATED(DstParamData%IDC_L)) THEN - ALLOCATE(DstParamData%IDC_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDC_L = SrcParamData%IDC_L -ENDIF -IF (ALLOCATED(SrcParamData%IDC_F)) THEN - i1_l = LBOUND(SrcParamData%IDC_F,1) - i1_u = UBOUND(SrcParamData%IDC_F,1) - IF (.NOT. ALLOCATED(DstParamData%IDC_F)) THEN - ALLOCATE(DstParamData%IDC_F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDC_F = SrcParamData%IDC_F -ENDIF -IF (ALLOCATED(SrcParamData%IDR__)) THEN - i1_l = LBOUND(SrcParamData%IDR__,1) - i1_u = UBOUND(SrcParamData%IDR__,1) - IF (.NOT. ALLOCATED(DstParamData%IDR__)) THEN - ALLOCATE(DstParamData%IDR__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDR__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%IDR__ = SrcParamData%IDR__ -ENDIF -IF (ALLOCATED(SrcParamData%ID__Rb)) THEN - i1_l = LBOUND(SrcParamData%ID__Rb,1) - i1_u = UBOUND(SrcParamData%ID__Rb,1) - IF (.NOT. ALLOCATED(DstParamData%ID__Rb)) THEN - ALLOCATE(DstParamData%ID__Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%ID__Rb = SrcParamData%ID__Rb -ENDIF -IF (ALLOCATED(SrcParamData%ID__L)) THEN - i1_l = LBOUND(SrcParamData%ID__L,1) - i1_u = UBOUND(SrcParamData%ID__L,1) - IF (.NOT. ALLOCATED(DstParamData%ID__L)) THEN - ALLOCATE(DstParamData%ID__L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%ID__L = SrcParamData%ID__L -ENDIF -IF (ALLOCATED(SrcParamData%ID__F)) THEN - i1_l = LBOUND(SrcParamData%ID__F,1) - i1_u = UBOUND(SrcParamData%ID__F,1) - IF (.NOT. ALLOCATED(DstParamData%ID__F)) THEN - ALLOCATE(DstParamData%ID__F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%ID__F = SrcParamData%ID__F -ENDIF - DstParamData%NMOutputs = SrcParamData%NMOutputs - DstParamData%NumOuts = SrcParamData%NumOuts - DstParamData%OutSwtch = SrcParamData%OutSwtch - DstParamData%UnJckF = SrcParamData%UnJckF - DstParamData%Delim = SrcParamData%Delim - DstParamData%OutFmt = SrcParamData%OutFmt - DstParamData%OutSFmt = SrcParamData%OutSFmt -IF (ALLOCATED(SrcParamData%MoutLst)) THEN - i1_l = LBOUND(SrcParamData%MoutLst,1) - i1_u = UBOUND(SrcParamData%MoutLst,1) - IF (.NOT. ALLOCATED(DstParamData%MoutLst)) THEN - ALLOCATE(DstParamData%MoutLst(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%MoutLst,1), UBOUND(SrcParamData%MoutLst,1) - CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst(i1), DstParamData%MoutLst(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%MoutLst2)) THEN - i1_l = LBOUND(SrcParamData%MoutLst2,1) - i1_u = UBOUND(SrcParamData%MoutLst2,1) - IF (.NOT. ALLOCATED(DstParamData%MoutLst2)) THEN - ALLOCATE(DstParamData%MoutLst2(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%MoutLst2,1), UBOUND(SrcParamData%MoutLst2,1) - CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst2(i1), DstParamData%MoutLst2(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%MoutLst3)) THEN - i1_l = LBOUND(SrcParamData%MoutLst3,1) - i1_u = UBOUND(SrcParamData%MoutLst3,1) - IF (.NOT. ALLOCATED(DstParamData%MoutLst3)) THEN - ALLOCATE(DstParamData%MoutLst3(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst3.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%MoutLst3,1), UBOUND(SrcParamData%MoutLst3,1) - CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst3(i1), DstParamData%MoutLst3(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF -IF (ALLOCATED(SrcParamData%OutParam)) THEN - i1_l = LBOUND(SrcParamData%OutParam,1) - i1_u = UBOUND(SrcParamData%OutParam,1) - IF (.NOT. ALLOCATED(DstParamData%OutParam)) THEN - ALLOCATE(DstParamData%OutParam(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%OutParam.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DO i1 = LBOUND(SrcParamData%OutParam,1), UBOUND(SrcParamData%OutParam,1) - CALL NWTC_Library_Copyoutparmtype( SrcParamData%OutParam(i1), DstParamData%OutParam(i1), CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - ENDDO -ENDIF - DstParamData%OutAll = SrcParamData%OutAll - DstParamData%OutCBModes = SrcParamData%OutCBModes - DstParamData%OutFEMModes = SrcParamData%OutFEMModes - DstParamData%OutReact = SrcParamData%OutReact - DstParamData%OutAllInt = SrcParamData%OutAllInt - DstParamData%OutAllDims = SrcParamData%OutAllDims - DstParamData%OutDec = SrcParamData%OutDec -IF (ALLOCATED(SrcParamData%Jac_u_indx)) THEN - i1_l = LBOUND(SrcParamData%Jac_u_indx,1) - i1_u = UBOUND(SrcParamData%Jac_u_indx,1) - i2_l = LBOUND(SrcParamData%Jac_u_indx,2) - i2_u = UBOUND(SrcParamData%Jac_u_indx,2) - IF (.NOT. ALLOCATED(DstParamData%Jac_u_indx)) THEN - ALLOCATE(DstParamData%Jac_u_indx(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Jac_u_indx.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%Jac_u_indx = SrcParamData%Jac_u_indx -ENDIF -IF (ALLOCATED(SrcParamData%du)) THEN - i1_l = LBOUND(SrcParamData%du,1) - i1_u = UBOUND(SrcParamData%du,1) - IF (.NOT. ALLOCATED(DstParamData%du)) THEN - ALLOCATE(DstParamData%du(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%du.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstParamData%du = SrcParamData%du -ENDIF - DstParamData%dx = SrcParamData%dx - DstParamData%Jac_ny = SrcParamData%Jac_ny - DstParamData%Jac_nx = SrcParamData%Jac_nx - DstParamData%RotStates = SrcParamData%RotStates - END SUBROUTINE SD_CopyParam - - SUBROUTINE SD_DestroyParam( ParamData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_ParameterType), INTENT(INOUT) :: ParamData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyParam' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - -IF (ALLOCATED(ParamData%Elems)) THEN - DEALLOCATE(ParamData%Elems) -ENDIF -IF (ALLOCATED(ParamData%ElemProps)) THEN -DO i1 = LBOUND(ParamData%ElemProps,1), UBOUND(ParamData%ElemProps,1) - CALL SD_Destroyelemproptype( ParamData%ElemProps(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%ElemProps) -ENDIF -IF (ALLOCATED(ParamData%FG)) THEN - DEALLOCATE(ParamData%FG) -ENDIF -IF (ALLOCATED(ParamData%DP0)) THEN - DEALLOCATE(ParamData%DP0) -ENDIF -IF (ALLOCATED(ParamData%NodeID2JointID)) THEN - DEALLOCATE(ParamData%NodeID2JointID) -ENDIF -IF (ALLOCATED(ParamData%T_red)) THEN - DEALLOCATE(ParamData%T_red) -ENDIF -IF (ALLOCATED(ParamData%T_red_T)) THEN - DEALLOCATE(ParamData%T_red_T) -ENDIF -IF (ALLOCATED(ParamData%NodesDOF)) THEN -DO i1 = LBOUND(ParamData%NodesDOF,1), UBOUND(ParamData%NodesDOF,1) - CALL SD_Destroyilist( ParamData%NodesDOF(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%NodesDOF) -ENDIF -IF (ALLOCATED(ParamData%NodesDOFred)) THEN -DO i1 = LBOUND(ParamData%NodesDOFred,1), UBOUND(ParamData%NodesDOFred,1) - CALL SD_Destroyilist( ParamData%NodesDOFred(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%NodesDOFred) -ENDIF -IF (ALLOCATED(ParamData%ElemsDOF)) THEN - DEALLOCATE(ParamData%ElemsDOF) -ENDIF -IF (ALLOCATED(ParamData%DOFred2Nodes)) THEN - DEALLOCATE(ParamData%DOFred2Nodes) -ENDIF -IF (ALLOCATED(ParamData%CtrlElem2Channel)) THEN - DEALLOCATE(ParamData%CtrlElem2Channel) -ENDIF -IF (ALLOCATED(ParamData%KMMDiag)) THEN - DEALLOCATE(ParamData%KMMDiag) -ENDIF -IF (ALLOCATED(ParamData%CMMDiag)) THEN - DEALLOCATE(ParamData%CMMDiag) -ENDIF -IF (ALLOCATED(ParamData%MMB)) THEN - DEALLOCATE(ParamData%MMB) -ENDIF -IF (ALLOCATED(ParamData%MBmmB)) THEN - DEALLOCATE(ParamData%MBmmB) -ENDIF -IF (ALLOCATED(ParamData%C1_11)) THEN - DEALLOCATE(ParamData%C1_11) -ENDIF -IF (ALLOCATED(ParamData%C1_12)) THEN - DEALLOCATE(ParamData%C1_12) -ENDIF -IF (ALLOCATED(ParamData%D1_141)) THEN - DEALLOCATE(ParamData%D1_141) -ENDIF -IF (ALLOCATED(ParamData%D1_142)) THEN - DEALLOCATE(ParamData%D1_142) -ENDIF -IF (ALLOCATED(ParamData%PhiM)) THEN - DEALLOCATE(ParamData%PhiM) -ENDIF -IF (ALLOCATED(ParamData%C2_61)) THEN - DEALLOCATE(ParamData%C2_61) -ENDIF -IF (ALLOCATED(ParamData%C2_62)) THEN - DEALLOCATE(ParamData%C2_62) -ENDIF -IF (ALLOCATED(ParamData%PhiRb_TI)) THEN - DEALLOCATE(ParamData%PhiRb_TI) -ENDIF -IF (ALLOCATED(ParamData%D2_63)) THEN - DEALLOCATE(ParamData%D2_63) -ENDIF -IF (ALLOCATED(ParamData%D2_64)) THEN - DEALLOCATE(ParamData%D2_64) -ENDIF -IF (ALLOCATED(ParamData%MBB)) THEN - DEALLOCATE(ParamData%MBB) -ENDIF -IF (ALLOCATED(ParamData%KBB)) THEN - DEALLOCATE(ParamData%KBB) -ENDIF -IF (ALLOCATED(ParamData%CBB)) THEN - DEALLOCATE(ParamData%CBB) -ENDIF -IF (ALLOCATED(ParamData%CMM)) THEN - DEALLOCATE(ParamData%CMM) -ENDIF -IF (ALLOCATED(ParamData%MBM)) THEN - DEALLOCATE(ParamData%MBM) -ENDIF -IF (ALLOCATED(ParamData%PhiL_T)) THEN - DEALLOCATE(ParamData%PhiL_T) -ENDIF -IF (ALLOCATED(ParamData%PhiLInvOmgL2)) THEN - DEALLOCATE(ParamData%PhiLInvOmgL2) -ENDIF -IF (ALLOCATED(ParamData%KLLm1)) THEN - DEALLOCATE(ParamData%KLLm1) -ENDIF -IF (ALLOCATED(ParamData%AM2Jac)) THEN - DEALLOCATE(ParamData%AM2Jac) -ENDIF -IF (ALLOCATED(ParamData%AM2JacPiv)) THEN - DEALLOCATE(ParamData%AM2JacPiv) -ENDIF -IF (ALLOCATED(ParamData%TI)) THEN - DEALLOCATE(ParamData%TI) -ENDIF -IF (ALLOCATED(ParamData%TIreact)) THEN - DEALLOCATE(ParamData%TIreact) -ENDIF -IF (ALLOCATED(ParamData%Nodes_I)) THEN - DEALLOCATE(ParamData%Nodes_I) -ENDIF -IF (ALLOCATED(ParamData%Nodes_L)) THEN - DEALLOCATE(ParamData%Nodes_L) -ENDIF -IF (ALLOCATED(ParamData%Nodes_C)) THEN - DEALLOCATE(ParamData%Nodes_C) -ENDIF -IF (ALLOCATED(ParamData%IDI__)) THEN - DEALLOCATE(ParamData%IDI__) -ENDIF -IF (ALLOCATED(ParamData%IDI_Rb)) THEN - DEALLOCATE(ParamData%IDI_Rb) -ENDIF -IF (ALLOCATED(ParamData%IDI_F)) THEN - DEALLOCATE(ParamData%IDI_F) -ENDIF -IF (ALLOCATED(ParamData%IDL_L)) THEN - DEALLOCATE(ParamData%IDL_L) -ENDIF -IF (ALLOCATED(ParamData%IDC__)) THEN - DEALLOCATE(ParamData%IDC__) -ENDIF -IF (ALLOCATED(ParamData%IDC_Rb)) THEN - DEALLOCATE(ParamData%IDC_Rb) -ENDIF -IF (ALLOCATED(ParamData%IDC_L)) THEN - DEALLOCATE(ParamData%IDC_L) -ENDIF -IF (ALLOCATED(ParamData%IDC_F)) THEN - DEALLOCATE(ParamData%IDC_F) -ENDIF -IF (ALLOCATED(ParamData%IDR__)) THEN - DEALLOCATE(ParamData%IDR__) -ENDIF -IF (ALLOCATED(ParamData%ID__Rb)) THEN - DEALLOCATE(ParamData%ID__Rb) -ENDIF -IF (ALLOCATED(ParamData%ID__L)) THEN - DEALLOCATE(ParamData%ID__L) -ENDIF -IF (ALLOCATED(ParamData%ID__F)) THEN - DEALLOCATE(ParamData%ID__F) -ENDIF -IF (ALLOCATED(ParamData%MoutLst)) THEN -DO i1 = LBOUND(ParamData%MoutLst,1), UBOUND(ParamData%MoutLst,1) - CALL SD_Destroymeshauxdatatype( ParamData%MoutLst(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%MoutLst) -ENDIF -IF (ALLOCATED(ParamData%MoutLst2)) THEN -DO i1 = LBOUND(ParamData%MoutLst2,1), UBOUND(ParamData%MoutLst2,1) - CALL SD_Destroymeshauxdatatype( ParamData%MoutLst2(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%MoutLst2) -ENDIF -IF (ALLOCATED(ParamData%MoutLst3)) THEN -DO i1 = LBOUND(ParamData%MoutLst3,1), UBOUND(ParamData%MoutLst3,1) - CALL SD_Destroymeshauxdatatype( ParamData%MoutLst3(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%MoutLst3) -ENDIF -IF (ALLOCATED(ParamData%OutParam)) THEN -DO i1 = LBOUND(ParamData%OutParam,1), UBOUND(ParamData%OutParam,1) - CALL NWTC_Library_Destroyoutparmtype( ParamData%OutParam(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -ENDDO - DEALLOCATE(ParamData%OutParam) -ENDIF -IF (ALLOCATED(ParamData%Jac_u_indx)) THEN - DEALLOCATE(ParamData%Jac_u_indx) -ENDIF -IF (ALLOCATED(ParamData%du)) THEN - DEALLOCATE(ParamData%du) -ENDIF - END SUBROUTINE SD_DestroyParam - - SUBROUTINE SD_PackParam( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_ParameterType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackParam' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - Db_BufSz = Db_BufSz + 1 ! SDDeltaT - Int_BufSz = Int_BufSz + 1 ! IntMethod - Int_BufSz = Int_BufSz + 1 ! nDOF - Int_BufSz = Int_BufSz + 1 ! nDOF_red - Int_BufSz = Int_BufSz + 1 ! Nmembers - Int_BufSz = Int_BufSz + 1 ! Elems allocated yes/no - IF ( ALLOCATED(InData%Elems) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Elems upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Elems) ! Elems - END IF - Int_BufSz = Int_BufSz + 1 ! ElemProps allocated yes/no - IF ( ALLOCATED(InData%ElemProps) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! ElemProps upper/lower bounds for each dimension - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) - Int_BufSz = Int_BufSz + 3 ! ElemProps: size of buffers for each call to pack subtype - CALL SD_Packelemproptype( Re_Buf, Db_Buf, Int_Buf, InData%ElemProps(i1), ErrStat2, ErrMsg2, .TRUE. ) ! ElemProps - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! ElemProps - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! ElemProps - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! ElemProps - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! FG allocated yes/no - IF ( ALLOCATED(InData%FG) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! FG upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%FG) ! FG - END IF - Int_BufSz = Int_BufSz + 1 ! DP0 allocated yes/no - IF ( ALLOCATED(InData%DP0) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! DP0 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%DP0) ! DP0 - END IF - Int_BufSz = Int_BufSz + 1 ! NodeID2JointID allocated yes/no - IF ( ALLOCATED(InData%NodeID2JointID) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! NodeID2JointID upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%NodeID2JointID) ! NodeID2JointID - END IF - Int_BufSz = Int_BufSz + 1 ! reduced - Int_BufSz = Int_BufSz + 1 ! T_red allocated yes/no - IF ( ALLOCATED(InData%T_red) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! T_red upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%T_red) ! T_red - END IF - Int_BufSz = Int_BufSz + 1 ! T_red_T allocated yes/no - IF ( ALLOCATED(InData%T_red_T) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! T_red_T upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%T_red_T) ! T_red_T - END IF - Int_BufSz = Int_BufSz + 1 ! NodesDOF allocated yes/no - IF ( ALLOCATED(InData%NodesDOF) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! NodesDOF upper/lower bounds for each dimension - DO i1 = LBOUND(InData%NodesDOF,1), UBOUND(InData%NodesDOF,1) - Int_BufSz = Int_BufSz + 3 ! NodesDOF: size of buffers for each call to pack subtype - CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOF(i1), ErrStat2, ErrMsg2, .TRUE. ) ! NodesDOF - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! NodesDOF - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! NodesDOF - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! NodesDOF - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! NodesDOFred allocated yes/no - IF ( ALLOCATED(InData%NodesDOFred) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! NodesDOFred upper/lower bounds for each dimension - DO i1 = LBOUND(InData%NodesDOFred,1), UBOUND(InData%NodesDOFred,1) - Int_BufSz = Int_BufSz + 3 ! NodesDOFred: size of buffers for each call to pack subtype - CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOFred(i1), ErrStat2, ErrMsg2, .TRUE. ) ! NodesDOFred - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! NodesDOFred - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! NodesDOFred - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! NodesDOFred - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! ElemsDOF allocated yes/no - IF ( ALLOCATED(InData%ElemsDOF) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! ElemsDOF upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ElemsDOF) ! ElemsDOF - END IF - Int_BufSz = Int_BufSz + 1 ! DOFred2Nodes allocated yes/no - IF ( ALLOCATED(InData%DOFred2Nodes) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! DOFred2Nodes upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%DOFred2Nodes) ! DOFred2Nodes - END IF - Int_BufSz = Int_BufSz + 1 ! CtrlElem2Channel allocated yes/no - IF ( ALLOCATED(InData%CtrlElem2Channel) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! CtrlElem2Channel upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%CtrlElem2Channel) ! CtrlElem2Channel - END IF - Int_BufSz = Int_BufSz + 1 ! nDOFM - Int_BufSz = Int_BufSz + 1 ! SttcSolve - Int_BufSz = Int_BufSz + 1 ! GuyanLoadCorrection - Int_BufSz = Int_BufSz + 1 ! Floating - Int_BufSz = Int_BufSz + 1 ! KMMDiag allocated yes/no - IF ( ALLOCATED(InData%KMMDiag) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! KMMDiag upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%KMMDiag) ! KMMDiag - END IF - Int_BufSz = Int_BufSz + 1 ! CMMDiag allocated yes/no - IF ( ALLOCATED(InData%CMMDiag) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! CMMDiag upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%CMMDiag) ! CMMDiag - END IF - Int_BufSz = Int_BufSz + 1 ! MMB allocated yes/no - IF ( ALLOCATED(InData%MMB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MMB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%MMB) ! MMB - END IF - Int_BufSz = Int_BufSz + 1 ! MBmmB allocated yes/no - IF ( ALLOCATED(InData%MBmmB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MBmmB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%MBmmB) ! MBmmB - END IF - Int_BufSz = Int_BufSz + 1 ! C1_11 allocated yes/no - IF ( ALLOCATED(InData%C1_11) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! C1_11 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%C1_11) ! C1_11 - END IF - Int_BufSz = Int_BufSz + 1 ! C1_12 allocated yes/no - IF ( ALLOCATED(InData%C1_12) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! C1_12 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%C1_12) ! C1_12 - END IF - Int_BufSz = Int_BufSz + 1 ! D1_141 allocated yes/no - IF ( ALLOCATED(InData%D1_141) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! D1_141 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%D1_141) ! D1_141 - END IF - Int_BufSz = Int_BufSz + 1 ! D1_142 allocated yes/no - IF ( ALLOCATED(InData%D1_142) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! D1_142 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%D1_142) ! D1_142 - END IF - Int_BufSz = Int_BufSz + 1 ! PhiM allocated yes/no - IF ( ALLOCATED(InData%PhiM) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiM upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PhiM) ! PhiM - END IF - Int_BufSz = Int_BufSz + 1 ! C2_61 allocated yes/no - IF ( ALLOCATED(InData%C2_61) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! C2_61 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%C2_61) ! C2_61 - END IF - Int_BufSz = Int_BufSz + 1 ! C2_62 allocated yes/no - IF ( ALLOCATED(InData%C2_62) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! C2_62 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%C2_62) ! C2_62 - END IF - Int_BufSz = Int_BufSz + 1 ! PhiRb_TI allocated yes/no - IF ( ALLOCATED(InData%PhiRb_TI) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiRb_TI upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PhiRb_TI) ! PhiRb_TI - END IF - Int_BufSz = Int_BufSz + 1 ! D2_63 allocated yes/no - IF ( ALLOCATED(InData%D2_63) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! D2_63 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%D2_63) ! D2_63 - END IF - Int_BufSz = Int_BufSz + 1 ! D2_64 allocated yes/no - IF ( ALLOCATED(InData%D2_64) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! D2_64 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%D2_64) ! D2_64 - END IF - Int_BufSz = Int_BufSz + 1 ! MBB allocated yes/no - IF ( ALLOCATED(InData%MBB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MBB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%MBB) ! MBB - END IF - Int_BufSz = Int_BufSz + 1 ! KBB allocated yes/no - IF ( ALLOCATED(InData%KBB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! KBB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%KBB) ! KBB - END IF - Int_BufSz = Int_BufSz + 1 ! CBB allocated yes/no - IF ( ALLOCATED(InData%CBB) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! CBB upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%CBB) ! CBB - END IF - Int_BufSz = Int_BufSz + 1 ! CMM allocated yes/no - IF ( ALLOCATED(InData%CMM) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! CMM upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%CMM) ! CMM - END IF - Int_BufSz = Int_BufSz + 1 ! MBM allocated yes/no - IF ( ALLOCATED(InData%MBM) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! MBM upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%MBM) ! MBM - END IF - Int_BufSz = Int_BufSz + 1 ! PhiL_T allocated yes/no - IF ( ALLOCATED(InData%PhiL_T) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiL_T upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PhiL_T) ! PhiL_T - END IF - Int_BufSz = Int_BufSz + 1 ! PhiLInvOmgL2 allocated yes/no - IF ( ALLOCATED(InData%PhiLInvOmgL2) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! PhiLInvOmgL2 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%PhiLInvOmgL2) ! PhiLInvOmgL2 - END IF - Int_BufSz = Int_BufSz + 1 ! KLLm1 allocated yes/no - IF ( ALLOCATED(InData%KLLm1) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! KLLm1 upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%KLLm1) ! KLLm1 - END IF - Int_BufSz = Int_BufSz + 1 ! AM2Jac allocated yes/no - IF ( ALLOCATED(InData%AM2Jac) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! AM2Jac upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%AM2Jac) ! AM2Jac - END IF - Int_BufSz = Int_BufSz + 1 ! AM2JacPiv allocated yes/no - IF ( ALLOCATED(InData%AM2JacPiv) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! AM2JacPiv upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%AM2JacPiv) ! AM2JacPiv - END IF - Int_BufSz = Int_BufSz + 1 ! TI allocated yes/no - IF ( ALLOCATED(InData%TI) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! TI upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%TI) ! TI - END IF - Int_BufSz = Int_BufSz + 1 ! TIreact allocated yes/no - IF ( ALLOCATED(InData%TIreact) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! TIreact upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%TIreact) ! TIreact - END IF - Int_BufSz = Int_BufSz + 1 ! nNodes - Int_BufSz = Int_BufSz + 1 ! nNodes_I - Int_BufSz = Int_BufSz + 1 ! nNodes_L - Int_BufSz = Int_BufSz + 1 ! nNodes_C - Int_BufSz = Int_BufSz + 1 ! Nodes_I allocated yes/no - IF ( ALLOCATED(InData%Nodes_I) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Nodes_I upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Nodes_I) ! Nodes_I - END IF - Int_BufSz = Int_BufSz + 1 ! Nodes_L allocated yes/no - IF ( ALLOCATED(InData%Nodes_L) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Nodes_L upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Nodes_L) ! Nodes_L - END IF - Int_BufSz = Int_BufSz + 1 ! Nodes_C allocated yes/no - IF ( ALLOCATED(InData%Nodes_C) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Nodes_C upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Nodes_C) ! Nodes_C - END IF - Int_BufSz = Int_BufSz + 1 ! nDOFI__ - Int_BufSz = Int_BufSz + 1 ! nDOFI_Rb - Int_BufSz = Int_BufSz + 1 ! nDOFI_F - Int_BufSz = Int_BufSz + 1 ! nDOFL_L - Int_BufSz = Int_BufSz + 1 ! nDOFC__ - Int_BufSz = Int_BufSz + 1 ! nDOFC_Rb - Int_BufSz = Int_BufSz + 1 ! nDOFC_L - Int_BufSz = Int_BufSz + 1 ! nDOFC_F - Int_BufSz = Int_BufSz + 1 ! nDOFR__ - Int_BufSz = Int_BufSz + 1 ! nDOF__Rb - Int_BufSz = Int_BufSz + 1 ! nDOF__L - Int_BufSz = Int_BufSz + 1 ! nDOF__F - Int_BufSz = Int_BufSz + 1 ! IDI__ allocated yes/no - IF ( ALLOCATED(InData%IDI__) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDI__ upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDI__) ! IDI__ - END IF - Int_BufSz = Int_BufSz + 1 ! IDI_Rb allocated yes/no - IF ( ALLOCATED(InData%IDI_Rb) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDI_Rb upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDI_Rb) ! IDI_Rb - END IF - Int_BufSz = Int_BufSz + 1 ! IDI_F allocated yes/no - IF ( ALLOCATED(InData%IDI_F) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDI_F upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDI_F) ! IDI_F - END IF - Int_BufSz = Int_BufSz + 1 ! IDL_L allocated yes/no - IF ( ALLOCATED(InData%IDL_L) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDL_L upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDL_L) ! IDL_L - END IF - Int_BufSz = Int_BufSz + 1 ! IDC__ allocated yes/no - IF ( ALLOCATED(InData%IDC__) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDC__ upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDC__) ! IDC__ - END IF - Int_BufSz = Int_BufSz + 1 ! IDC_Rb allocated yes/no - IF ( ALLOCATED(InData%IDC_Rb) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDC_Rb upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDC_Rb) ! IDC_Rb - END IF - Int_BufSz = Int_BufSz + 1 ! IDC_L allocated yes/no - IF ( ALLOCATED(InData%IDC_L) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDC_L upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDC_L) ! IDC_L - END IF - Int_BufSz = Int_BufSz + 1 ! IDC_F allocated yes/no - IF ( ALLOCATED(InData%IDC_F) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDC_F upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDC_F) ! IDC_F - END IF - Int_BufSz = Int_BufSz + 1 ! IDR__ allocated yes/no - IF ( ALLOCATED(InData%IDR__) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! IDR__ upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%IDR__) ! IDR__ - END IF - Int_BufSz = Int_BufSz + 1 ! ID__Rb allocated yes/no - IF ( ALLOCATED(InData%ID__Rb) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! ID__Rb upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ID__Rb) ! ID__Rb - END IF - Int_BufSz = Int_BufSz + 1 ! ID__L allocated yes/no - IF ( ALLOCATED(InData%ID__L) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! ID__L upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ID__L) ! ID__L - END IF - Int_BufSz = Int_BufSz + 1 ! ID__F allocated yes/no - IF ( ALLOCATED(InData%ID__F) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! ID__F upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%ID__F) ! ID__F - END IF - Int_BufSz = Int_BufSz + 1 ! NMOutputs - Int_BufSz = Int_BufSz + 1 ! NumOuts - Int_BufSz = Int_BufSz + 1 ! OutSwtch - Int_BufSz = Int_BufSz + 1 ! UnJckF - Int_BufSz = Int_BufSz + 1*LEN(InData%Delim) ! Delim - Int_BufSz = Int_BufSz + 1*LEN(InData%OutFmt) ! OutFmt - Int_BufSz = Int_BufSz + 1*LEN(InData%OutSFmt) ! OutSFmt - Int_BufSz = Int_BufSz + 1 ! MoutLst allocated yes/no - IF ( ALLOCATED(InData%MoutLst) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! MoutLst upper/lower bounds for each dimension - DO i1 = LBOUND(InData%MoutLst,1), UBOUND(InData%MoutLst,1) - Int_BufSz = Int_BufSz + 3 ! MoutLst: size of buffers for each call to pack subtype - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! MoutLst - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! MoutLst - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! MoutLst - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! MoutLst2 allocated yes/no - IF ( ALLOCATED(InData%MoutLst2) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! MoutLst2 upper/lower bounds for each dimension - DO i1 = LBOUND(InData%MoutLst2,1), UBOUND(InData%MoutLst2,1) - Int_BufSz = Int_BufSz + 3 ! MoutLst2: size of buffers for each call to pack subtype - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst2(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst2 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! MoutLst2 - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! MoutLst2 - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! MoutLst2 - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! MoutLst3 allocated yes/no - IF ( ALLOCATED(InData%MoutLst3) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! MoutLst3 upper/lower bounds for each dimension - DO i1 = LBOUND(InData%MoutLst3,1), UBOUND(InData%MoutLst3,1) - Int_BufSz = Int_BufSz + 3 ! MoutLst3: size of buffers for each call to pack subtype - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst3(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst3 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! MoutLst3 - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! MoutLst3 - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! MoutLst3 - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! OutParam allocated yes/no - IF ( ALLOCATED(InData%OutParam) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! OutParam upper/lower bounds for each dimension - DO i1 = LBOUND(InData%OutParam,1), UBOUND(InData%OutParam,1) - Int_BufSz = Int_BufSz + 3 ! OutParam: size of buffers for each call to pack subtype - CALL NWTC_Library_Packoutparmtype( Re_Buf, Db_Buf, Int_Buf, InData%OutParam(i1), ErrStat2, ErrMsg2, .TRUE. ) ! OutParam - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! OutParam - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! OutParam - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! OutParam - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - END DO - END IF - Int_BufSz = Int_BufSz + 1 ! OutAll - Int_BufSz = Int_BufSz + 1 ! OutCBModes - Int_BufSz = Int_BufSz + 1 ! OutFEMModes - Int_BufSz = Int_BufSz + 1 ! OutReact - Int_BufSz = Int_BufSz + 1 ! OutAllInt - Int_BufSz = Int_BufSz + 1 ! OutAllDims - Int_BufSz = Int_BufSz + 1 ! OutDec - Int_BufSz = Int_BufSz + 1 ! Jac_u_indx allocated yes/no - IF ( ALLOCATED(InData%Jac_u_indx) ) THEN - Int_BufSz = Int_BufSz + 2*2 ! Jac_u_indx upper/lower bounds for each dimension - Int_BufSz = Int_BufSz + SIZE(InData%Jac_u_indx) ! Jac_u_indx - END IF - Int_BufSz = Int_BufSz + 1 ! du allocated yes/no - IF ( ALLOCATED(InData%du) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! du upper/lower bounds for each dimension - Db_BufSz = Db_BufSz + SIZE(InData%du) ! du - END IF - Db_BufSz = Db_BufSz + SIZE(InData%dx) ! dx - Int_BufSz = Int_BufSz + 1 ! Jac_ny - Int_BufSz = Int_BufSz + 1 ! Jac_nx - Int_BufSz = Int_BufSz + 1 ! RotStates - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - DbKiBuf(Db_Xferred) = InData%SDDeltaT - Db_Xferred = Db_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%IntMethod - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOF - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOF_red - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%Nmembers - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Elems) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Elems,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Elems,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Elems,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Elems,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Elems,2), UBOUND(InData%Elems,2) - DO i1 = LBOUND(InData%Elems,1), UBOUND(InData%Elems,1) - IntKiBuf(Int_Xferred) = InData%Elems(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ElemProps) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) - CALL SD_Packelemproptype( Re_Buf, Db_Buf, Int_Buf, InData%ElemProps(i1), ErrStat2, ErrMsg2, OnlySize ) ! ElemProps - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%FG) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%FG,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%FG,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%FG,1), UBOUND(InData%FG,1) - DbKiBuf(Db_Xferred) = InData%FG(i1) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%DP0) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DP0,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DP0,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DP0,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DP0,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%DP0,2), UBOUND(InData%DP0,2) - DO i1 = LBOUND(InData%DP0,1), UBOUND(InData%DP0,1) - ReKiBuf(Re_Xferred) = InData%DP0(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodeID2JointID) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeID2JointID,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeID2JointID,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%NodeID2JointID,1), UBOUND(InData%NodeID2JointID,1) - IntKiBuf(Int_Xferred) = InData%NodeID2JointID(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IntKiBuf(Int_Xferred) = TRANSFER(InData%reduced, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%T_red) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%T_red,2), UBOUND(InData%T_red,2) - DO i1 = LBOUND(InData%T_red,1), UBOUND(InData%T_red,1) - DbKiBuf(Db_Xferred) = InData%T_red(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%T_red_T) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red_T,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red_T,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red_T,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red_T,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%T_red_T,2), UBOUND(InData%T_red_T,2) - DO i1 = LBOUND(InData%T_red_T,1), UBOUND(InData%T_red_T,1) - DbKiBuf(Db_Xferred) = InData%T_red_T(i1,i2) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodesDOF) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesDOF,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesDOF,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%NodesDOF,1), UBOUND(InData%NodesDOF,1) - CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOF(i1), ErrStat2, ErrMsg2, OnlySize ) ! NodesDOF - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%NodesDOFred) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesDOFred,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesDOFred,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%NodesDOFred,1), UBOUND(InData%NodesDOFred,1) - CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOFred(i1), ErrStat2, ErrMsg2, OnlySize ) ! NodesDOFred - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ElemsDOF) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemsDOF,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemsDOF,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemsDOF,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemsDOF,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%ElemsDOF,2), UBOUND(InData%ElemsDOF,2) - DO i1 = LBOUND(InData%ElemsDOF,1), UBOUND(InData%ElemsDOF,1) - IntKiBuf(Int_Xferred) = InData%ElemsDOF(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%DOFred2Nodes) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DOFred2Nodes,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DOFred2Nodes,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%DOFred2Nodes,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DOFred2Nodes,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%DOFred2Nodes,2), UBOUND(InData%DOFred2Nodes,2) - DO i1 = LBOUND(InData%DOFred2Nodes,1), UBOUND(InData%DOFred2Nodes,1) - IntKiBuf(Int_Xferred) = InData%DOFred2Nodes(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CtrlElem2Channel) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CtrlElem2Channel,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CtrlElem2Channel,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CtrlElem2Channel,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CtrlElem2Channel,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%CtrlElem2Channel,2), UBOUND(InData%CtrlElem2Channel,2) - DO i1 = LBOUND(InData%CtrlElem2Channel,1), UBOUND(InData%CtrlElem2Channel,1) - IntKiBuf(Int_Xferred) = InData%CtrlElem2Channel(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IntKiBuf(Int_Xferred) = InData%nDOFM - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%SttcSolve - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%GuyanLoadCorrection, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%Floating, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%KMMDiag) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KMMDiag,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KMMDiag,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%KMMDiag,1), UBOUND(InData%KMMDiag,1) - ReKiBuf(Re_Xferred) = InData%KMMDiag(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CMMDiag) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CMMDiag,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMMDiag,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%CMMDiag,1), UBOUND(InData%CMMDiag,1) - ReKiBuf(Re_Xferred) = InData%CMMDiag(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MMB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MMB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MMB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MMB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MMB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MMB,2), UBOUND(InData%MMB,2) - DO i1 = LBOUND(InData%MMB,1), UBOUND(InData%MMB,1) - ReKiBuf(Re_Xferred) = InData%MMB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MBmmB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBmmB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBmmB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBmmB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBmmB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MBmmB,2), UBOUND(InData%MBmmB,2) - DO i1 = LBOUND(InData%MBmmB,1), UBOUND(InData%MBmmB,1) - ReKiBuf(Re_Xferred) = InData%MBmmB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%C1_11) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_11,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_11,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_11,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_11,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%C1_11,2), UBOUND(InData%C1_11,2) - DO i1 = LBOUND(InData%C1_11,1), UBOUND(InData%C1_11,1) - ReKiBuf(Re_Xferred) = InData%C1_11(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%C1_12) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_12,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_12,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_12,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_12,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%C1_12,2), UBOUND(InData%C1_12,2) - DO i1 = LBOUND(InData%C1_12,1), UBOUND(InData%C1_12,1) - ReKiBuf(Re_Xferred) = InData%C1_12(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%D1_141) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_141,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_141,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_141,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_141,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%D1_141,2), UBOUND(InData%D1_141,2) - DO i1 = LBOUND(InData%D1_141,1), UBOUND(InData%D1_141,1) - ReKiBuf(Re_Xferred) = InData%D1_141(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%D1_142) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_142,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_142,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_142,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_142,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%D1_142,2), UBOUND(InData%D1_142,2) - DO i1 = LBOUND(InData%D1_142,1), UBOUND(InData%D1_142,1) - ReKiBuf(Re_Xferred) = InData%D1_142(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiM,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiM,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiM,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiM,2), UBOUND(InData%PhiM,2) - DO i1 = LBOUND(InData%PhiM,1), UBOUND(InData%PhiM,1) - ReKiBuf(Re_Xferred) = InData%PhiM(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%C2_61) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_61,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_61,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_61,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_61,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%C2_61,2), UBOUND(InData%C2_61,2) - DO i1 = LBOUND(InData%C2_61,1), UBOUND(InData%C2_61,1) - ReKiBuf(Re_Xferred) = InData%C2_61(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%C2_62) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_62,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_62,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_62,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_62,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%C2_62,2), UBOUND(InData%C2_62,2) - DO i1 = LBOUND(InData%C2_62,1), UBOUND(InData%C2_62,1) - ReKiBuf(Re_Xferred) = InData%C2_62(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiRb_TI) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiRb_TI,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiRb_TI,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiRb_TI,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiRb_TI,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiRb_TI,2), UBOUND(InData%PhiRb_TI,2) - DO i1 = LBOUND(InData%PhiRb_TI,1), UBOUND(InData%PhiRb_TI,1) - ReKiBuf(Re_Xferred) = InData%PhiRb_TI(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%D2_63) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_63,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_63,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_63,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_63,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%D2_63,2), UBOUND(InData%D2_63,2) - DO i1 = LBOUND(InData%D2_63,1), UBOUND(InData%D2_63,1) - ReKiBuf(Re_Xferred) = InData%D2_63(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%D2_64) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_64,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_64,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_64,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_64,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%D2_64,2), UBOUND(InData%D2_64,2) - DO i1 = LBOUND(InData%D2_64,1), UBOUND(InData%D2_64,1) - ReKiBuf(Re_Xferred) = InData%D2_64(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MBB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MBB,2), UBOUND(InData%MBB,2) - DO i1 = LBOUND(InData%MBB,1), UBOUND(InData%MBB,1) - ReKiBuf(Re_Xferred) = InData%MBB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%KBB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%KBB,2), UBOUND(InData%KBB,2) - DO i1 = LBOUND(InData%KBB,1), UBOUND(InData%KBB,1) - ReKiBuf(Re_Xferred) = InData%KBB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CBB) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CBB,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CBB,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CBB,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CBB,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%CBB,2), UBOUND(InData%CBB,2) - DO i1 = LBOUND(InData%CBB,1), UBOUND(InData%CBB,1) - ReKiBuf(Re_Xferred) = InData%CBB(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%CMM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CMM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMM,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CMM,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMM,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%CMM,2), UBOUND(InData%CMM,2) - DO i1 = LBOUND(InData%CMM,1), UBOUND(InData%CMM,1) - ReKiBuf(Re_Xferred) = InData%CMM(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MBM) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%MBM,2), UBOUND(InData%MBM,2) - DO i1 = LBOUND(InData%MBM,1), UBOUND(InData%MBM,1) - ReKiBuf(Re_Xferred) = InData%MBM(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiL_T) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL_T,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL_T,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL_T,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL_T,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiL_T,2), UBOUND(InData%PhiL_T,2) - DO i1 = LBOUND(InData%PhiL_T,1), UBOUND(InData%PhiL_T,1) - ReKiBuf(Re_Xferred) = InData%PhiL_T(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%PhiLInvOmgL2) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiLInvOmgL2,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiLInvOmgL2,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiLInvOmgL2,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiLInvOmgL2,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%PhiLInvOmgL2,2), UBOUND(InData%PhiLInvOmgL2,2) - DO i1 = LBOUND(InData%PhiLInvOmgL2,1), UBOUND(InData%PhiLInvOmgL2,1) - ReKiBuf(Re_Xferred) = InData%PhiLInvOmgL2(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%KLLm1) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KLLm1,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KLLm1,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%KLLm1,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KLLm1,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%KLLm1,2), UBOUND(InData%KLLm1,2) - DO i1 = LBOUND(InData%KLLm1,1), UBOUND(InData%KLLm1,1) - ReKiBuf(Re_Xferred) = InData%KLLm1(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%AM2Jac) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2Jac,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2Jac,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2Jac,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2Jac,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%AM2Jac,2), UBOUND(InData%AM2Jac,2) - DO i1 = LBOUND(InData%AM2Jac,1), UBOUND(InData%AM2Jac,1) - ReKiBuf(Re_Xferred) = InData%AM2Jac(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%AM2JacPiv) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2JacPiv,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2JacPiv,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%AM2JacPiv,1), UBOUND(InData%AM2JacPiv,1) - IntKiBuf(Int_Xferred) = InData%AM2JacPiv(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%TI) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%TI,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TI,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%TI,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TI,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%TI,2), UBOUND(InData%TI,2) - DO i1 = LBOUND(InData%TI,1), UBOUND(InData%TI,1) - ReKiBuf(Re_Xferred) = InData%TI(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%TIreact) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%TIreact,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TIreact,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%TIreact,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TIreact,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%TIreact,2), UBOUND(InData%TIreact,2) - DO i1 = LBOUND(InData%TIreact,1), UBOUND(InData%TIreact,1) - ReKiBuf(Re_Xferred) = InData%TIreact(i1,i2) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IntKiBuf(Int_Xferred) = InData%nNodes - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nNodes_I - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nNodes_L - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nNodes_C - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Nodes_I) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_I,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_I,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_I,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_I,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Nodes_I,2), UBOUND(InData%Nodes_I,2) - DO i1 = LBOUND(InData%Nodes_I,1), UBOUND(InData%Nodes_I,1) - IntKiBuf(Int_Xferred) = InData%Nodes_I(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Nodes_L) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_L,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_L,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_L,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_L,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Nodes_L,2), UBOUND(InData%Nodes_L,2) - DO i1 = LBOUND(InData%Nodes_L,1), UBOUND(InData%Nodes_L,1) - IntKiBuf(Int_Xferred) = InData%Nodes_L(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%Nodes_C) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_C,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_C,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_C,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_C,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Nodes_C,2), UBOUND(InData%Nodes_C,2) - DO i1 = LBOUND(InData%Nodes_C,1), UBOUND(InData%Nodes_C,1) - IntKiBuf(Int_Xferred) = InData%Nodes_C(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IntKiBuf(Int_Xferred) = InData%nDOFI__ - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFI_Rb - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFI_F - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFL_L - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFC__ - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFC_Rb - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFC_L - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFC_F - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOFR__ - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOF__Rb - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOF__L - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%nDOF__F - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%IDI__) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI__,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI__,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDI__,1), UBOUND(InData%IDI__,1) - IntKiBuf(Int_Xferred) = InData%IDI__(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDI_Rb) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI_Rb,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI_Rb,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDI_Rb,1), UBOUND(InData%IDI_Rb,1) - IntKiBuf(Int_Xferred) = InData%IDI_Rb(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDI_F) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI_F,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI_F,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDI_F,1), UBOUND(InData%IDI_F,1) - IntKiBuf(Int_Xferred) = InData%IDI_F(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDL_L) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDL_L,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDL_L,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDL_L,1), UBOUND(InData%IDL_L,1) - IntKiBuf(Int_Xferred) = InData%IDL_L(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDC__) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC__,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC__,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDC__,1), UBOUND(InData%IDC__,1) - IntKiBuf(Int_Xferred) = InData%IDC__(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDC_Rb) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_Rb,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_Rb,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDC_Rb,1), UBOUND(InData%IDC_Rb,1) - IntKiBuf(Int_Xferred) = InData%IDC_Rb(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDC_L) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_L,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_L,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDC_L,1), UBOUND(InData%IDC_L,1) - IntKiBuf(Int_Xferred) = InData%IDC_L(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDC_F) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_F,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_F,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDC_F,1), UBOUND(InData%IDC_F,1) - IntKiBuf(Int_Xferred) = InData%IDC_F(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%IDR__) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%IDR__,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDR__,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%IDR__,1), UBOUND(InData%IDR__,1) - IntKiBuf(Int_Xferred) = InData%IDR__(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ID__Rb) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__Rb,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__Rb,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%ID__Rb,1), UBOUND(InData%ID__Rb,1) - IntKiBuf(Int_Xferred) = InData%ID__Rb(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ID__L) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__L,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__L,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%ID__L,1), UBOUND(InData%ID__L,1) - IntKiBuf(Int_Xferred) = InData%ID__L(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( .NOT. ALLOCATED(InData%ID__F) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__F,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__F,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%ID__F,1), UBOUND(InData%ID__F,1) - IntKiBuf(Int_Xferred) = InData%ID__F(i1) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IntKiBuf(Int_Xferred) = InData%NMOutputs - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%NumOuts - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutSwtch - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%UnJckF - Int_Xferred = Int_Xferred + 1 - DO I = 1, LEN(InData%Delim) - IntKiBuf(Int_Xferred) = ICHAR(InData%Delim(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(InData%OutFmt) - IntKiBuf(Int_Xferred) = ICHAR(InData%OutFmt(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(InData%OutSFmt) - IntKiBuf(Int_Xferred) = ICHAR(InData%OutSFmt(I:I), IntKi) - Int_Xferred = Int_Xferred + 1 - END DO ! I - IF ( .NOT. ALLOCATED(InData%MoutLst) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%MoutLst,1), UBOUND(InData%MoutLst,1) - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MoutLst2) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst2,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst2,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%MoutLst2,1), UBOUND(InData%MoutLst2,1) - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst2(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst2 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%MoutLst3) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst3,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst3,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%MoutLst3,1), UBOUND(InData%MoutLst3,1) - CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst3(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst3 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IF ( .NOT. ALLOCATED(InData%OutParam) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%OutParam,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%OutParam,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%OutParam,1), UBOUND(InData%OutParam,1) - CALL NWTC_Library_Packoutparmtype( Re_Buf, Db_Buf, Int_Buf, InData%OutParam(i1), ErrStat2, ErrMsg2, OnlySize ) ! OutParam - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - END DO - END IF - IntKiBuf(Int_Xferred) = TRANSFER(InData%OutAll, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutCBModes - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutFEMModes - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%OutReact, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutAllInt - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutAllDims - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%OutDec - Int_Xferred = Int_Xferred + 1 - IF ( .NOT. ALLOCATED(InData%Jac_u_indx) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Jac_u_indx,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Jac_u_indx,1) - Int_Xferred = Int_Xferred + 2 - IntKiBuf( Int_Xferred ) = LBOUND(InData%Jac_u_indx,2) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Jac_u_indx,2) - Int_Xferred = Int_Xferred + 2 - - DO i2 = LBOUND(InData%Jac_u_indx,2), UBOUND(InData%Jac_u_indx,2) - DO i1 = LBOUND(InData%Jac_u_indx,1), UBOUND(InData%Jac_u_indx,1) - IntKiBuf(Int_Xferred) = InData%Jac_u_indx(i1,i2) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( .NOT. ALLOCATED(InData%du) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%du,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%du,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%du,1), UBOUND(InData%du,1) - DbKiBuf(Db_Xferred) = InData%du(i1) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - DO i1 = LBOUND(InData%dx,1), UBOUND(InData%dx,1) - DbKiBuf(Db_Xferred) = InData%dx(i1) - Db_Xferred = Db_Xferred + 1 - END DO - IntKiBuf(Int_Xferred) = InData%Jac_ny - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = InData%Jac_nx - Int_Xferred = Int_Xferred + 1 - IntKiBuf(Int_Xferred) = TRANSFER(InData%RotStates, IntKiBuf(1)) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_PackParam - - SUBROUTINE SD_UnPackParam( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_ParameterType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackParam' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - OutData%SDDeltaT = DbKiBuf(Db_Xferred) - Db_Xferred = Db_Xferred + 1 - OutData%IntMethod = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOF = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOF_red = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%Nmembers = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Elems not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Elems)) DEALLOCATE(OutData%Elems) - ALLOCATE(OutData%Elems(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Elems.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Elems,2), UBOUND(OutData%Elems,2) - DO i1 = LBOUND(OutData%Elems,1), UBOUND(OutData%Elems,1) - OutData%Elems(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemProps not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ElemProps)) DEALLOCATE(OutData%ElemProps) - ALLOCATE(OutData%ElemProps(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemProps.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%ElemProps,1), UBOUND(OutData%ElemProps,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackelemproptype( Re_Buf, Db_Buf, Int_Buf, OutData%ElemProps(i1), ErrStat2, ErrMsg2 ) ! ElemProps - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! FG not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%FG)) DEALLOCATE(OutData%FG) - ALLOCATE(OutData%FG(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%FG.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%FG,1), UBOUND(OutData%FG,1) - OutData%FG(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DP0 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%DP0)) DEALLOCATE(OutData%DP0) - ALLOCATE(OutData%DP0(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DP0.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%DP0,2), UBOUND(OutData%DP0,2) - DO i1 = LBOUND(OutData%DP0,1), UBOUND(OutData%DP0,1) - OutData%DP0(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeID2JointID not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodeID2JointID)) DEALLOCATE(OutData%NodeID2JointID) - ALLOCATE(OutData%NodeID2JointID(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeID2JointID.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%NodeID2JointID,1), UBOUND(OutData%NodeID2JointID,1) - OutData%NodeID2JointID(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - OutData%reduced = TRANSFER(IntKiBuf(Int_Xferred), OutData%reduced) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! T_red not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%T_red)) DEALLOCATE(OutData%T_red) - ALLOCATE(OutData%T_red(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%T_red.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%T_red,2), UBOUND(OutData%T_red,2) - DO i1 = LBOUND(OutData%T_red,1), UBOUND(OutData%T_red,1) - OutData%T_red(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! T_red_T not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%T_red_T)) DEALLOCATE(OutData%T_red_T) - ALLOCATE(OutData%T_red_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%T_red_T.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%T_red_T,2), UBOUND(OutData%T_red_T,2) - DO i1 = LBOUND(OutData%T_red_T,1), UBOUND(OutData%T_red_T,1) - OutData%T_red_T(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesDOF not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodesDOF)) DEALLOCATE(OutData%NodesDOF) - ALLOCATE(OutData%NodesDOF(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesDOF.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%NodesDOF,1), UBOUND(OutData%NodesDOF,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackilist( Re_Buf, Db_Buf, Int_Buf, OutData%NodesDOF(i1), ErrStat2, ErrMsg2 ) ! NodesDOF - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesDOFred not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%NodesDOFred)) DEALLOCATE(OutData%NodesDOFred) - ALLOCATE(OutData%NodesDOFred(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesDOFred.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%NodesDOFred,1), UBOUND(OutData%NodesDOFred,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackilist( Re_Buf, Db_Buf, Int_Buf, OutData%NodesDOFred(i1), ErrStat2, ErrMsg2 ) ! NodesDOFred - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemsDOF not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ElemsDOF)) DEALLOCATE(OutData%ElemsDOF) - ALLOCATE(OutData%ElemsDOF(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemsDOF.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%ElemsDOF,2), UBOUND(OutData%ElemsDOF,2) - DO i1 = LBOUND(OutData%ElemsDOF,1), UBOUND(OutData%ElemsDOF,1) - OutData%ElemsDOF(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DOFred2Nodes not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%DOFred2Nodes)) DEALLOCATE(OutData%DOFred2Nodes) - ALLOCATE(OutData%DOFred2Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DOFred2Nodes.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%DOFred2Nodes,2), UBOUND(OutData%DOFred2Nodes,2) - DO i1 = LBOUND(OutData%DOFred2Nodes,1), UBOUND(OutData%DOFred2Nodes,1) - OutData%DOFred2Nodes(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CtrlElem2Channel not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CtrlElem2Channel)) DEALLOCATE(OutData%CtrlElem2Channel) - ALLOCATE(OutData%CtrlElem2Channel(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CtrlElem2Channel.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%CtrlElem2Channel,2), UBOUND(OutData%CtrlElem2Channel,2) - DO i1 = LBOUND(OutData%CtrlElem2Channel,1), UBOUND(OutData%CtrlElem2Channel,1) - OutData%CtrlElem2Channel(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - OutData%nDOFM = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%SttcSolve = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%GuyanLoadCorrection = TRANSFER(IntKiBuf(Int_Xferred), OutData%GuyanLoadCorrection) - Int_Xferred = Int_Xferred + 1 - OutData%Floating = TRANSFER(IntKiBuf(Int_Xferred), OutData%Floating) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KMMDiag not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%KMMDiag)) DEALLOCATE(OutData%KMMDiag) - ALLOCATE(OutData%KMMDiag(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KMMDiag.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%KMMDiag,1), UBOUND(OutData%KMMDiag,1) - OutData%KMMDiag(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMMDiag not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CMMDiag)) DEALLOCATE(OutData%CMMDiag) - ALLOCATE(OutData%CMMDiag(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMMDiag.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%CMMDiag,1), UBOUND(OutData%CMMDiag,1) - OutData%CMMDiag(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MMB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MMB)) DEALLOCATE(OutData%MMB) - ALLOCATE(OutData%MMB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MMB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MMB,2), UBOUND(OutData%MMB,2) - DO i1 = LBOUND(OutData%MMB,1), UBOUND(OutData%MMB,1) - OutData%MMB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBmmB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MBmmB)) DEALLOCATE(OutData%MBmmB) - ALLOCATE(OutData%MBmmB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBmmB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MBmmB,2), UBOUND(OutData%MBmmB,2) - DO i1 = LBOUND(OutData%MBmmB,1), UBOUND(OutData%MBmmB,1) - OutData%MBmmB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C1_11 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%C1_11)) DEALLOCATE(OutData%C1_11) - ALLOCATE(OutData%C1_11(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C1_11.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%C1_11,2), UBOUND(OutData%C1_11,2) - DO i1 = LBOUND(OutData%C1_11,1), UBOUND(OutData%C1_11,1) - OutData%C1_11(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C1_12 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%C1_12)) DEALLOCATE(OutData%C1_12) - ALLOCATE(OutData%C1_12(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C1_12.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%C1_12,2), UBOUND(OutData%C1_12,2) - DO i1 = LBOUND(OutData%C1_12,1), UBOUND(OutData%C1_12,1) - OutData%C1_12(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D1_141 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%D1_141)) DEALLOCATE(OutData%D1_141) - ALLOCATE(OutData%D1_141(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D1_141.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%D1_141,2), UBOUND(OutData%D1_141,2) - DO i1 = LBOUND(OutData%D1_141,1), UBOUND(OutData%D1_141,1) - OutData%D1_141(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D1_142 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%D1_142)) DEALLOCATE(OutData%D1_142) - ALLOCATE(OutData%D1_142(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D1_142.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%D1_142,2), UBOUND(OutData%D1_142,2) - DO i1 = LBOUND(OutData%D1_142,1), UBOUND(OutData%D1_142,1) - OutData%D1_142(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiM)) DEALLOCATE(OutData%PhiM) - ALLOCATE(OutData%PhiM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiM,2), UBOUND(OutData%PhiM,2) - DO i1 = LBOUND(OutData%PhiM,1), UBOUND(OutData%PhiM,1) - OutData%PhiM(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C2_61 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%C2_61)) DEALLOCATE(OutData%C2_61) - ALLOCATE(OutData%C2_61(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C2_61.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%C2_61,2), UBOUND(OutData%C2_61,2) - DO i1 = LBOUND(OutData%C2_61,1), UBOUND(OutData%C2_61,1) - OutData%C2_61(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C2_62 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%C2_62)) DEALLOCATE(OutData%C2_62) - ALLOCATE(OutData%C2_62(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C2_62.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%C2_62,2), UBOUND(OutData%C2_62,2) - DO i1 = LBOUND(OutData%C2_62,1), UBOUND(OutData%C2_62,1) - OutData%C2_62(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiRb_TI not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiRb_TI)) DEALLOCATE(OutData%PhiRb_TI) - ALLOCATE(OutData%PhiRb_TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiRb_TI.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiRb_TI,2), UBOUND(OutData%PhiRb_TI,2) - DO i1 = LBOUND(OutData%PhiRb_TI,1), UBOUND(OutData%PhiRb_TI,1) - OutData%PhiRb_TI(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D2_63 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%D2_63)) DEALLOCATE(OutData%D2_63) - ALLOCATE(OutData%D2_63(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D2_63.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%D2_63,2), UBOUND(OutData%D2_63,2) - DO i1 = LBOUND(OutData%D2_63,1), UBOUND(OutData%D2_63,1) - OutData%D2_63(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D2_64 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%D2_64)) DEALLOCATE(OutData%D2_64) - ALLOCATE(OutData%D2_64(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D2_64.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%D2_64,2), UBOUND(OutData%D2_64,2) - DO i1 = LBOUND(OutData%D2_64,1), UBOUND(OutData%D2_64,1) - OutData%D2_64(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MBB)) DEALLOCATE(OutData%MBB) - ALLOCATE(OutData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MBB,2), UBOUND(OutData%MBB,2) - DO i1 = LBOUND(OutData%MBB,1), UBOUND(OutData%MBB,1) - OutData%MBB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KBB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%KBB)) DEALLOCATE(OutData%KBB) - ALLOCATE(OutData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%KBB,2), UBOUND(OutData%KBB,2) - DO i1 = LBOUND(OutData%KBB,1), UBOUND(OutData%KBB,1) - OutData%KBB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CBB not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CBB)) DEALLOCATE(OutData%CBB) - ALLOCATE(OutData%CBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CBB.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%CBB,2), UBOUND(OutData%CBB,2) - DO i1 = LBOUND(OutData%CBB,1), UBOUND(OutData%CBB,1) - OutData%CBB(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CMM)) DEALLOCATE(OutData%CMM) - ALLOCATE(OutData%CMM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%CMM,2), UBOUND(OutData%CMM,2) - DO i1 = LBOUND(OutData%CMM,1), UBOUND(OutData%CMM,1) - OutData%CMM(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBM not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MBM)) DEALLOCATE(OutData%MBM) - ALLOCATE(OutData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBM.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%MBM,2), UBOUND(OutData%MBM,2) - DO i1 = LBOUND(OutData%MBM,1), UBOUND(OutData%MBM,1) - OutData%MBM(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiL_T not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiL_T)) DEALLOCATE(OutData%PhiL_T) - ALLOCATE(OutData%PhiL_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiL_T.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiL_T,2), UBOUND(OutData%PhiL_T,2) - DO i1 = LBOUND(OutData%PhiL_T,1), UBOUND(OutData%PhiL_T,1) - OutData%PhiL_T(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiLInvOmgL2 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%PhiLInvOmgL2)) DEALLOCATE(OutData%PhiLInvOmgL2) - ALLOCATE(OutData%PhiLInvOmgL2(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiLInvOmgL2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%PhiLInvOmgL2,2), UBOUND(OutData%PhiLInvOmgL2,2) - DO i1 = LBOUND(OutData%PhiLInvOmgL2,1), UBOUND(OutData%PhiLInvOmgL2,1) - OutData%PhiLInvOmgL2(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KLLm1 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%KLLm1)) DEALLOCATE(OutData%KLLm1) - ALLOCATE(OutData%KLLm1(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KLLm1.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%KLLm1,2), UBOUND(OutData%KLLm1,2) - DO i1 = LBOUND(OutData%KLLm1,1), UBOUND(OutData%KLLm1,1) - OutData%KLLm1(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AM2Jac not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%AM2Jac)) DEALLOCATE(OutData%AM2Jac) - ALLOCATE(OutData%AM2Jac(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AM2Jac.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%AM2Jac,2), UBOUND(OutData%AM2Jac,2) - DO i1 = LBOUND(OutData%AM2Jac,1), UBOUND(OutData%AM2Jac,1) - OutData%AM2Jac(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AM2JacPiv not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%AM2JacPiv)) DEALLOCATE(OutData%AM2JacPiv) - ALLOCATE(OutData%AM2JacPiv(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AM2JacPiv.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%AM2JacPiv,1), UBOUND(OutData%AM2JacPiv,1) - OutData%AM2JacPiv(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! TI not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%TI)) DEALLOCATE(OutData%TI) - ALLOCATE(OutData%TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%TI.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%TI,2), UBOUND(OutData%TI,2) - DO i1 = LBOUND(OutData%TI,1), UBOUND(OutData%TI,1) - OutData%TI(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! TIreact not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%TIreact)) DEALLOCATE(OutData%TIreact) - ALLOCATE(OutData%TIreact(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%TIreact.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%TIreact,2), UBOUND(OutData%TIreact,2) - DO i1 = LBOUND(OutData%TIreact,1), UBOUND(OutData%TIreact,1) - OutData%TIreact(i1,i2) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END DO - END IF - OutData%nNodes = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nNodes_I = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nNodes_L = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nNodes_C = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_I not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Nodes_I)) DEALLOCATE(OutData%Nodes_I) - ALLOCATE(OutData%Nodes_I(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_I.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Nodes_I,2), UBOUND(OutData%Nodes_I,2) - DO i1 = LBOUND(OutData%Nodes_I,1), UBOUND(OutData%Nodes_I,1) - OutData%Nodes_I(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_L not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Nodes_L)) DEALLOCATE(OutData%Nodes_L) - ALLOCATE(OutData%Nodes_L(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Nodes_L,2), UBOUND(OutData%Nodes_L,2) - DO i1 = LBOUND(OutData%Nodes_L,1), UBOUND(OutData%Nodes_L,1) - OutData%Nodes_L(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_C not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Nodes_C)) DEALLOCATE(OutData%Nodes_C) - ALLOCATE(OutData%Nodes_C(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_C.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Nodes_C,2), UBOUND(OutData%Nodes_C,2) - DO i1 = LBOUND(OutData%Nodes_C,1), UBOUND(OutData%Nodes_C,1) - OutData%Nodes_C(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - OutData%nDOFI__ = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFI_Rb = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFI_F = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFL_L = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFC__ = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFC_Rb = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFC_L = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFC_F = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOFR__ = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOF__Rb = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOF__L = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%nDOF__F = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI__ not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDI__)) DEALLOCATE(OutData%IDI__) - ALLOCATE(OutData%IDI__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDI__,1), UBOUND(OutData%IDI__,1) - OutData%IDI__(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI_Rb not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDI_Rb)) DEALLOCATE(OutData%IDI_Rb) - ALLOCATE(OutData%IDI_Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI_Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDI_Rb,1), UBOUND(OutData%IDI_Rb,1) - OutData%IDI_Rb(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI_F not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDI_F)) DEALLOCATE(OutData%IDI_F) - ALLOCATE(OutData%IDI_F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI_F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDI_F,1), UBOUND(OutData%IDI_F,1) - OutData%IDI_F(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDL_L not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDL_L)) DEALLOCATE(OutData%IDL_L) - ALLOCATE(OutData%IDL_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDL_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDL_L,1), UBOUND(OutData%IDL_L,1) - OutData%IDL_L(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC__ not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDC__)) DEALLOCATE(OutData%IDC__) - ALLOCATE(OutData%IDC__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDC__,1), UBOUND(OutData%IDC__,1) - OutData%IDC__(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_Rb not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDC_Rb)) DEALLOCATE(OutData%IDC_Rb) - ALLOCATE(OutData%IDC_Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDC_Rb,1), UBOUND(OutData%IDC_Rb,1) - OutData%IDC_Rb(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_L not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDC_L)) DEALLOCATE(OutData%IDC_L) - ALLOCATE(OutData%IDC_L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDC_L,1), UBOUND(OutData%IDC_L,1) - OutData%IDC_L(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_F not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDC_F)) DEALLOCATE(OutData%IDC_F) - ALLOCATE(OutData%IDC_F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDC_F,1), UBOUND(OutData%IDC_F,1) - OutData%IDC_F(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDR__ not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%IDR__)) DEALLOCATE(OutData%IDR__) - ALLOCATE(OutData%IDR__(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDR__.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%IDR__,1), UBOUND(OutData%IDR__,1) - OutData%IDR__(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__Rb not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ID__Rb)) DEALLOCATE(OutData%ID__Rb) - ALLOCATE(OutData%ID__Rb(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__Rb.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%ID__Rb,1), UBOUND(OutData%ID__Rb,1) - OutData%ID__Rb(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__L not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ID__L)) DEALLOCATE(OutData%ID__L) - ALLOCATE(OutData%ID__L(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__L.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%ID__L,1), UBOUND(OutData%ID__L,1) - OutData%ID__L(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__F not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%ID__F)) DEALLOCATE(OutData%ID__F) - ALLOCATE(OutData%ID__F(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__F.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%ID__F,1), UBOUND(OutData%ID__F,1) - OutData%ID__F(i1) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END IF - OutData%NMOutputs = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%NumOuts = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%OutSwtch = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%UnJckF = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - DO I = 1, LEN(OutData%Delim) - OutData%Delim(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(OutData%OutFmt) - OutData%OutFmt(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - DO I = 1, LEN(OutData%OutSFmt) - OutData%OutSFmt(I:I) = CHAR(IntKiBuf(Int_Xferred)) - Int_Xferred = Int_Xferred + 1 - END DO ! I - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MoutLst)) DEALLOCATE(OutData%MoutLst) - ALLOCATE(OutData%MoutLst(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%MoutLst,1), UBOUND(OutData%MoutLst,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst(i1), ErrStat2, ErrMsg2 ) ! MoutLst - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst2 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MoutLst2)) DEALLOCATE(OutData%MoutLst2) - ALLOCATE(OutData%MoutLst2(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst2.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%MoutLst2,1), UBOUND(OutData%MoutLst2,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst2(i1), ErrStat2, ErrMsg2 ) ! MoutLst2 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst3 not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%MoutLst3)) DEALLOCATE(OutData%MoutLst3) - ALLOCATE(OutData%MoutLst3(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst3.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%MoutLst3,1), UBOUND(OutData%MoutLst3,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst3(i1), ErrStat2, ErrMsg2 ) ! MoutLst3 - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! OutParam not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%OutParam)) DEALLOCATE(OutData%OutParam) - ALLOCATE(OutData%OutParam(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%OutParam.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%OutParam,1), UBOUND(OutData%OutParam,1) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL NWTC_Library_Unpackoutparmtype( Re_Buf, Db_Buf, Int_Buf, OutData%OutParam(i1), ErrStat2, ErrMsg2 ) ! OutParam - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - END DO - END IF - OutData%OutAll = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutAll) - Int_Xferred = Int_Xferred + 1 - OutData%OutCBModes = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%OutFEMModes = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%OutReact = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutReact) - Int_Xferred = Int_Xferred + 1 - OutData%OutAllInt = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%OutAllDims = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%OutDec = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Jac_u_indx not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - i2_l = IntKiBuf( Int_Xferred ) - i2_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%Jac_u_indx)) DEALLOCATE(OutData%Jac_u_indx) - ALLOCATE(OutData%Jac_u_indx(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Jac_u_indx.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i2 = LBOUND(OutData%Jac_u_indx,2), UBOUND(OutData%Jac_u_indx,2) - DO i1 = LBOUND(OutData%Jac_u_indx,1), UBOUND(OutData%Jac_u_indx,1) - OutData%Jac_u_indx(i1,i2) = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - END DO - END DO - END IF - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! du not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%du)) DEALLOCATE(OutData%du) - ALLOCATE(OutData%du(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%du.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%du,1), UBOUND(OutData%du,1) - OutData%du(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - END IF - i1_l = LBOUND(OutData%dx,1) - i1_u = UBOUND(OutData%dx,1) - DO i1 = LBOUND(OutData%dx,1), UBOUND(OutData%dx,1) - OutData%dx(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) - Db_Xferred = Db_Xferred + 1 - END DO - OutData%Jac_ny = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%Jac_nx = IntKiBuf(Int_Xferred) - Int_Xferred = Int_Xferred + 1 - OutData%RotStates = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotStates) - Int_Xferred = Int_Xferred + 1 - END SUBROUTINE SD_UnPackParam - - SUBROUTINE SD_CopyInput( SrcInputData, DstInputData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_InputType), INTENT(INOUT) :: SrcInputData - TYPE(SD_InputType), INTENT(INOUT) :: DstInputData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInput' -! - ErrStat = ErrID_None - ErrMsg = "" - CALL MeshCopy( SrcInputData%TPMesh, DstInputData%TPMesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - CALL MeshCopy( SrcInputData%LMesh, DstInputData%LMesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN -IF (ALLOCATED(SrcInputData%CableDeltaL)) THEN - i1_l = LBOUND(SrcInputData%CableDeltaL,1) - i1_u = UBOUND(SrcInputData%CableDeltaL,1) - IF (.NOT. ALLOCATED(DstInputData%CableDeltaL)) THEN - ALLOCATE(DstInputData%CableDeltaL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInputData%CableDeltaL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstInputData%CableDeltaL = SrcInputData%CableDeltaL -ENDIF - END SUBROUTINE SD_CopyInput - - SUBROUTINE SD_DestroyInput( InputData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_InputType), INTENT(INOUT) :: InputData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInput' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - - CALL MeshDestroy( InputData%TPMesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - CALL MeshDestroy( InputData%LMesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -IF (ALLOCATED(InputData%CableDeltaL)) THEN - DEALLOCATE(InputData%CableDeltaL) -ENDIF - END SUBROUTINE SD_DestroyInput - - SUBROUTINE SD_PackInput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_InputType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInput' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - Int_BufSz = Int_BufSz + 3 ! TPMesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! TPMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! TPMesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! TPMesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! TPMesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 3 ! LMesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! LMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! LMesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! LMesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! LMesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 1 ! CableDeltaL allocated yes/no - IF ( ALLOCATED(InData%CableDeltaL) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! CableDeltaL upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%CableDeltaL) ! CableDeltaL - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - CALL MeshPack( InData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! TPMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - CALL MeshPack( InData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! LMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF ( .NOT. ALLOCATED(InData%CableDeltaL) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%CableDeltaL,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CableDeltaL,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%CableDeltaL,1), UBOUND(InData%CableDeltaL,1) - ReKiBuf(Re_Xferred) = InData%CableDeltaL(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackInput - - SUBROUTINE SD_UnPackInput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_InputType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInput' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! TPMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! LMesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CableDeltaL not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%CableDeltaL)) DEALLOCATE(OutData%CableDeltaL) - ALLOCATE(OutData%CableDeltaL(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CableDeltaL.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%CableDeltaL,1), UBOUND(OutData%CableDeltaL,1) - OutData%CableDeltaL(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackInput - - SUBROUTINE SD_CopyOutput( SrcOutputData, DstOutputData, CtrlCode, ErrStat, ErrMsg ) - TYPE(SD_OutputType), INTENT(INOUT) :: SrcOutputData - TYPE(SD_OutputType), INTENT(INOUT) :: DstOutputData - INTEGER(IntKi), INTENT(IN ) :: CtrlCode - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg -! Local - INTEGER(IntKi) :: i,j,k - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyOutput' -! - ErrStat = ErrID_None - ErrMsg = "" - CALL MeshCopy( SrcOutputData%Y1Mesh, DstOutputData%Y1Mesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - CALL MeshCopy( SrcOutputData%Y2Mesh, DstOutputData%Y2Mesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN - CALL MeshCopy( SrcOutputData%Y3Mesh, DstOutputData%Y3Mesh, CtrlCode, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat>=AbortErrLev) RETURN -IF (ALLOCATED(SrcOutputData%WriteOutput)) THEN - i1_l = LBOUND(SrcOutputData%WriteOutput,1) - i1_u = UBOUND(SrcOutputData%WriteOutput,1) - IF (.NOT. ALLOCATED(DstOutputData%WriteOutput)) THEN - ALLOCATE(DstOutputData%WriteOutput(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DstOutputData%WriteOutput.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - DstOutputData%WriteOutput = SrcOutputData%WriteOutput -ENDIF - END SUBROUTINE SD_CopyOutput - - SUBROUTINE SD_DestroyOutput( OutputData, ErrStat, ErrMsg, DEALLOCATEpointers ) - TYPE(SD_OutputType), INTENT(INOUT) :: OutputData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers - - INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 - LOGICAL :: DEALLOCATEpointers_local - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyOutput' - - ErrStat = ErrID_None - ErrMsg = "" - - IF (PRESENT(DEALLOCATEpointers)) THEN - DEALLOCATEpointers_local = DEALLOCATEpointers - ELSE - DEALLOCATEpointers_local = .true. - END IF - - CALL MeshDestroy( OutputData%Y1Mesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - CALL MeshDestroy( OutputData%Y2Mesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - CALL MeshDestroy( OutputData%Y3Mesh, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) -IF (ALLOCATED(OutputData%WriteOutput)) THEN - DEALLOCATE(OutputData%WriteOutput) -ENDIF - END SUBROUTINE SD_DestroyOutput - - SUBROUTINE SD_PackOutput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) - REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) - TYPE(SD_OutputType), INTENT(IN) :: InData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly - ! Local variables - INTEGER(IntKi) :: Re_BufSz - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_BufSz - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_BufSz - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 - LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackOutput' - ! buffers to store subtypes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - - OnlySize = .FALSE. - IF ( PRESENT(SizeOnly) ) THEN - OnlySize = SizeOnly - ENDIF - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_BufSz = 0 - Db_BufSz = 0 - Int_BufSz = 0 - ! Allocate buffers for subtypes, if any (we'll get sizes from these) - Int_BufSz = Int_BufSz + 3 ! Y1Mesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y1Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! Y1Mesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! Y1Mesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! Y1Mesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 3 ! Y2Mesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y2Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! Y2Mesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! Y2Mesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! Y2Mesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 3 ! Y3Mesh: size of buffers for each call to pack subtype - CALL MeshPack( InData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y3Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN ! Y3Mesh - Re_BufSz = Re_BufSz + SIZE( Re_Buf ) - DEALLOCATE(Re_Buf) - END IF - IF(ALLOCATED(Db_Buf)) THEN ! Y3Mesh - Db_BufSz = Db_BufSz + SIZE( Db_Buf ) - DEALLOCATE(Db_Buf) - END IF - IF(ALLOCATED(Int_Buf)) THEN ! Y3Mesh - Int_BufSz = Int_BufSz + SIZE( Int_Buf ) - DEALLOCATE(Int_Buf) - END IF - Int_BufSz = Int_BufSz + 1 ! WriteOutput allocated yes/no - IF ( ALLOCATED(InData%WriteOutput) ) THEN - Int_BufSz = Int_BufSz + 2*1 ! WriteOutput upper/lower bounds for each dimension - Re_BufSz = Re_BufSz + SIZE(InData%WriteOutput) ! WriteOutput - END IF - IF ( Re_BufSz .GT. 0 ) THEN - ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Db_BufSz .GT. 0 ) THEN - ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF ( Int_BufSz .GT. 0 ) THEN - ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - END IF - IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) - - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - - CALL MeshPack( InData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y1Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - CALL MeshPack( InData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y2Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - CALL MeshPack( InData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y3Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf - Re_Xferred = Re_Xferred + SIZE(Re_Buf) - DEALLOCATE(Re_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Db_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf - Db_Xferred = Db_Xferred + SIZE(Db_Buf) - DEALLOCATE(Db_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF(ALLOCATED(Int_Buf)) THEN - IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 - IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf - Int_Xferred = Int_Xferred + SIZE(Int_Buf) - DEALLOCATE(Int_Buf) - ELSE - IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 - ENDIF - IF ( .NOT. ALLOCATED(InData%WriteOutput) ) THEN - IntKiBuf( Int_Xferred ) = 0 - Int_Xferred = Int_Xferred + 1 - ELSE - IntKiBuf( Int_Xferred ) = 1 - Int_Xferred = Int_Xferred + 1 - IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutput,1) - IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutput,1) - Int_Xferred = Int_Xferred + 2 - - DO i1 = LBOUND(InData%WriteOutput,1), UBOUND(InData%WriteOutput,1) - ReKiBuf(Re_Xferred) = InData%WriteOutput(i1) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_PackOutput - - SUBROUTINE SD_UnPackOutput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) - REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) - REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) - INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) - TYPE(SD_OutputType), INTENT(INOUT) :: OutData - INTEGER(IntKi), INTENT( OUT) :: ErrStat - CHARACTER(*), INTENT( OUT) :: ErrMsg - ! Local variables - INTEGER(IntKi) :: Buf_size - INTEGER(IntKi) :: Re_Xferred - INTEGER(IntKi) :: Db_Xferred - INTEGER(IntKi) :: Int_Xferred - INTEGER(IntKi) :: i - INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 - INTEGER(IntKi) :: ErrStat2 - CHARACTER(ErrMsgLen) :: ErrMsg2 - CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackOutput' - ! buffers to store meshes, if any - REAL(ReKi), ALLOCATABLE :: Re_Buf(:) - REAL(DbKi), ALLOCATABLE :: Db_Buf(:) - INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) - ! - ErrStat = ErrID_None - ErrMsg = "" - Re_Xferred = 1 - Db_Xferred = 1 - Int_Xferred = 1 - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y1Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y2Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) - Re_Xferred = Re_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) - Db_Xferred = Db_Xferred + Buf_size - END IF - Buf_size=IntKiBuf( Int_Xferred ) - Int_Xferred = Int_Xferred + 1 - IF(Buf_size > 0) THEN - ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) - Int_Xferred = Int_Xferred + Buf_size - END IF - CALL MeshUnpack( OutData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y3Mesh - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) - IF (ErrStat >= AbortErrLev) RETURN - - IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) - IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) - IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) - IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutput not allocated - Int_Xferred = Int_Xferred + 1 - ELSE - Int_Xferred = Int_Xferred + 1 - i1_l = IntKiBuf( Int_Xferred ) - i1_u = IntKiBuf( Int_Xferred + 1) - Int_Xferred = Int_Xferred + 2 - IF (ALLOCATED(OutData%WriteOutput)) DEALLOCATE(OutData%WriteOutput) - ALLOCATE(OutData%WriteOutput(i1_l:i1_u),STAT=ErrStat2) - IF (ErrStat2 /= 0) THEN - CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutput.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - DO i1 = LBOUND(OutData%WriteOutput,1), UBOUND(OutData%WriteOutput,1) - OutData%WriteOutput(i1) = ReKiBuf(Re_Xferred) - Re_Xferred = Re_Xferred + 1 - END DO - END IF - END SUBROUTINE SD_UnPackOutput - - - SUBROUTINE SD_Input_ExtrapInterp(u, t, u_out, t_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time -! values of u (which has values associated with times in t). Order of the interpolation is given by the size of u -! -! expressions below based on either -! -! f(t) = a -! f(t) = a + b * t, or -! f(t) = a + b * t + c * t**2 -! -! where a, b and c are determined as the solution to -! f(t1) = u1, f(t2) = u2, f(t3) = u3 (as appropriate) -! -!.................................................................................................................................. - - TYPE(SD_InputType), INTENT(INOUT) :: u(:) ! Input at t1 > t2 > t3 - REAL(DbKi), INTENT(IN ) :: t(:) ! Times associated with the Inputs - TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out - REAL(DbKi), INTENT(IN ) :: t_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - INTEGER(IntKi) :: order ! order of polynomial fit (max 2) - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp' - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - if ( size(t) .ne. size(u)) then - CALL SetErrStat(ErrID_Fatal,'size(t) must equal size(u)',ErrStat,ErrMsg,RoutineName) - RETURN - endif - order = SIZE(u) - 1 - IF ( order .eq. 0 ) THEN - CALL SD_CopyInput(u(1), u_out, MESH_UPDATECOPY, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE IF ( order .eq. 1 ) THEN - CALL SD_Input_ExtrapInterp1(u(1), u(2), t, u_out, t_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE IF ( order .eq. 2 ) THEN - CALL SD_Input_ExtrapInterp2(u(1), u(2), u(3), t, u_out, t_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE - CALL SetErrStat(ErrID_Fatal,'size(u) must be less than 4 (order must be less than 3).',ErrStat,ErrMsg,RoutineName) - RETURN - ENDIF - END SUBROUTINE SD_Input_ExtrapInterp - - - SUBROUTINE SD_Input_ExtrapInterp1(u1, u2, tin, u_out, tin_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time -! values of u (which has values associated with times in t). Order of the interpolation is 1. -! -! f(t) = a + b * t, or -! -! where a and b are determined as the solution to -! f(t1) = u1, f(t2) = u2 -! -!.................................................................................................................................. - - TYPE(SD_InputType), INTENT(INOUT) :: u1 ! Input at t1 > t2 - TYPE(SD_InputType), INTENT(INOUT) :: u2 ! Input at t2 - REAL(DbKi), INTENT(IN ) :: tin(2) ! Times associated with the Inputs - TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out - REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - REAL(DbKi) :: t(2) ! Times associated with the Inputs - REAL(DbKi) :: t_out ! Time to which to be extrap/interpd - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp1' - REAL(DbKi) :: b ! temporary for extrapolation/interpolation - REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts - INTEGER :: i1 ! dim1 counter variable for arrays - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - ! we'll subtract a constant from the times to resolve some - ! numerical issues when t gets large (and to simplify the equations) - t = tin - tin(1) - t_out = tin_out - tin(1) - - IF ( EqualRealNos( t(1), t(2) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - - ScaleFactor = t_out / t(2) - CALL MeshExtrapInterp1(u1%TPMesh, u2%TPMesh, tin, u_out%TPMesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp1(u1%LMesh, u2%LMesh, tin, u_out%LMesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) -IF (ALLOCATED(u_out%CableDeltaL) .AND. ALLOCATED(u1%CableDeltaL)) THEN - DO i1 = LBOUND(u_out%CableDeltaL,1),UBOUND(u_out%CableDeltaL,1) - b = -(u1%CableDeltaL(i1) - u2%CableDeltaL(i1)) - u_out%CableDeltaL(i1) = u1%CableDeltaL(i1) + b * ScaleFactor - END DO -END IF ! check if allocated - END SUBROUTINE SD_Input_ExtrapInterp1 - - - SUBROUTINE SD_Input_ExtrapInterp2(u1, u2, u3, tin, u_out, tin_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time -! values of u (which has values associated with times in t). Order of the interpolation is 2. -! -! expressions below based on either -! -! f(t) = a + b * t + c * t**2 -! -! where a, b and c are determined as the solution to -! f(t1) = u1, f(t2) = u2, f(t3) = u3 -! -!.................................................................................................................................. - - TYPE(SD_InputType), INTENT(INOUT) :: u1 ! Input at t1 > t2 > t3 - TYPE(SD_InputType), INTENT(INOUT) :: u2 ! Input at t2 > t3 - TYPE(SD_InputType), INTENT(INOUT) :: u3 ! Input at t3 - REAL(DbKi), INTENT(IN ) :: tin(3) ! Times associated with the Inputs - TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out - REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - REAL(DbKi) :: t(3) ! Times associated with the Inputs - REAL(DbKi) :: t_out ! Time to which to be extrap/interpd - INTEGER(IntKi) :: order ! order of polynomial fit (max 2) - REAL(DbKi) :: b ! temporary for extrapolation/interpolation - REAL(DbKi) :: c ! temporary for extrapolation/interpolation - REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp2' - INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts - INTEGER :: i1 ! dim1 counter variable for arrays - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - ! we'll subtract a constant from the times to resolve some - ! numerical issues when t gets large (and to simplify the equations) - t = tin - tin(1) - t_out = tin_out - tin(1) - - IF ( EqualRealNos( t(1), t(2) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - ELSE IF ( EqualRealNos( t(2), t(3) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(2) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - ELSE IF ( EqualRealNos( t(1), t(3) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - - ScaleFactor = t_out / (t(2) * t(3) * (t(2) - t(3))) - CALL MeshExtrapInterp2(u1%TPMesh, u2%TPMesh, u3%TPMesh, tin, u_out%TPMesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp2(u1%LMesh, u2%LMesh, u3%LMesh, tin, u_out%LMesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) -IF (ALLOCATED(u_out%CableDeltaL) .AND. ALLOCATED(u1%CableDeltaL)) THEN - DO i1 = LBOUND(u_out%CableDeltaL,1),UBOUND(u_out%CableDeltaL,1) - b = (t(3)**2*(u1%CableDeltaL(i1) - u2%CableDeltaL(i1)) + t(2)**2*(-u1%CableDeltaL(i1) + u3%CableDeltaL(i1)))* scaleFactor - c = ( (t(2)-t(3))*u1%CableDeltaL(i1) + t(3)*u2%CableDeltaL(i1) - t(2)*u3%CableDeltaL(i1) ) * scaleFactor - u_out%CableDeltaL(i1) = u1%CableDeltaL(i1) + b + c * t_out - END DO -END IF ! check if allocated - END SUBROUTINE SD_Input_ExtrapInterp2 - - - SUBROUTINE SD_Output_ExtrapInterp(y, t, y_out, t_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time -! values of y (which has values associated with times in t). Order of the interpolation is given by the size of y -! -! expressions below based on either -! -! f(t) = a -! f(t) = a + b * t, or -! f(t) = a + b * t + c * t**2 -! -! where a, b and c are determined as the solution to -! f(t1) = y1, f(t2) = y2, f(t3) = y3 (as appropriate) -! -!.................................................................................................................................. - - TYPE(SD_OutputType), INTENT(INOUT) :: y(:) ! Output at t1 > t2 > t3 - REAL(DbKi), INTENT(IN ) :: t(:) ! Times associated with the Outputs - TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out - REAL(DbKi), INTENT(IN ) :: t_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - INTEGER(IntKi) :: order ! order of polynomial fit (max 2) - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp' - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - if ( size(t) .ne. size(y)) then - CALL SetErrStat(ErrID_Fatal,'size(t) must equal size(y)',ErrStat,ErrMsg,RoutineName) - RETURN - endif - order = SIZE(y) - 1 - IF ( order .eq. 0 ) THEN - CALL SD_CopyOutput(y(1), y_out, MESH_UPDATECOPY, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE IF ( order .eq. 1 ) THEN - CALL SD_Output_ExtrapInterp1(y(1), y(2), t, y_out, t_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE IF ( order .eq. 2 ) THEN - CALL SD_Output_ExtrapInterp2(y(1), y(2), y(3), t, y_out, t_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - ELSE - CALL SetErrStat(ErrID_Fatal,'size(y) must be less than 4 (order must be less than 3).',ErrStat,ErrMsg,RoutineName) - RETURN - ENDIF - END SUBROUTINE SD_Output_ExtrapInterp - - - SUBROUTINE SD_Output_ExtrapInterp1(y1, y2, tin, y_out, tin_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time -! values of y (which has values associated with times in t). Order of the interpolation is 1. -! -! f(t) = a + b * t, or -! -! where a and b are determined as the solution to -! f(t1) = y1, f(t2) = y2 -! -!.................................................................................................................................. - - TYPE(SD_OutputType), INTENT(INOUT) :: y1 ! Output at t1 > t2 - TYPE(SD_OutputType), INTENT(INOUT) :: y2 ! Output at t2 - REAL(DbKi), INTENT(IN ) :: tin(2) ! Times associated with the Outputs - TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out - REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - REAL(DbKi) :: t(2) ! Times associated with the Outputs - REAL(DbKi) :: t_out ! Time to which to be extrap/interpd - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp1' - REAL(DbKi) :: b ! temporary for extrapolation/interpolation - REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts - INTEGER :: i1 ! dim1 counter variable for arrays - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - ! we'll subtract a constant from the times to resolve some - ! numerical issues when t gets large (and to simplify the equations) - t = tin - tin(1) - t_out = tin_out - tin(1) - - IF ( EqualRealNos( t(1), t(2) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - - ScaleFactor = t_out / t(2) - CALL MeshExtrapInterp1(y1%Y1Mesh, y2%Y1Mesh, tin, y_out%Y1Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp1(y1%Y2Mesh, y2%Y2Mesh, tin, y_out%Y2Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp1(y1%Y3Mesh, y2%Y3Mesh, tin, y_out%Y3Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) -IF (ALLOCATED(y_out%WriteOutput) .AND. ALLOCATED(y1%WriteOutput)) THEN - DO i1 = LBOUND(y_out%WriteOutput,1),UBOUND(y_out%WriteOutput,1) - b = -(y1%WriteOutput(i1) - y2%WriteOutput(i1)) - y_out%WriteOutput(i1) = y1%WriteOutput(i1) + b * ScaleFactor - END DO -END IF ! check if allocated - END SUBROUTINE SD_Output_ExtrapInterp1 - - - SUBROUTINE SD_Output_ExtrapInterp2(y1, y2, y3, tin, y_out, tin_out, ErrStat, ErrMsg ) -! -! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time -! values of y (which has values associated with times in t). Order of the interpolation is 2. -! -! expressions below based on either -! -! f(t) = a + b * t + c * t**2 -! -! where a, b and c are determined as the solution to -! f(t1) = y1, f(t2) = y2, f(t3) = y3 -! -!.................................................................................................................................. - - TYPE(SD_OutputType), INTENT(INOUT) :: y1 ! Output at t1 > t2 > t3 - TYPE(SD_OutputType), INTENT(INOUT) :: y2 ! Output at t2 > t3 - TYPE(SD_OutputType), INTENT(INOUT) :: y3 ! Output at t3 - REAL(DbKi), INTENT(IN ) :: tin(3) ! Times associated with the Outputs - TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out - REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to - INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation - CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None - ! local variables - REAL(DbKi) :: t(3) ! Times associated with the Outputs - REAL(DbKi) :: t_out ! Time to which to be extrap/interpd - INTEGER(IntKi) :: order ! order of polynomial fit (max 2) - REAL(DbKi) :: b ! temporary for extrapolation/interpolation - REAL(DbKi) :: c ! temporary for extrapolation/interpolation - REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation - INTEGER(IntKi) :: ErrStat2 ! local errors - CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors - CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp2' - INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts - INTEGER :: i1 ! dim1 counter variable for arrays - ! Initialize ErrStat - ErrStat = ErrID_None - ErrMsg = "" - ! we'll subtract a constant from the times to resolve some - ! numerical issues when t gets large (and to simplify the equations) - t = tin - tin(1) - t_out = tin_out - tin(1) - - IF ( EqualRealNos( t(1), t(2) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - ELSE IF ( EqualRealNos( t(2), t(3) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(2) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - ELSE IF ( EqualRealNos( t(1), t(3) ) ) THEN - CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) - RETURN - END IF - - ScaleFactor = t_out / (t(2) * t(3) * (t(2) - t(3))) - CALL MeshExtrapInterp2(y1%Y1Mesh, y2%Y1Mesh, y3%Y1Mesh, tin, y_out%Y1Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp2(y1%Y2Mesh, y2%Y2Mesh, y3%Y2Mesh, tin, y_out%Y2Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) - CALL MeshExtrapInterp2(y1%Y3Mesh, y2%Y3Mesh, y3%Y3Mesh, tin, y_out%Y3Mesh, tin_out, ErrStat2, ErrMsg2 ) - CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) -IF (ALLOCATED(y_out%WriteOutput) .AND. ALLOCATED(y1%WriteOutput)) THEN - DO i1 = LBOUND(y_out%WriteOutput,1),UBOUND(y_out%WriteOutput,1) - b = (t(3)**2*(y1%WriteOutput(i1) - y2%WriteOutput(i1)) + t(2)**2*(-y1%WriteOutput(i1) + y3%WriteOutput(i1)))* scaleFactor - c = ( (t(2)-t(3))*y1%WriteOutput(i1) + t(3)*y2%WriteOutput(i1) - t(2)*y3%WriteOutput(i1) ) * scaleFactor - y_out%WriteOutput(i1) = y1%WriteOutput(i1) + b + c * t_out - END DO -END IF ! check if allocated - END SUBROUTINE SD_Output_ExtrapInterp2 - -END MODULE SubDyn_Types -!ENDOFREGISTRYGENERATEDFILE +!STARTOFREGISTRYGENERATEDFILE 'SubDyn_Types.f90' +! +! WARNING This file is generated automatically by the FAST registry. +! Do not edit. Your changes to this file will be lost. +! +! FAST Registry +!********************************************************************************************************************************* +! SubDyn_Types +!................................................................................................................................. +! This file is part of SubDyn. +! +! Copyright (C) 2012-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. +! +! +! W A R N I N G : This file was automatically generated from the FAST registry. Changes made to this file may be lost. +! +!********************************************************************************************************************************* +!> This module contains the user-defined types needed in SubDyn. It also contains copy, destroy, pack, and +!! unpack routines associated with each defined data type. This code is automatically generated by the FAST Registry. +MODULE SubDyn_Types +!--------------------------------------------------------------------------------------------------------------------------------- +USE NWTC_Library +IMPLICIT NONE +! ========= IList ======= + TYPE, PUBLIC :: IList + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: List !< List of integers [-] + END TYPE IList +! ======================= +! ========= MeshAuxDataType ======= + TYPE, PUBLIC :: MeshAuxDataType + INTEGER(IntKi) :: MemberID !< Member ID for Output [-] + INTEGER(IntKi) :: NOutCnt !< Number of Nodes for the output member [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeCnt !< Node ordinal numbers for the output member [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeIDs !< Node IDs associated with ordinal numbers for the output member [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElmIDs !< Element IDs connected to each NodeIDs; max 10 elements [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElmNds !< Flag to indicate 1st or 2nd node of element for each ElmIDs [-] + REAL(R8Ki) , DIMENSION(:,:,:,:), ALLOCATABLE :: Me !< Mass matrix connected to each joint element for outAll output [-] + REAL(R8Ki) , DIMENSION(:,:,:,:), ALLOCATABLE :: Ke !< Mass matrix connected to each joint element for outAll output [-] + REAL(R8Ki) , DIMENSION(:,:,:), ALLOCATABLE :: Fg !< Gravity load vector connected to each joint element for requested member output [-] + END TYPE MeshAuxDataType +! ======================= +! ========= CB_MatArrays ======= + TYPE, PUBLIC :: CB_MatArrays + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: MBB !< FULL MBB ( no constraints applied) [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: MBM !< FULL MBM ( no constraints applied) [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: KBB !< FULL KBB ( no constraints applied) [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: PhiL !< Retained CB modes, possibly allPhiL(nDOFL,nDOFL), or PhiL(nDOFL,nDOFM) [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: PhiR !< FULL PhiR ( no constraints applied) [-] + REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: OmegaL !< Eigenvalues of retained CB modes, possibly all (nDOFL or nDOFM) [-] + END TYPE CB_MatArrays +! ======================= +! ========= ElemPropType ======= + TYPE, PUBLIC :: ElemPropType + INTEGER(IntKi) :: eType !< Element Type [-] + REAL(ReKi) :: Length !< Length of an element [-] + REAL(ReKi) :: Ixx !< Moment of inertia of an element [-] + REAL(ReKi) :: Iyy !< Moment of inertia of an element [-] + REAL(ReKi) :: Jzz !< Moment of inertia of an element [-] + LOGICAL :: Shear !< Use timoshenko (true) E-B (false) [-] + REAL(ReKi) :: Kappa_x !< Shear coefficient [-] + REAL(ReKi) :: Kappa_y !< Shear coefficient [-] + REAL(ReKi) :: YoungE !< Young's modulus [-] + REAL(ReKi) :: ShearG !< Shear modulus [N/m^2] + REAL(ReKi) , DIMENSION(1:2) :: D !< Diameter at node 1 and 2, for visualization only [m] + REAL(ReKi) :: Area !< Area of an element [m^2] + REAL(ReKi) :: Rho !< Density [kg/m^3] + REAL(ReKi) :: T0 !< Pretension [N] + REAL(ReKi) :: k11 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k12 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k13 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k14 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k15 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k16 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k22 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k23 !< Spring cross-coupling stiffness [N/m] + REAL(ReKi) :: k24 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k25 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k26 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k33 !< Spring translational stiffness [N/m] + REAL(ReKi) :: k34 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k35 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k36 !< Spring cross-coupling stiffness [N/rad] + REAL(ReKi) :: k44 !< Spring rotational stiffness [Nm/rad] + REAL(ReKi) :: k45 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k46 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k55 !< Spring rotational stiffness [Nm/rad] + REAL(ReKi) :: k56 !< Spring cross-coupling stiffness [Nm/rad] + REAL(ReKi) :: k66 !< Spring rotational stiffness [Nm/rad] + REAL(R8Ki) , DIMENSION(1:3,1:3) :: DirCos !< Element direction cosine matrix [-] + END TYPE ElemPropType +! ======================= +! ========= SD_InitInputType ======= + TYPE, PUBLIC :: SD_InitInputType + CHARACTER(1024) :: SDInputFile !< Name of the input file [-] + CHARACTER(1024) :: RootName !< SubDyn rootname [-] + REAL(ReKi) :: g !< Gravity acceleration [-] + REAL(ReKi) :: WtrDpth !< Water Depth (positive valued) [-] + REAL(ReKi) , DIMENSION(1:3) :: TP_RefPoint !< global position of transition piece reference point (could also be defined in SubDyn itself) [-] + REAL(ReKi) :: SubRotateZ !< Rotation angle in degrees about global Z [-] + REAL(ReKi) , DIMENSION(:,:,:), ALLOCATABLE :: SoilStiffness !< Soil stiffness matrices from SoilDyn ['(N/m,] + TYPE(MeshType) :: SoilMesh !< Mesh for soil stiffness locations [-] + LOGICAL :: Linearize = .FALSE. !< Flag that tells this module if the glue code wants to linearize. [-] + END TYPE SD_InitInputType +! ======================= +! ========= SD_InitOutputType ======= + TYPE, PUBLIC :: SD_InitOutputType + CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: WriteOutputHdr !< Names of the output-to-file channels [-] + CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: WriteOutputUnt !< Units of the output-to-file channels [-] + TYPE(ProgDesc) :: Ver !< This module's name, version, and date [-] + CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_y !< Names of the outputs used in linearization [-] + CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_x !< Names of the continuous states used in linearization [-] + CHARACTER(LinChanLen) , DIMENSION(:), ALLOCATABLE :: LinNames_u !< Names of the inputs used in linearization [-] + LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_y !< Flag that tells FAST/MBC3 if the outputs used in linearization are in the rotating frame [-] + LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_x !< Flag that tells FAST/MBC3 if the continuous states used in linearization are in the rotating frame (not used for glue) [-] + LOGICAL , DIMENSION(:), ALLOCATABLE :: RotFrame_u !< Flag that tells FAST/MBC3 if the inputs used in linearization are in the rotating frame [-] + LOGICAL , DIMENSION(:), ALLOCATABLE :: IsLoad_u !< Flag that tells FAST if the inputs used in linearization are loads (for preconditioning matrix) [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: DerivOrder_x !< Integer that tells FAST/MBC3 the maximum derivative order of continuous states used in linearization [-] + LOGICAL , DIMENSION(:), ALLOCATABLE :: CableCChanRqst !< flag indicating control channel for active cable tensioning is requested [-] + END TYPE SD_InitOutputType +! ======================= +! ========= SD_InitType ======= + TYPE, PUBLIC :: SD_InitType + CHARACTER(1024) :: RootName !< SubDyn rootname [-] + REAL(ReKi) , DIMENSION(1:3) :: TP_RefPoint !< global position of transition piece reference point (could also be defined in SubDyn itself) [-] + REAL(ReKi) :: SubRotateZ !< Rotation angle in degrees about global Z [-] + REAL(ReKi) :: g !< Gravity acceleration [-] + REAL(DbKi) :: DT !< Time step from Glue Code [seconds] + INTEGER(IntKi) :: NJoints !< Number of joints of the sub structure [-] + INTEGER(IntKi) :: NPropSetsX !< Number of extended property sets [-] + INTEGER(IntKi) :: NPropSetsB !< Number of property sets for beams [-] + INTEGER(IntKi) :: NPropSetsC !< Number of property sets for cables [-] + INTEGER(IntKi) :: NPropSetsR !< Number of property sets for rigid links [-] + INTEGER(IntKi) :: NPropSetsS !< Number of property sets for spring elements [-] + INTEGER(IntKi) :: NCMass !< Number of joints with concentrated mass [-] + INTEGER(IntKi) :: NCOSMs !< Number of independent cosine matrices [-] + INTEGER(IntKi) :: FEMMod !< FEM switch element model in the FEM [-] + INTEGER(IntKi) :: NDiv !< Number of divisions for each member [-] + LOGICAL :: CBMod !< Perform C-B flag [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Joints !< Joints number and coordinate values [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsB !< Property sets number and values [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsC !< Property ID and values for cables [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsR !< Property ID and values for rigid link [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsS !< Property ID and values for spring element [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropSetsX !< Extended property sets [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: COSMs !< Independent direction cosine matrices [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CMass !< Concentrated mass information [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: JDampings !< Damping coefficients for internal modes [-] + INTEGER(IntKi) :: GuyanDampMod !< Guyan damping [0=none, 1=Rayleigh Damping, 2= user specified 6x6 matrix] [-] + REAL(ReKi) , DIMENSION(1:2) :: RayleighDamp !< Mass and stiffness proportional damping coefficients (Rayleigh Damping) [only if GuyanDampMod=1] [-] + REAL(ReKi) , DIMENSION(1:6,1:6) :: GuyanDampMat !< Guyan Damping Matrix, see also CBB [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Members !< Member joints connection [-] + CHARACTER(ChanLen) , DIMENSION(:), ALLOCATABLE :: SSOutList !< List of Output Channels [-] + LOGICAL :: OutCOSM !< Output Cos-matrices Flag [-] + LOGICAL :: TabDelim !< Generate a tab-delimited output file in OutJckF-Flag [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: SSIK !< SSI stiffness packed matrix elements (21 of them), for each reaction joint [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: SSIM !< SSI mass packed matrix elements (21 of them), for each reaction joint [-] + CHARACTER(1024) , DIMENSION(:), ALLOCATABLE :: SSIfile !< Soil Structure Interaction (SSI) files to associate with each reaction node [-] + REAL(ReKi) , DIMENSION(:,:,:), ALLOCATABLE :: Soil_K !< Soil stiffness (at passed at Init, not in input file) 6x6xn [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Soil_Points !< Node positions where soil stiffness will be added [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: Soil_Nodes !< Node indices where soil stiffness will be added [-] + INTEGER(IntKi) :: NElem !< Total number of elements [-] + INTEGER(IntKi) :: NPropB !< Total number of property sets for Beams [-] + INTEGER(IntKi) :: NPropC !< Total number of property sets for Cable [-] + INTEGER(IntKi) :: NPropR !< Total number of property sets for Rigid [-] + INTEGER(IntKi) :: NPropS !< Total number of property sets for Spring [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes !< Nodes number and coordinates [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsB !< Property sets and values for Beams [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsC !< Property sets and values for Cable [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsR !< Property sets and values for Rigid link [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PropsS !< Property sets and values for Spring [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: K !< System stiffness matrix [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: M !< System mass matrix [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: ElemProps !< Element properties(A, L, Ixx, Iyy, Jzz, Shear, Kappa, E, G, Rho, DirCos(1,1), DirCos(2, 1), ....., DirCos(3, 3) ) [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: MemberNodes !< Member number and list of nodes making up a member (>2 if subdivided) [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: NodesConnN !< Nodes that connect to a common node [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: NodesConnE !< Elements that connect to a common node [-] + LOGICAL :: SSSum !< SubDyn Summary File Flag [-] + END TYPE SD_InitType +! ======================= +! ========= SD_ContinuousStateType ======= + TYPE, PUBLIC :: SD_ContinuousStateType + REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: qm !< Virtual states, Nmod elements [-] + REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: qmdot !< Derivative of states, Nmod elements [-] + END TYPE SD_ContinuousStateType +! ======================= +! ========= SD_DiscreteStateType ======= + TYPE, PUBLIC :: SD_DiscreteStateType + REAL(ReKi) :: DummyDiscState !< Remove this variable if you have discrete states [-] + END TYPE SD_DiscreteStateType +! ======================= +! ========= SD_ConstraintStateType ======= + TYPE, PUBLIC :: SD_ConstraintStateType + REAL(ReKi) :: DummyConstrState !< Remove this variable if you have constraint states [-] + END TYPE SD_ConstraintStateType +! ======================= +! ========= SD_OtherStateType ======= + TYPE, PUBLIC :: SD_OtherStateType + TYPE(SD_ContinuousStateType) , DIMENSION(:), ALLOCATABLE :: xdot !< previous state derivs for m-step time integrator [-] + INTEGER(IntKi) :: n !< tracks time step for which OtherState was updated last [-] + END TYPE SD_OtherStateType +! ======================= +! ========= SD_MiscVarType ======= + TYPE, PUBLIC :: SD_MiscVarType + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: qmdotdot !< 2nd Derivative of states, used only for output-file purposes [-] + REAL(ReKi) , DIMENSION(1:6) :: u_TP + REAL(ReKi) , DIMENSION(1:6) :: udot_TP + REAL(ReKi) , DIMENSION(1:6) :: udotdot_TP + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: F_L !< Loads on internal DOF, size nL [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: F_L2 !< Loads on internal DOF, size nL, used for SIM and ADM4 [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar_dot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UR_bar_dotdot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL !< Internal DOFs (L) displacements [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_NS !< Internal DOFs (L) displacements, No SIM (NS) [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_dot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_dotdot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: DU_full !< Delta U used for extra moment, size nDOF [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full !< Displacement of all DOFs (full system) with SIM [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_NS !< Displacement of all DOFs (full system), No SIM (NS) [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_dot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_dotdot + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_full_elast !< Elastic displacements for computation of K ue (without rigid body mode for floating), includes SIM [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: U_red + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: FC_unit !< Cable Force vector (for varying cable load, of unit cable load) [N] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: SDWrOutput !< Data from previous step to be written to a SubDyn output file [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: AllOuts !< Data for output file [-] + REAL(DbKi) :: LastOutTime !< The time of the most recent stored output data [s] + INTEGER(IntKi) :: Decimat !< Current output decimation counter [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: Fext !< External loads on unconstrained DOFs [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: Fext_red !< External loads on constrained DOFs, Fext_red= T^t Fext [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_SIM !< UL for SIM = PhiL qL0- PhiM qm0, size nL [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: UL_0m !< Intermediate UL term for SIM = PhiM qm0, size nL [-] + END TYPE SD_MiscVarType +! ======================= +! ========= SD_ParameterType ======= + TYPE, PUBLIC :: SD_ParameterType + REAL(DbKi) :: SDDeltaT !< Time step (for integration of continuous states) [seconds] + INTEGER(IntKi) :: IntMethod !< Integration Method (1/2/3)Length of y2 array [-] + INTEGER(IntKi) :: nDOF !< Total degree of freedom [-] + INTEGER(IntKi) :: nDOF_red !< Total degree of freedom after constraint reduction [-] + INTEGER(IntKi) :: Nmembers !< Number of members of the sub structure [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Elems !< Element nodes connections [-] + TYPE(ElemPropType) , DIMENSION(:), ALLOCATABLE :: ElemProps !< List of element properties [-] + REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: FG !< Gravity force vector (with initial cable force T0), not reduced [N] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: DP0 !< Vector from TP to a Node at t=0, used for Floating Rigid Body motion [m] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: NodeID2JointID !< Store Joint ID for each NodeID since SubDyn re-label nodes (and add more nodes) [-] + LOGICAL :: reduced !< True if system has been reduced to account for constraints [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: T_red !< Transformation matrix performing the constraint reduction x = T. xtilde [-] + REAL(R8Ki) , DIMENSION(:,:), ALLOCATABLE :: T_red_T !< Transpose of T_red [-] + TYPE(IList) , DIMENSION(:), ALLOCATABLE :: NodesDOF !< DOF indices of each nodes in unconstrained assembled system [-] + TYPE(IList) , DIMENSION(:), ALLOCATABLE :: NodesDOFred !< DOF indices of each nodes in constrained assembled system [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: ElemsDOF !< 12 DOF indices of node 1 and 2 of a given member in unconstrained assembled system [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: DOFred2Nodes !< nDOFRed x 3, for each constrained DOF, col1 node index, col2 number of DOF, col3 DOF starting from 1 [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: CtrlElem2Channel !< nCtrlCable x 2, for each CtrlCable, Elem index, and Channel Index [-] + INTEGER(IntKi) :: nDOFM !< retained degrees of freedom (modes) [-] + INTEGER(IntKi) :: SttcSolve !< Solve dynamics about static equilibrium point (flag) [-] + LOGICAL :: GuyanLoadCorrection !< Add Extra lever arm contribution to interface reaction outputs [-] + LOGICAL :: Floating !< True if floating bottom (the 6 DOF are free at all reaction nodes) [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: KMMDiag !< Diagonal coefficients of Kmm (OmegaM squared) [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: CMMDiag !< Diagonal coefficients of Cmm (~2 Zeta OmegaM)) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MMB !< Matrix after C-B reduction (transpose of MBM [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBmmB !< MBm * MmB, used for Y1 [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C1_11 !< Coefficient of x in Y1 [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C1_12 !< Coefficient of x in Y1 [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D1_141 !< MBm PhiM^T [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D1_142 !< TI^T PhiR^T [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiM !< Coefficient of x in Y2 [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C2_61 !< Coefficient of x in Y2 (URdotdot ULdotdot) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: C2_62 !< Coefficient of x in Y2 (URdotdot ULdotdot) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiRb_TI !< Coefficient of u in Y2 (Phi_R bar * TI) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D2_63 !< Coefficient of u in Y2 (URdotdot ULdotdot) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: D2_64 !< Coefficient of u in Y2 (URdotdot ULdotdot) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBB !< Guyan Mass Matrix after C-B reduction [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: KBB !< Guyan Stiffness Matrix after C-B reduction [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CBB !< Guyan Damping Matrix after C-B reduction [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: CMM !< CB damping matrix [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: MBM !< Matrix after C-B reduction [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiL_T !< Transpose of Matrix of C-B modes [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: PhiLInvOmgL2 !< Matrix of C-B modes times the inverse of OmegaL**2 (Phi_L*(Omg**2)^-1) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: KLLm1 !< KLL^{-1}, inverse of matrix KLL, for static solve only [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: AM2Jac !< Jacobian (factored) for Adams-Boulton 2nd order Integration [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: AM2JacPiv !< Pivot array for Jacobian factorization (for Adams-Boulton 2nd order Integration) [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: TI !< Matrix to calculate TP reference point reaction at top of structure [-] + REAL(ReKi) , DIMENSION(:,:), ALLOCATABLE :: TIreact !< Matrix to calculate single point reaction at base of structure [-] + INTEGER(IntKi) :: nNodes !< Total number of nodes [-] + INTEGER(IntKi) :: nNodes_I !< Number of Interface nodes [-] + INTEGER(IntKi) :: nNodes_L !< Number of Internal nodes [-] + INTEGER(IntKi) :: nNodes_C !< Number of joints with reactions [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_I !< Interface degree of freedoms [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_L !< Internal nodes (not interface nor reaction) [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Nodes_C !< React degree of freedoms [-] + INTEGER(IntKi) :: nDOFI__ !< Size of IDI__ [-] + INTEGER(IntKi) :: nDOFI_Rb !< Size of IDI_Rb [-] + INTEGER(IntKi) :: nDOFI_F !< Size of IDI_F [-] + INTEGER(IntKi) :: nDOFL_L !< Size of IDL_L [-] + INTEGER(IntKi) :: nDOFC__ !< Size of IDC__ [-] + INTEGER(IntKi) :: nDOFC_Rb !< Size of IDC_Rb [-] + INTEGER(IntKi) :: nDOFC_L !< Size of IDC_L [-] + INTEGER(IntKi) :: nDOFC_F !< Size of IDC_F [-] + INTEGER(IntKi) :: nDOFR__ !< Size of IDR__ [-] + INTEGER(IntKi) :: nDOF__Rb !< Size of ID__Rb [-] + INTEGER(IntKi) :: nDOF__L !< Size of ID__L [-] + INTEGER(IntKi) :: nDOF__F !< Size of ID__F [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI__ !< Index of all Interface DOFs [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI_Rb !< Index array of the interface (nodes connect to TP) dofs that are retained/master/follower DOFs [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDI_F !< Index array of the interface (nodes connect to TP) dofs that are fixed DOF [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDL_L !< Index array of the internal dofs coming from internal nodes [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC__ !< Index of all bottom DOF [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_Rb !< Index array of the contraint dofs that are retained/master/follower DOF [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_L !< Index array of the contraint dofs that are follower/internal DOF [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDC_F !< Index array of the contraint dofs that are fixd DOF [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: IDR__ !< Index array of the interface and restraint dofs [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__Rb !< Index array of all the retained/leader/master dofs (from any nodes of the structure) [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__L !< Index array of all the follower/internal dofs (from any nodes of the structure) [-] + INTEGER(IntKi) , DIMENSION(:), ALLOCATABLE :: ID__F !< Index array of the DOF that are fixed (from any nodes of the structure) [-] + INTEGER(IntKi) :: NMOutputs !< Number of members whose output is written [-] + INTEGER(IntKi) :: NumOuts !< Number of output channels read from input file [-] + INTEGER(IntKi) :: OutSwtch !< Output Requested Channels to local or global output file [1/2/3] [-] + INTEGER(IntKi) :: UnJckF !< Unit of SD ouput file [-] + CHARACTER(1) :: Delim !< Column delimiter for output text files [-] + CHARACTER(20) :: OutFmt !< Format for Output [-] + CHARACTER(20) :: OutSFmt !< Format for Output Headers [-] + TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst !< List of user requested members and nodes [-] + TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst2 !< List of all member joint nodes and elements for output [-] + TYPE(MeshAuxDataType) , DIMENSION(:), ALLOCATABLE :: MoutLst3 !< List of all member joint nodes and elements for output [-] + TYPE(OutParmType) , DIMENSION(:), ALLOCATABLE :: OutParam !< An array holding names, units, and indices of all of the selected output channels. logical [-] + LOGICAL :: OutAll !< Flag to output or not all joint forces [-] + INTEGER(IntKi) :: OutCBModes !< Flag to output CB and Guyan modes to a given format [-] + INTEGER(IntKi) :: OutFEMModes !< Flag to output FEM modes to a given format [-] + LOGICAL :: OutReact !< Flag to check whether reactions are requested [-] + INTEGER(IntKi) :: OutAllInt !< Integer version of OutAll [-] + INTEGER(IntKi) :: OutAllDims !< Integer version of OutAll [-] + INTEGER(IntKi) :: OutDec !< Output Decimation for Requested Channels [-] + INTEGER(IntKi) , DIMENSION(:,:), ALLOCATABLE :: Jac_u_indx !< matrix to help fill/pack the u vector in computing the jacobian [-] + REAL(R8Ki) , DIMENSION(:), ALLOCATABLE :: du !< vector that determines size of perturbation for u (inputs) [-] + REAL(R8Ki) , DIMENSION(1:2) :: dx !< vector that determines size of perturbation for x (continuous states) [-] + INTEGER(IntKi) :: Jac_ny !< number of outputs in jacobian matrix [-] + INTEGER(IntKi) :: Jac_nx !< half the number of continuous states in jacobian matrix [-] + LOGICAL :: RotStates !< Orient states in rotating frame during linearization? (flag) [-] + END TYPE SD_ParameterType +! ======================= +! ========= SD_InputType ======= + TYPE, PUBLIC :: SD_InputType + TYPE(MeshType) :: TPMesh !< Transition piece inputs on a point mesh [-] + TYPE(MeshType) :: LMesh !< Point mesh for interior node inputs [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: CableDeltaL !< Cable tension, control input [-] + END TYPE SD_InputType +! ======================= +! ========= SD_OutputType ======= + TYPE, PUBLIC :: SD_OutputType + TYPE(MeshType) :: Y1Mesh !< Transition piece outputs on a point mesh [-] + TYPE(MeshType) :: Y2Mesh !< Interior+Interface nodes rigid body displacements + elastic velocities and accelerations on a point mesh [-] + TYPE(MeshType) :: Y3Mesh !< Interior+Interface nodes full elastic displacements/velocities and accelerations on a point mesh [-] + REAL(ReKi) , DIMENSION(:), ALLOCATABLE :: WriteOutput !< Data to be written to an output file [-] + END TYPE SD_OutputType +! ======================= +CONTAINS + SUBROUTINE SD_CopyIList( SrcIListData, DstIListData, CtrlCode, ErrStat, ErrMsg ) + TYPE(IList), INTENT(IN) :: SrcIListData + TYPE(IList), INTENT(INOUT) :: DstIListData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyIList' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcIListData%List)) THEN + i1_l = LBOUND(SrcIListData%List,1) + i1_u = UBOUND(SrcIListData%List,1) + IF (.NOT. ALLOCATED(DstIListData%List)) THEN + ALLOCATE(DstIListData%List(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstIListData%List.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstIListData%List = SrcIListData%List +ENDIF + END SUBROUTINE SD_CopyIList + + SUBROUTINE SD_DestroyIList( IListData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(IList), INTENT(INOUT) :: IListData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyIList' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(IListData%List)) THEN + DEALLOCATE(IListData%List) +ENDIF + END SUBROUTINE SD_DestroyIList + + SUBROUTINE SD_PackIList( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(IList), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackIList' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! List allocated yes/no + IF ( ALLOCATED(InData%List) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! List upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%List) ! List + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%List) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%List,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%List,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%List,1), UBOUND(InData%List,1) + IntKiBuf(Int_Xferred) = InData%List(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackIList + + SUBROUTINE SD_UnPackIList( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(IList), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackIList' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! List not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%List)) DEALLOCATE(OutData%List) + ALLOCATE(OutData%List(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%List.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%List,1), UBOUND(OutData%List,1) + OutData%List(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackIList + + SUBROUTINE SD_CopyMeshAuxDataType( SrcMeshAuxDataTypeData, DstMeshAuxDataTypeData, CtrlCode, ErrStat, ErrMsg ) + TYPE(MeshAuxDataType), INTENT(IN) :: SrcMeshAuxDataTypeData + TYPE(MeshAuxDataType), INTENT(INOUT) :: DstMeshAuxDataTypeData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyMeshAuxDataType' +! + ErrStat = ErrID_None + ErrMsg = "" + DstMeshAuxDataTypeData%MemberID = SrcMeshAuxDataTypeData%MemberID + DstMeshAuxDataTypeData%NOutCnt = SrcMeshAuxDataTypeData%NOutCnt +IF (ALLOCATED(SrcMeshAuxDataTypeData%NodeCnt)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%NodeCnt,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%NodeCnt,1) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%NodeCnt)) THEN + ALLOCATE(DstMeshAuxDataTypeData%NodeCnt(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%NodeCnt.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%NodeCnt = SrcMeshAuxDataTypeData%NodeCnt +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%NodeIDs)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%NodeIDs,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%NodeIDs,1) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%NodeIDs)) THEN + ALLOCATE(DstMeshAuxDataTypeData%NodeIDs(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%NodeIDs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%NodeIDs = SrcMeshAuxDataTypeData%NodeIDs +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%ElmIDs)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%ElmIDs,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%ElmIDs,1) + i2_l = LBOUND(SrcMeshAuxDataTypeData%ElmIDs,2) + i2_u = UBOUND(SrcMeshAuxDataTypeData%ElmIDs,2) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%ElmIDs)) THEN + ALLOCATE(DstMeshAuxDataTypeData%ElmIDs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%ElmIDs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%ElmIDs = SrcMeshAuxDataTypeData%ElmIDs +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%ElmNds)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%ElmNds,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%ElmNds,1) + i2_l = LBOUND(SrcMeshAuxDataTypeData%ElmNds,2) + i2_u = UBOUND(SrcMeshAuxDataTypeData%ElmNds,2) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%ElmNds)) THEN + ALLOCATE(DstMeshAuxDataTypeData%ElmNds(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%ElmNds.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%ElmNds = SrcMeshAuxDataTypeData%ElmNds +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%Me)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%Me,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%Me,1) + i2_l = LBOUND(SrcMeshAuxDataTypeData%Me,2) + i2_u = UBOUND(SrcMeshAuxDataTypeData%Me,2) + i3_l = LBOUND(SrcMeshAuxDataTypeData%Me,3) + i3_u = UBOUND(SrcMeshAuxDataTypeData%Me,3) + i4_l = LBOUND(SrcMeshAuxDataTypeData%Me,4) + i4_u = UBOUND(SrcMeshAuxDataTypeData%Me,4) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Me)) THEN + ALLOCATE(DstMeshAuxDataTypeData%Me(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Me.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%Me = SrcMeshAuxDataTypeData%Me +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%Ke)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%Ke,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%Ke,1) + i2_l = LBOUND(SrcMeshAuxDataTypeData%Ke,2) + i2_u = UBOUND(SrcMeshAuxDataTypeData%Ke,2) + i3_l = LBOUND(SrcMeshAuxDataTypeData%Ke,3) + i3_u = UBOUND(SrcMeshAuxDataTypeData%Ke,3) + i4_l = LBOUND(SrcMeshAuxDataTypeData%Ke,4) + i4_u = UBOUND(SrcMeshAuxDataTypeData%Ke,4) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Ke)) THEN + ALLOCATE(DstMeshAuxDataTypeData%Ke(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Ke.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%Ke = SrcMeshAuxDataTypeData%Ke +ENDIF +IF (ALLOCATED(SrcMeshAuxDataTypeData%Fg)) THEN + i1_l = LBOUND(SrcMeshAuxDataTypeData%Fg,1) + i1_u = UBOUND(SrcMeshAuxDataTypeData%Fg,1) + i2_l = LBOUND(SrcMeshAuxDataTypeData%Fg,2) + i2_u = UBOUND(SrcMeshAuxDataTypeData%Fg,2) + i3_l = LBOUND(SrcMeshAuxDataTypeData%Fg,3) + i3_u = UBOUND(SrcMeshAuxDataTypeData%Fg,3) + IF (.NOT. ALLOCATED(DstMeshAuxDataTypeData%Fg)) THEN + ALLOCATE(DstMeshAuxDataTypeData%Fg(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMeshAuxDataTypeData%Fg.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMeshAuxDataTypeData%Fg = SrcMeshAuxDataTypeData%Fg +ENDIF + END SUBROUTINE SD_CopyMeshAuxDataType + + SUBROUTINE SD_DestroyMeshAuxDataType( MeshAuxDataTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(MeshAuxDataType), INTENT(INOUT) :: MeshAuxDataTypeData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyMeshAuxDataType' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(MeshAuxDataTypeData%NodeCnt)) THEN + DEALLOCATE(MeshAuxDataTypeData%NodeCnt) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%NodeIDs)) THEN + DEALLOCATE(MeshAuxDataTypeData%NodeIDs) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%ElmIDs)) THEN + DEALLOCATE(MeshAuxDataTypeData%ElmIDs) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%ElmNds)) THEN + DEALLOCATE(MeshAuxDataTypeData%ElmNds) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%Me)) THEN + DEALLOCATE(MeshAuxDataTypeData%Me) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%Ke)) THEN + DEALLOCATE(MeshAuxDataTypeData%Ke) +ENDIF +IF (ALLOCATED(MeshAuxDataTypeData%Fg)) THEN + DEALLOCATE(MeshAuxDataTypeData%Fg) +ENDIF + END SUBROUTINE SD_DestroyMeshAuxDataType + + SUBROUTINE SD_PackMeshAuxDataType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(MeshAuxDataType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackMeshAuxDataType' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! MemberID + Int_BufSz = Int_BufSz + 1 ! NOutCnt + Int_BufSz = Int_BufSz + 1 ! NodeCnt allocated yes/no + IF ( ALLOCATED(InData%NodeCnt) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! NodeCnt upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%NodeCnt) ! NodeCnt + END IF + Int_BufSz = Int_BufSz + 1 ! NodeIDs allocated yes/no + IF ( ALLOCATED(InData%NodeIDs) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! NodeIDs upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%NodeIDs) ! NodeIDs + END IF + Int_BufSz = Int_BufSz + 1 ! ElmIDs allocated yes/no + IF ( ALLOCATED(InData%ElmIDs) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! ElmIDs upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ElmIDs) ! ElmIDs + END IF + Int_BufSz = Int_BufSz + 1 ! ElmNds allocated yes/no + IF ( ALLOCATED(InData%ElmNds) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! ElmNds upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ElmNds) ! ElmNds + END IF + Int_BufSz = Int_BufSz + 1 ! Me allocated yes/no + IF ( ALLOCATED(InData%Me) ) THEN + Int_BufSz = Int_BufSz + 2*4 ! Me upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%Me) ! Me + END IF + Int_BufSz = Int_BufSz + 1 ! Ke allocated yes/no + IF ( ALLOCATED(InData%Ke) ) THEN + Int_BufSz = Int_BufSz + 2*4 ! Ke upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%Ke) ! Ke + END IF + Int_BufSz = Int_BufSz + 1 ! Fg allocated yes/no + IF ( ALLOCATED(InData%Fg) ) THEN + Int_BufSz = Int_BufSz + 2*3 ! Fg upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%Fg) ! Fg + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IntKiBuf(Int_Xferred) = InData%MemberID + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NOutCnt + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%NodeCnt) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeCnt,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeCnt,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%NodeCnt,1), UBOUND(InData%NodeCnt,1) + IntKiBuf(Int_Xferred) = InData%NodeCnt(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodeIDs) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeIDs,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeIDs,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%NodeIDs,1), UBOUND(InData%NodeIDs,1) + IntKiBuf(Int_Xferred) = InData%NodeIDs(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ElmIDs) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmIDs,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmIDs,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmIDs,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmIDs,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%ElmIDs,2), UBOUND(InData%ElmIDs,2) + DO i1 = LBOUND(InData%ElmIDs,1), UBOUND(InData%ElmIDs,1) + IntKiBuf(Int_Xferred) = InData%ElmIDs(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ElmNds) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmNds,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmNds,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElmNds,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElmNds,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%ElmNds,2), UBOUND(InData%ElmNds,2) + DO i1 = LBOUND(InData%ElmNds,1), UBOUND(InData%ElmNds,1) + IntKiBuf(Int_Xferred) = InData%ElmNds(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Me) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,2) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,3) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,3) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Me,4) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Me,4) + Int_Xferred = Int_Xferred + 2 + + DO i4 = LBOUND(InData%Me,4), UBOUND(InData%Me,4) + DO i3 = LBOUND(InData%Me,3), UBOUND(InData%Me,3) + DO i2 = LBOUND(InData%Me,2), UBOUND(InData%Me,2) + DO i1 = LBOUND(InData%Me,1), UBOUND(InData%Me,1) + DbKiBuf(Db_Xferred) = InData%Me(i1,i2,i3,i4) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Ke) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,2) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,3) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,3) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Ke,4) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Ke,4) + Int_Xferred = Int_Xferred + 2 + + DO i4 = LBOUND(InData%Ke,4), UBOUND(InData%Ke,4) + DO i3 = LBOUND(InData%Ke,3), UBOUND(InData%Ke,3) + DO i2 = LBOUND(InData%Ke,2), UBOUND(InData%Ke,2) + DO i1 = LBOUND(InData%Ke,1), UBOUND(InData%Ke,1) + DbKiBuf(Db_Xferred) = InData%Ke(i1,i2,i3,i4) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Fg) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,2) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Fg,3) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fg,3) + Int_Xferred = Int_Xferred + 2 + + DO i3 = LBOUND(InData%Fg,3), UBOUND(InData%Fg,3) + DO i2 = LBOUND(InData%Fg,2), UBOUND(InData%Fg,2) + DO i1 = LBOUND(InData%Fg,1), UBOUND(InData%Fg,1) + DbKiBuf(Db_Xferred) = InData%Fg(i1,i2,i3) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END IF + END SUBROUTINE SD_PackMeshAuxDataType + + SUBROUTINE SD_UnPackMeshAuxDataType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(MeshAuxDataType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: i4, i4_l, i4_u ! bounds (upper/lower) for an array dimension 4 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackMeshAuxDataType' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + OutData%MemberID = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NOutCnt = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeCnt not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodeCnt)) DEALLOCATE(OutData%NodeCnt) + ALLOCATE(OutData%NodeCnt(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeCnt.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%NodeCnt,1), UBOUND(OutData%NodeCnt,1) + OutData%NodeCnt(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeIDs not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodeIDs)) DEALLOCATE(OutData%NodeIDs) + ALLOCATE(OutData%NodeIDs(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeIDs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%NodeIDs,1), UBOUND(OutData%NodeIDs,1) + OutData%NodeIDs(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElmIDs not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ElmIDs)) DEALLOCATE(OutData%ElmIDs) + ALLOCATE(OutData%ElmIDs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElmIDs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%ElmIDs,2), UBOUND(OutData%ElmIDs,2) + DO i1 = LBOUND(OutData%ElmIDs,1), UBOUND(OutData%ElmIDs,1) + OutData%ElmIDs(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElmNds not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ElmNds)) DEALLOCATE(OutData%ElmNds) + ALLOCATE(OutData%ElmNds(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElmNds.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%ElmNds,2), UBOUND(OutData%ElmNds,2) + DO i1 = LBOUND(OutData%ElmNds,1), UBOUND(OutData%ElmNds,1) + OutData%ElmNds(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Me not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i3_l = IntKiBuf( Int_Xferred ) + i3_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i4_l = IntKiBuf( Int_Xferred ) + i4_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Me)) DEALLOCATE(OutData%Me) + ALLOCATE(OutData%Me(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Me.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i4 = LBOUND(OutData%Me,4), UBOUND(OutData%Me,4) + DO i3 = LBOUND(OutData%Me,3), UBOUND(OutData%Me,3) + DO i2 = LBOUND(OutData%Me,2), UBOUND(OutData%Me,2) + DO i1 = LBOUND(OutData%Me,1), UBOUND(OutData%Me,1) + OutData%Me(i1,i2,i3,i4) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Ke not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i3_l = IntKiBuf( Int_Xferred ) + i3_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i4_l = IntKiBuf( Int_Xferred ) + i4_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Ke)) DEALLOCATE(OutData%Ke) + ALLOCATE(OutData%Ke(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u,i4_l:i4_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Ke.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i4 = LBOUND(OutData%Ke,4), UBOUND(OutData%Ke,4) + DO i3 = LBOUND(OutData%Ke,3), UBOUND(OutData%Ke,3) + DO i2 = LBOUND(OutData%Ke,2), UBOUND(OutData%Ke,2) + DO i1 = LBOUND(OutData%Ke,1), UBOUND(OutData%Ke,1) + OutData%Ke(i1,i2,i3,i4) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fg not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i3_l = IntKiBuf( Int_Xferred ) + i3_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Fg)) DEALLOCATE(OutData%Fg) + ALLOCATE(OutData%Fg(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fg.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i3 = LBOUND(OutData%Fg,3), UBOUND(OutData%Fg,3) + DO i2 = LBOUND(OutData%Fg,2), UBOUND(OutData%Fg,2) + DO i1 = LBOUND(OutData%Fg,1), UBOUND(OutData%Fg,1) + OutData%Fg(i1,i2,i3) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END DO + END IF + END SUBROUTINE SD_UnPackMeshAuxDataType + + SUBROUTINE SD_CopyCB_MatArrays( SrcCB_MatArraysData, DstCB_MatArraysData, CtrlCode, ErrStat, ErrMsg ) + TYPE(CB_MatArrays), INTENT(IN) :: SrcCB_MatArraysData + TYPE(CB_MatArrays), INTENT(INOUT) :: DstCB_MatArraysData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyCB_MatArrays' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcCB_MatArraysData%MBB)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%MBB,1) + i1_u = UBOUND(SrcCB_MatArraysData%MBB,1) + i2_l = LBOUND(SrcCB_MatArraysData%MBB,2) + i2_u = UBOUND(SrcCB_MatArraysData%MBB,2) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%MBB)) THEN + ALLOCATE(DstCB_MatArraysData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%MBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%MBB = SrcCB_MatArraysData%MBB +ENDIF +IF (ALLOCATED(SrcCB_MatArraysData%MBM)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%MBM,1) + i1_u = UBOUND(SrcCB_MatArraysData%MBM,1) + i2_l = LBOUND(SrcCB_MatArraysData%MBM,2) + i2_u = UBOUND(SrcCB_MatArraysData%MBM,2) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%MBM)) THEN + ALLOCATE(DstCB_MatArraysData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%MBM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%MBM = SrcCB_MatArraysData%MBM +ENDIF +IF (ALLOCATED(SrcCB_MatArraysData%KBB)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%KBB,1) + i1_u = UBOUND(SrcCB_MatArraysData%KBB,1) + i2_l = LBOUND(SrcCB_MatArraysData%KBB,2) + i2_u = UBOUND(SrcCB_MatArraysData%KBB,2) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%KBB)) THEN + ALLOCATE(DstCB_MatArraysData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%KBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%KBB = SrcCB_MatArraysData%KBB +ENDIF +IF (ALLOCATED(SrcCB_MatArraysData%PhiL)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%PhiL,1) + i1_u = UBOUND(SrcCB_MatArraysData%PhiL,1) + i2_l = LBOUND(SrcCB_MatArraysData%PhiL,2) + i2_u = UBOUND(SrcCB_MatArraysData%PhiL,2) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%PhiL)) THEN + ALLOCATE(DstCB_MatArraysData%PhiL(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%PhiL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%PhiL = SrcCB_MatArraysData%PhiL +ENDIF +IF (ALLOCATED(SrcCB_MatArraysData%PhiR)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%PhiR,1) + i1_u = UBOUND(SrcCB_MatArraysData%PhiR,1) + i2_l = LBOUND(SrcCB_MatArraysData%PhiR,2) + i2_u = UBOUND(SrcCB_MatArraysData%PhiR,2) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%PhiR)) THEN + ALLOCATE(DstCB_MatArraysData%PhiR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%PhiR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%PhiR = SrcCB_MatArraysData%PhiR +ENDIF +IF (ALLOCATED(SrcCB_MatArraysData%OmegaL)) THEN + i1_l = LBOUND(SrcCB_MatArraysData%OmegaL,1) + i1_u = UBOUND(SrcCB_MatArraysData%OmegaL,1) + IF (.NOT. ALLOCATED(DstCB_MatArraysData%OmegaL)) THEN + ALLOCATE(DstCB_MatArraysData%OmegaL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstCB_MatArraysData%OmegaL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstCB_MatArraysData%OmegaL = SrcCB_MatArraysData%OmegaL +ENDIF + END SUBROUTINE SD_CopyCB_MatArrays + + SUBROUTINE SD_DestroyCB_MatArrays( CB_MatArraysData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(CB_MatArrays), INTENT(INOUT) :: CB_MatArraysData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyCB_MatArrays' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(CB_MatArraysData%MBB)) THEN + DEALLOCATE(CB_MatArraysData%MBB) +ENDIF +IF (ALLOCATED(CB_MatArraysData%MBM)) THEN + DEALLOCATE(CB_MatArraysData%MBM) +ENDIF +IF (ALLOCATED(CB_MatArraysData%KBB)) THEN + DEALLOCATE(CB_MatArraysData%KBB) +ENDIF +IF (ALLOCATED(CB_MatArraysData%PhiL)) THEN + DEALLOCATE(CB_MatArraysData%PhiL) +ENDIF +IF (ALLOCATED(CB_MatArraysData%PhiR)) THEN + DEALLOCATE(CB_MatArraysData%PhiR) +ENDIF +IF (ALLOCATED(CB_MatArraysData%OmegaL)) THEN + DEALLOCATE(CB_MatArraysData%OmegaL) +ENDIF + END SUBROUTINE SD_DestroyCB_MatArrays + + SUBROUTINE SD_PackCB_MatArrays( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(CB_MatArrays), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackCB_MatArrays' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! MBB allocated yes/no + IF ( ALLOCATED(InData%MBB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MBB upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%MBB) ! MBB + END IF + Int_BufSz = Int_BufSz + 1 ! MBM allocated yes/no + IF ( ALLOCATED(InData%MBM) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MBM upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%MBM) ! MBM + END IF + Int_BufSz = Int_BufSz + 1 ! KBB allocated yes/no + IF ( ALLOCATED(InData%KBB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! KBB upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%KBB) ! KBB + END IF + Int_BufSz = Int_BufSz + 1 ! PhiL allocated yes/no + IF ( ALLOCATED(InData%PhiL) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiL upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%PhiL) ! PhiL + END IF + Int_BufSz = Int_BufSz + 1 ! PhiR allocated yes/no + IF ( ALLOCATED(InData%PhiR) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiR upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%PhiR) ! PhiR + END IF + Int_BufSz = Int_BufSz + 1 ! OmegaL allocated yes/no + IF ( ALLOCATED(InData%OmegaL) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! OmegaL upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%OmegaL) ! OmegaL + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%MBB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MBB,2), UBOUND(InData%MBB,2) + DO i1 = LBOUND(InData%MBB,1), UBOUND(InData%MBB,1) + DbKiBuf(Db_Xferred) = InData%MBB(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MBM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MBM,2), UBOUND(InData%MBM,2) + DO i1 = LBOUND(InData%MBM,1), UBOUND(InData%MBM,1) + DbKiBuf(Db_Xferred) = InData%MBM(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%KBB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%KBB,2), UBOUND(InData%KBB,2) + DO i1 = LBOUND(InData%KBB,1), UBOUND(InData%KBB,1) + DbKiBuf(Db_Xferred) = InData%KBB(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiL) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiL,2), UBOUND(InData%PhiL,2) + DO i1 = LBOUND(InData%PhiL,1), UBOUND(InData%PhiL,1) + DbKiBuf(Db_Xferred) = InData%PhiL(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiR) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiR,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiR,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiR,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiR,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiR,2), UBOUND(InData%PhiR,2) + DO i1 = LBOUND(InData%PhiR,1), UBOUND(InData%PhiR,1) + DbKiBuf(Db_Xferred) = InData%PhiR(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%OmegaL) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%OmegaL,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%OmegaL,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%OmegaL,1), UBOUND(InData%OmegaL,1) + DbKiBuf(Db_Xferred) = InData%OmegaL(i1) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackCB_MatArrays + + SUBROUTINE SD_UnPackCB_MatArrays( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(CB_MatArrays), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackCB_MatArrays' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MBB)) DEALLOCATE(OutData%MBB) + ALLOCATE(OutData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MBB,2), UBOUND(OutData%MBB,2) + DO i1 = LBOUND(OutData%MBB,1), UBOUND(OutData%MBB,1) + OutData%MBB(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MBM)) DEALLOCATE(OutData%MBM) + ALLOCATE(OutData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MBM,2), UBOUND(OutData%MBM,2) + DO i1 = LBOUND(OutData%MBM,1), UBOUND(OutData%MBM,1) + OutData%MBM(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KBB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%KBB)) DEALLOCATE(OutData%KBB) + ALLOCATE(OutData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%KBB,2), UBOUND(OutData%KBB,2) + DO i1 = LBOUND(OutData%KBB,1), UBOUND(OutData%KBB,1) + OutData%KBB(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiL not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiL)) DEALLOCATE(OutData%PhiL) + ALLOCATE(OutData%PhiL(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiL,2), UBOUND(OutData%PhiL,2) + DO i1 = LBOUND(OutData%PhiL,1), UBOUND(OutData%PhiL,1) + OutData%PhiL(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiR not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiR)) DEALLOCATE(OutData%PhiR) + ALLOCATE(OutData%PhiR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiR,2), UBOUND(OutData%PhiR,2) + DO i1 = LBOUND(OutData%PhiR,1), UBOUND(OutData%PhiR,1) + OutData%PhiR(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! OmegaL not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%OmegaL)) DEALLOCATE(OutData%OmegaL) + ALLOCATE(OutData%OmegaL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%OmegaL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%OmegaL,1), UBOUND(OutData%OmegaL,1) + OutData%OmegaL(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackCB_MatArrays + + SUBROUTINE SD_CopyElemPropType( SrcElemPropTypeData, DstElemPropTypeData, CtrlCode, ErrStat, ErrMsg ) + TYPE(ElemPropType), INTENT(IN) :: SrcElemPropTypeData + TYPE(ElemPropType), INTENT(INOUT) :: DstElemPropTypeData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyElemPropType' +! + ErrStat = ErrID_None + ErrMsg = "" + DstElemPropTypeData%eType = SrcElemPropTypeData%eType + DstElemPropTypeData%Length = SrcElemPropTypeData%Length + DstElemPropTypeData%Ixx = SrcElemPropTypeData%Ixx + DstElemPropTypeData%Iyy = SrcElemPropTypeData%Iyy + DstElemPropTypeData%Jzz = SrcElemPropTypeData%Jzz + DstElemPropTypeData%Shear = SrcElemPropTypeData%Shear + DstElemPropTypeData%Kappa_x = SrcElemPropTypeData%Kappa_x + DstElemPropTypeData%Kappa_y = SrcElemPropTypeData%Kappa_y + DstElemPropTypeData%YoungE = SrcElemPropTypeData%YoungE + DstElemPropTypeData%ShearG = SrcElemPropTypeData%ShearG + DstElemPropTypeData%D = SrcElemPropTypeData%D + DstElemPropTypeData%Area = SrcElemPropTypeData%Area + DstElemPropTypeData%Rho = SrcElemPropTypeData%Rho + DstElemPropTypeData%T0 = SrcElemPropTypeData%T0 + DstElemPropTypeData%k11 = SrcElemPropTypeData%k11 + DstElemPropTypeData%k12 = SrcElemPropTypeData%k12 + DstElemPropTypeData%k13 = SrcElemPropTypeData%k13 + DstElemPropTypeData%k14 = SrcElemPropTypeData%k14 + DstElemPropTypeData%k15 = SrcElemPropTypeData%k15 + DstElemPropTypeData%k16 = SrcElemPropTypeData%k16 + DstElemPropTypeData%k22 = SrcElemPropTypeData%k22 + DstElemPropTypeData%k23 = SrcElemPropTypeData%k23 + DstElemPropTypeData%k24 = SrcElemPropTypeData%k24 + DstElemPropTypeData%k25 = SrcElemPropTypeData%k25 + DstElemPropTypeData%k26 = SrcElemPropTypeData%k26 + DstElemPropTypeData%k33 = SrcElemPropTypeData%k33 + DstElemPropTypeData%k34 = SrcElemPropTypeData%k34 + DstElemPropTypeData%k35 = SrcElemPropTypeData%k35 + DstElemPropTypeData%k36 = SrcElemPropTypeData%k36 + DstElemPropTypeData%k44 = SrcElemPropTypeData%k44 + DstElemPropTypeData%k45 = SrcElemPropTypeData%k45 + DstElemPropTypeData%k46 = SrcElemPropTypeData%k46 + DstElemPropTypeData%k55 = SrcElemPropTypeData%k55 + DstElemPropTypeData%k56 = SrcElemPropTypeData%k56 + DstElemPropTypeData%k66 = SrcElemPropTypeData%k66 + DstElemPropTypeData%DirCos = SrcElemPropTypeData%DirCos + END SUBROUTINE SD_CopyElemPropType + + SUBROUTINE SD_DestroyElemPropType( ElemPropTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(ElemPropType), INTENT(INOUT) :: ElemPropTypeData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyElemPropType' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + + END SUBROUTINE SD_DestroyElemPropType + + SUBROUTINE SD_PackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(ElemPropType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackElemPropType' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! eType + Re_BufSz = Re_BufSz + 1 ! Length + Re_BufSz = Re_BufSz + 1 ! Ixx + Re_BufSz = Re_BufSz + 1 ! Iyy + Re_BufSz = Re_BufSz + 1 ! Jzz + Int_BufSz = Int_BufSz + 1 ! Shear + Re_BufSz = Re_BufSz + 1 ! Kappa_x + Re_BufSz = Re_BufSz + 1 ! Kappa_y + Re_BufSz = Re_BufSz + 1 ! YoungE + Re_BufSz = Re_BufSz + 1 ! ShearG + Re_BufSz = Re_BufSz + SIZE(InData%D) ! D + Re_BufSz = Re_BufSz + 1 ! Area + Re_BufSz = Re_BufSz + 1 ! Rho + Re_BufSz = Re_BufSz + 1 ! T0 + Re_BufSz = Re_BufSz + 1 ! k11 + Re_BufSz = Re_BufSz + 1 ! k12 + Re_BufSz = Re_BufSz + 1 ! k13 + Re_BufSz = Re_BufSz + 1 ! k14 + Re_BufSz = Re_BufSz + 1 ! k15 + Re_BufSz = Re_BufSz + 1 ! k16 + Re_BufSz = Re_BufSz + 1 ! k22 + Re_BufSz = Re_BufSz + 1 ! k23 + Re_BufSz = Re_BufSz + 1 ! k24 + Re_BufSz = Re_BufSz + 1 ! k25 + Re_BufSz = Re_BufSz + 1 ! k26 + Re_BufSz = Re_BufSz + 1 ! k33 + Re_BufSz = Re_BufSz + 1 ! k34 + Re_BufSz = Re_BufSz + 1 ! k35 + Re_BufSz = Re_BufSz + 1 ! k36 + Re_BufSz = Re_BufSz + 1 ! k44 + Re_BufSz = Re_BufSz + 1 ! k45 + Re_BufSz = Re_BufSz + 1 ! k46 + Re_BufSz = Re_BufSz + 1 ! k55 + Re_BufSz = Re_BufSz + 1 ! k56 + Re_BufSz = Re_BufSz + 1 ! k66 + Db_BufSz = Db_BufSz + SIZE(InData%DirCos) ! DirCos + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IntKiBuf(Int_Xferred) = InData%eType + Int_Xferred = Int_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Length + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Ixx + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Iyy + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Jzz + Re_Xferred = Re_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%Shear, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Kappa_x + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Kappa_y + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%YoungE + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%ShearG + Re_Xferred = Re_Xferred + 1 + DO i1 = LBOUND(InData%D,1), UBOUND(InData%D,1) + ReKiBuf(Re_Xferred) = InData%D(i1) + Re_Xferred = Re_Xferred + 1 + END DO + ReKiBuf(Re_Xferred) = InData%Area + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%Rho + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%T0 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k11 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k12 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k13 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k14 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k15 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k16 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k22 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k23 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k24 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k25 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k26 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k33 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k34 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k35 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k36 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k44 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k45 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k46 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k55 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k56 + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%k66 + Re_Xferred = Re_Xferred + 1 + DO i2 = LBOUND(InData%DirCos,2), UBOUND(InData%DirCos,2) + DO i1 = LBOUND(InData%DirCos,1), UBOUND(InData%DirCos,1) + DbKiBuf(Db_Xferred) = InData%DirCos(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END SUBROUTINE SD_PackElemPropType + + SUBROUTINE SD_UnPackElemPropType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(ElemPropType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackElemPropType' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + OutData%eType = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%Length = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Ixx = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Iyy = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Jzz = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Shear = TRANSFER(IntKiBuf(Int_Xferred), OutData%Shear) + Int_Xferred = Int_Xferred + 1 + OutData%Kappa_x = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Kappa_y = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%YoungE = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%ShearG = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + i1_l = LBOUND(OutData%D,1) + i1_u = UBOUND(OutData%D,1) + DO i1 = LBOUND(OutData%D,1), UBOUND(OutData%D,1) + OutData%D(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + OutData%Area = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%Rho = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%T0 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k11 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k12 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k13 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k14 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k15 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k16 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k22 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k23 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k24 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k25 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k26 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k33 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k34 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k35 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k36 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k44 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k45 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k46 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k55 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k56 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%k66 = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + i1_l = LBOUND(OutData%DirCos,1) + i1_u = UBOUND(OutData%DirCos,1) + i2_l = LBOUND(OutData%DirCos,2) + i2_u = UBOUND(OutData%DirCos,2) + DO i2 = LBOUND(OutData%DirCos,2), UBOUND(OutData%DirCos,2) + DO i1 = LBOUND(OutData%DirCos,1), UBOUND(OutData%DirCos,1) + OutData%DirCos(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END SUBROUTINE SD_UnPackElemPropType + + SUBROUTINE SD_CopyInitInput( SrcInitInputData, DstInitInputData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_InitInputType), INTENT(INOUT) :: SrcInitInputData + TYPE(SD_InitInputType), INTENT(INOUT) :: DstInitInputData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitInput' +! + ErrStat = ErrID_None + ErrMsg = "" + DstInitInputData%SDInputFile = SrcInitInputData%SDInputFile + DstInitInputData%RootName = SrcInitInputData%RootName + DstInitInputData%g = SrcInitInputData%g + DstInitInputData%WtrDpth = SrcInitInputData%WtrDpth + DstInitInputData%TP_RefPoint = SrcInitInputData%TP_RefPoint + DstInitInputData%SubRotateZ = SrcInitInputData%SubRotateZ +IF (ALLOCATED(SrcInitInputData%SoilStiffness)) THEN + i1_l = LBOUND(SrcInitInputData%SoilStiffness,1) + i1_u = UBOUND(SrcInitInputData%SoilStiffness,1) + i2_l = LBOUND(SrcInitInputData%SoilStiffness,2) + i2_u = UBOUND(SrcInitInputData%SoilStiffness,2) + i3_l = LBOUND(SrcInitInputData%SoilStiffness,3) + i3_u = UBOUND(SrcInitInputData%SoilStiffness,3) + IF (.NOT. ALLOCATED(DstInitInputData%SoilStiffness)) THEN + ALLOCATE(DstInitInputData%SoilStiffness(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitInputData%SoilStiffness.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitInputData%SoilStiffness = SrcInitInputData%SoilStiffness +ENDIF + CALL MeshCopy( SrcInitInputData%SoilMesh, DstInitInputData%SoilMesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + DstInitInputData%Linearize = SrcInitInputData%Linearize + END SUBROUTINE SD_CopyInitInput + + SUBROUTINE SD_DestroyInitInput( InitInputData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_InitInputType), INTENT(INOUT) :: InitInputData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitInput' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(InitInputData%SoilStiffness)) THEN + DEALLOCATE(InitInputData%SoilStiffness) +ENDIF + CALL MeshDestroy( InitInputData%SoilMesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + END SUBROUTINE SD_DestroyInitInput + + SUBROUTINE SD_PackInitInput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_InitInputType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitInput' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1*LEN(InData%SDInputFile) ! SDInputFile + Int_BufSz = Int_BufSz + 1*LEN(InData%RootName) ! RootName + Re_BufSz = Re_BufSz + 1 ! g + Re_BufSz = Re_BufSz + 1 ! WtrDpth + Re_BufSz = Re_BufSz + SIZE(InData%TP_RefPoint) ! TP_RefPoint + Re_BufSz = Re_BufSz + 1 ! SubRotateZ + Int_BufSz = Int_BufSz + 1 ! SoilStiffness allocated yes/no + IF ( ALLOCATED(InData%SoilStiffness) ) THEN + Int_BufSz = Int_BufSz + 2*3 ! SoilStiffness upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%SoilStiffness) ! SoilStiffness + END IF + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + Int_BufSz = Int_BufSz + 3 ! SoilMesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! SoilMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! SoilMesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! SoilMesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! SoilMesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 1 ! Linearize + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + DO I = 1, LEN(InData%SDInputFile) + IntKiBuf(Int_Xferred) = ICHAR(InData%SDInputFile(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(InData%RootName) + IntKiBuf(Int_Xferred) = ICHAR(InData%RootName(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + ReKiBuf(Re_Xferred) = InData%g + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%WtrDpth + Re_Xferred = Re_Xferred + 1 + DO i1 = LBOUND(InData%TP_RefPoint,1), UBOUND(InData%TP_RefPoint,1) + ReKiBuf(Re_Xferred) = InData%TP_RefPoint(i1) + Re_Xferred = Re_Xferred + 1 + END DO + ReKiBuf(Re_Xferred) = InData%SubRotateZ + Re_Xferred = Re_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%SoilStiffness) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,2) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SoilStiffness,3) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SoilStiffness,3) + Int_Xferred = Int_Xferred + 2 + + DO i3 = LBOUND(InData%SoilStiffness,3), UBOUND(InData%SoilStiffness,3) + DO i2 = LBOUND(InData%SoilStiffness,2), UBOUND(InData%SoilStiffness,2) + DO i1 = LBOUND(InData%SoilStiffness,1), UBOUND(InData%SoilStiffness,1) + ReKiBuf(Re_Xferred) = InData%SoilStiffness(i1,i2,i3) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END DO + END IF + CALL MeshPack( InData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! SoilMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IntKiBuf(Int_Xferred) = TRANSFER(InData%Linearize, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_PackInitInput + + SUBROUTINE SD_UnPackInitInput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_InitInputType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitInput' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + DO I = 1, LEN(OutData%SDInputFile) + OutData%SDInputFile(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(OutData%RootName) + OutData%RootName(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + OutData%g = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%WtrDpth = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + i1_l = LBOUND(OutData%TP_RefPoint,1) + i1_u = UBOUND(OutData%TP_RefPoint,1) + DO i1 = LBOUND(OutData%TP_RefPoint,1), UBOUND(OutData%TP_RefPoint,1) + OutData%TP_RefPoint(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + OutData%SubRotateZ = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SoilStiffness not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i3_l = IntKiBuf( Int_Xferred ) + i3_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SoilStiffness)) DEALLOCATE(OutData%SoilStiffness) + ALLOCATE(OutData%SoilStiffness(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SoilStiffness.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i3 = LBOUND(OutData%SoilStiffness,3), UBOUND(OutData%SoilStiffness,3) + DO i2 = LBOUND(OutData%SoilStiffness,2), UBOUND(OutData%SoilStiffness,2) + DO i1 = LBOUND(OutData%SoilStiffness,1), UBOUND(OutData%SoilStiffness,1) + OutData%SoilStiffness(i1,i2,i3) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END DO + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%SoilMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! SoilMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + OutData%Linearize = TRANSFER(IntKiBuf(Int_Xferred), OutData%Linearize) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_UnPackInitInput + + SUBROUTINE SD_CopyInitOutput( SrcInitOutputData, DstInitOutputData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_InitOutputType), INTENT(IN) :: SrcInitOutputData + TYPE(SD_InitOutputType), INTENT(INOUT) :: DstInitOutputData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitOutput' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcInitOutputData%WriteOutputHdr)) THEN + i1_l = LBOUND(SrcInitOutputData%WriteOutputHdr,1) + i1_u = UBOUND(SrcInitOutputData%WriteOutputHdr,1) + IF (.NOT. ALLOCATED(DstInitOutputData%WriteOutputHdr)) THEN + ALLOCATE(DstInitOutputData%WriteOutputHdr(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%WriteOutputHdr.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%WriteOutputHdr = SrcInitOutputData%WriteOutputHdr +ENDIF +IF (ALLOCATED(SrcInitOutputData%WriteOutputUnt)) THEN + i1_l = LBOUND(SrcInitOutputData%WriteOutputUnt,1) + i1_u = UBOUND(SrcInitOutputData%WriteOutputUnt,1) + IF (.NOT. ALLOCATED(DstInitOutputData%WriteOutputUnt)) THEN + ALLOCATE(DstInitOutputData%WriteOutputUnt(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%WriteOutputUnt.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%WriteOutputUnt = SrcInitOutputData%WriteOutputUnt +ENDIF + CALL NWTC_Library_Copyprogdesc( SrcInitOutputData%Ver, DstInitOutputData%Ver, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN +IF (ALLOCATED(SrcInitOutputData%LinNames_y)) THEN + i1_l = LBOUND(SrcInitOutputData%LinNames_y,1) + i1_u = UBOUND(SrcInitOutputData%LinNames_y,1) + IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_y)) THEN + ALLOCATE(DstInitOutputData%LinNames_y(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_y.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%LinNames_y = SrcInitOutputData%LinNames_y +ENDIF +IF (ALLOCATED(SrcInitOutputData%LinNames_x)) THEN + i1_l = LBOUND(SrcInitOutputData%LinNames_x,1) + i1_u = UBOUND(SrcInitOutputData%LinNames_x,1) + IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_x)) THEN + ALLOCATE(DstInitOutputData%LinNames_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%LinNames_x = SrcInitOutputData%LinNames_x +ENDIF +IF (ALLOCATED(SrcInitOutputData%LinNames_u)) THEN + i1_l = LBOUND(SrcInitOutputData%LinNames_u,1) + i1_u = UBOUND(SrcInitOutputData%LinNames_u,1) + IF (.NOT. ALLOCATED(DstInitOutputData%LinNames_u)) THEN + ALLOCATE(DstInitOutputData%LinNames_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%LinNames_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%LinNames_u = SrcInitOutputData%LinNames_u +ENDIF +IF (ALLOCATED(SrcInitOutputData%RotFrame_y)) THEN + i1_l = LBOUND(SrcInitOutputData%RotFrame_y,1) + i1_u = UBOUND(SrcInitOutputData%RotFrame_y,1) + IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_y)) THEN + ALLOCATE(DstInitOutputData%RotFrame_y(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_y.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%RotFrame_y = SrcInitOutputData%RotFrame_y +ENDIF +IF (ALLOCATED(SrcInitOutputData%RotFrame_x)) THEN + i1_l = LBOUND(SrcInitOutputData%RotFrame_x,1) + i1_u = UBOUND(SrcInitOutputData%RotFrame_x,1) + IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_x)) THEN + ALLOCATE(DstInitOutputData%RotFrame_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%RotFrame_x = SrcInitOutputData%RotFrame_x +ENDIF +IF (ALLOCATED(SrcInitOutputData%RotFrame_u)) THEN + i1_l = LBOUND(SrcInitOutputData%RotFrame_u,1) + i1_u = UBOUND(SrcInitOutputData%RotFrame_u,1) + IF (.NOT. ALLOCATED(DstInitOutputData%RotFrame_u)) THEN + ALLOCATE(DstInitOutputData%RotFrame_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%RotFrame_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%RotFrame_u = SrcInitOutputData%RotFrame_u +ENDIF +IF (ALLOCATED(SrcInitOutputData%IsLoad_u)) THEN + i1_l = LBOUND(SrcInitOutputData%IsLoad_u,1) + i1_u = UBOUND(SrcInitOutputData%IsLoad_u,1) + IF (.NOT. ALLOCATED(DstInitOutputData%IsLoad_u)) THEN + ALLOCATE(DstInitOutputData%IsLoad_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%IsLoad_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%IsLoad_u = SrcInitOutputData%IsLoad_u +ENDIF +IF (ALLOCATED(SrcInitOutputData%DerivOrder_x)) THEN + i1_l = LBOUND(SrcInitOutputData%DerivOrder_x,1) + i1_u = UBOUND(SrcInitOutputData%DerivOrder_x,1) + IF (.NOT. ALLOCATED(DstInitOutputData%DerivOrder_x)) THEN + ALLOCATE(DstInitOutputData%DerivOrder_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%DerivOrder_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%DerivOrder_x = SrcInitOutputData%DerivOrder_x +ENDIF +IF (ALLOCATED(SrcInitOutputData%CableCChanRqst)) THEN + i1_l = LBOUND(SrcInitOutputData%CableCChanRqst,1) + i1_u = UBOUND(SrcInitOutputData%CableCChanRqst,1) + IF (.NOT. ALLOCATED(DstInitOutputData%CableCChanRqst)) THEN + ALLOCATE(DstInitOutputData%CableCChanRqst(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitOutputData%CableCChanRqst.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitOutputData%CableCChanRqst = SrcInitOutputData%CableCChanRqst +ENDIF + END SUBROUTINE SD_CopyInitOutput + + SUBROUTINE SD_DestroyInitOutput( InitOutputData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_InitOutputType), INTENT(INOUT) :: InitOutputData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitOutput' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(InitOutputData%WriteOutputHdr)) THEN + DEALLOCATE(InitOutputData%WriteOutputHdr) +ENDIF +IF (ALLOCATED(InitOutputData%WriteOutputUnt)) THEN + DEALLOCATE(InitOutputData%WriteOutputUnt) +ENDIF + CALL NWTC_Library_Destroyprogdesc( InitOutputData%Ver, ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +IF (ALLOCATED(InitOutputData%LinNames_y)) THEN + DEALLOCATE(InitOutputData%LinNames_y) +ENDIF +IF (ALLOCATED(InitOutputData%LinNames_x)) THEN + DEALLOCATE(InitOutputData%LinNames_x) +ENDIF +IF (ALLOCATED(InitOutputData%LinNames_u)) THEN + DEALLOCATE(InitOutputData%LinNames_u) +ENDIF +IF (ALLOCATED(InitOutputData%RotFrame_y)) THEN + DEALLOCATE(InitOutputData%RotFrame_y) +ENDIF +IF (ALLOCATED(InitOutputData%RotFrame_x)) THEN + DEALLOCATE(InitOutputData%RotFrame_x) +ENDIF +IF (ALLOCATED(InitOutputData%RotFrame_u)) THEN + DEALLOCATE(InitOutputData%RotFrame_u) +ENDIF +IF (ALLOCATED(InitOutputData%IsLoad_u)) THEN + DEALLOCATE(InitOutputData%IsLoad_u) +ENDIF +IF (ALLOCATED(InitOutputData%DerivOrder_x)) THEN + DEALLOCATE(InitOutputData%DerivOrder_x) +ENDIF +IF (ALLOCATED(InitOutputData%CableCChanRqst)) THEN + DEALLOCATE(InitOutputData%CableCChanRqst) +ENDIF + END SUBROUTINE SD_DestroyInitOutput + + SUBROUTINE SD_PackInitOutput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_InitOutputType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitOutput' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! WriteOutputHdr allocated yes/no + IF ( ALLOCATED(InData%WriteOutputHdr) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! WriteOutputHdr upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%WriteOutputHdr)*LEN(InData%WriteOutputHdr) ! WriteOutputHdr + END IF + Int_BufSz = Int_BufSz + 1 ! WriteOutputUnt allocated yes/no + IF ( ALLOCATED(InData%WriteOutputUnt) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! WriteOutputUnt upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%WriteOutputUnt)*LEN(InData%WriteOutputUnt) ! WriteOutputUnt + END IF + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + Int_BufSz = Int_BufSz + 3 ! Ver: size of buffers for each call to pack subtype + CALL NWTC_Library_Packprogdesc( Re_Buf, Db_Buf, Int_Buf, InData%Ver, ErrStat2, ErrMsg2, .TRUE. ) ! Ver + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! Ver + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! Ver + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! Ver + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 1 ! LinNames_y allocated yes/no + IF ( ALLOCATED(InData%LinNames_y) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! LinNames_y upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%LinNames_y)*LEN(InData%LinNames_y) ! LinNames_y + END IF + Int_BufSz = Int_BufSz + 1 ! LinNames_x allocated yes/no + IF ( ALLOCATED(InData%LinNames_x) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! LinNames_x upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%LinNames_x)*LEN(InData%LinNames_x) ! LinNames_x + END IF + Int_BufSz = Int_BufSz + 1 ! LinNames_u allocated yes/no + IF ( ALLOCATED(InData%LinNames_u) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! LinNames_u upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%LinNames_u)*LEN(InData%LinNames_u) ! LinNames_u + END IF + Int_BufSz = Int_BufSz + 1 ! RotFrame_y allocated yes/no + IF ( ALLOCATED(InData%RotFrame_y) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! RotFrame_y upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_y) ! RotFrame_y + END IF + Int_BufSz = Int_BufSz + 1 ! RotFrame_x allocated yes/no + IF ( ALLOCATED(InData%RotFrame_x) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! RotFrame_x upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_x) ! RotFrame_x + END IF + Int_BufSz = Int_BufSz + 1 ! RotFrame_u allocated yes/no + IF ( ALLOCATED(InData%RotFrame_u) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! RotFrame_u upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%RotFrame_u) ! RotFrame_u + END IF + Int_BufSz = Int_BufSz + 1 ! IsLoad_u allocated yes/no + IF ( ALLOCATED(InData%IsLoad_u) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IsLoad_u upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IsLoad_u) ! IsLoad_u + END IF + Int_BufSz = Int_BufSz + 1 ! DerivOrder_x allocated yes/no + IF ( ALLOCATED(InData%DerivOrder_x) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! DerivOrder_x upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%DerivOrder_x) ! DerivOrder_x + END IF + Int_BufSz = Int_BufSz + 1 ! CableCChanRqst allocated yes/no + IF ( ALLOCATED(InData%CableCChanRqst) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! CableCChanRqst upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%CableCChanRqst) ! CableCChanRqst + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%WriteOutputHdr) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutputHdr,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutputHdr,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%WriteOutputHdr,1), UBOUND(InData%WriteOutputHdr,1) + DO I = 1, LEN(InData%WriteOutputHdr) + IntKiBuf(Int_Xferred) = ICHAR(InData%WriteOutputHdr(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( .NOT. ALLOCATED(InData%WriteOutputUnt) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutputUnt,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutputUnt,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%WriteOutputUnt,1), UBOUND(InData%WriteOutputUnt,1) + DO I = 1, LEN(InData%WriteOutputUnt) + IntKiBuf(Int_Xferred) = ICHAR(InData%WriteOutputUnt(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + CALL NWTC_Library_Packprogdesc( Re_Buf, Db_Buf, Int_Buf, InData%Ver, ErrStat2, ErrMsg2, OnlySize ) ! Ver + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF ( .NOT. ALLOCATED(InData%LinNames_y) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_y,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_y,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%LinNames_y,1), UBOUND(InData%LinNames_y,1) + DO I = 1, LEN(InData%LinNames_y) + IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_y(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( .NOT. ALLOCATED(InData%LinNames_x) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_x,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_x,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%LinNames_x,1), UBOUND(InData%LinNames_x,1) + DO I = 1, LEN(InData%LinNames_x) + IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_x(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( .NOT. ALLOCATED(InData%LinNames_u) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%LinNames_u,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%LinNames_u,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%LinNames_u,1), UBOUND(InData%LinNames_u,1) + DO I = 1, LEN(InData%LinNames_u) + IntKiBuf(Int_Xferred) = ICHAR(InData%LinNames_u(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( .NOT. ALLOCATED(InData%RotFrame_y) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_y,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_y,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%RotFrame_y,1), UBOUND(InData%RotFrame_y,1) + IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_y(i1), IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%RotFrame_x) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_x,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_x,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%RotFrame_x,1), UBOUND(InData%RotFrame_x,1) + IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_x(i1), IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%RotFrame_u) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%RotFrame_u,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%RotFrame_u,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%RotFrame_u,1), UBOUND(InData%RotFrame_u,1) + IntKiBuf(Int_Xferred) = TRANSFER(InData%RotFrame_u(i1), IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IsLoad_u) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IsLoad_u,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IsLoad_u,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IsLoad_u,1), UBOUND(InData%IsLoad_u,1) + IntKiBuf(Int_Xferred) = TRANSFER(InData%IsLoad_u(i1), IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%DerivOrder_x) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DerivOrder_x,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DerivOrder_x,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%DerivOrder_x,1), UBOUND(InData%DerivOrder_x,1) + IntKiBuf(Int_Xferred) = InData%DerivOrder_x(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CableCChanRqst) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CableCChanRqst,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CableCChanRqst,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%CableCChanRqst,1), UBOUND(InData%CableCChanRqst,1) + IntKiBuf(Int_Xferred) = TRANSFER(InData%CableCChanRqst(i1), IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackInitOutput + + SUBROUTINE SD_UnPackInitOutput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_InitOutputType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitOutput' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutputHdr not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%WriteOutputHdr)) DEALLOCATE(OutData%WriteOutputHdr) + ALLOCATE(OutData%WriteOutputHdr(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutputHdr.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%WriteOutputHdr,1), UBOUND(OutData%WriteOutputHdr,1) + DO I = 1, LEN(OutData%WriteOutputHdr) + OutData%WriteOutputHdr(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutputUnt not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%WriteOutputUnt)) DEALLOCATE(OutData%WriteOutputUnt) + ALLOCATE(OutData%WriteOutputUnt(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutputUnt.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%WriteOutputUnt,1), UBOUND(OutData%WriteOutputUnt,1) + DO I = 1, LEN(OutData%WriteOutputUnt) + OutData%WriteOutputUnt(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL NWTC_Library_Unpackprogdesc( Re_Buf, Db_Buf, Int_Buf, OutData%Ver, ErrStat2, ErrMsg2 ) ! Ver + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_y not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%LinNames_y)) DEALLOCATE(OutData%LinNames_y) + ALLOCATE(OutData%LinNames_y(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_y.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%LinNames_y,1), UBOUND(OutData%LinNames_y,1) + DO I = 1, LEN(OutData%LinNames_y) + OutData%LinNames_y(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_x not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%LinNames_x)) DEALLOCATE(OutData%LinNames_x) + ALLOCATE(OutData%LinNames_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%LinNames_x,1), UBOUND(OutData%LinNames_x,1) + DO I = 1, LEN(OutData%LinNames_x) + OutData%LinNames_x(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! LinNames_u not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%LinNames_u)) DEALLOCATE(OutData%LinNames_u) + ALLOCATE(OutData%LinNames_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%LinNames_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%LinNames_u,1), UBOUND(OutData%LinNames_u,1) + DO I = 1, LEN(OutData%LinNames_u) + OutData%LinNames_u(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_y not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%RotFrame_y)) DEALLOCATE(OutData%RotFrame_y) + ALLOCATE(OutData%RotFrame_y(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_y.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%RotFrame_y,1), UBOUND(OutData%RotFrame_y,1) + OutData%RotFrame_y(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_y(i1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_x not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%RotFrame_x)) DEALLOCATE(OutData%RotFrame_x) + ALLOCATE(OutData%RotFrame_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%RotFrame_x,1), UBOUND(OutData%RotFrame_x,1) + OutData%RotFrame_x(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_x(i1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! RotFrame_u not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%RotFrame_u)) DEALLOCATE(OutData%RotFrame_u) + ALLOCATE(OutData%RotFrame_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%RotFrame_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%RotFrame_u,1), UBOUND(OutData%RotFrame_u,1) + OutData%RotFrame_u(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotFrame_u(i1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IsLoad_u not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IsLoad_u)) DEALLOCATE(OutData%IsLoad_u) + ALLOCATE(OutData%IsLoad_u(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IsLoad_u.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IsLoad_u,1), UBOUND(OutData%IsLoad_u,1) + OutData%IsLoad_u(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%IsLoad_u(i1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DerivOrder_x not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%DerivOrder_x)) DEALLOCATE(OutData%DerivOrder_x) + ALLOCATE(OutData%DerivOrder_x(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DerivOrder_x.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%DerivOrder_x,1), UBOUND(OutData%DerivOrder_x,1) + OutData%DerivOrder_x(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CableCChanRqst not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CableCChanRqst)) DEALLOCATE(OutData%CableCChanRqst) + ALLOCATE(OutData%CableCChanRqst(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CableCChanRqst.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%CableCChanRqst,1), UBOUND(OutData%CableCChanRqst,1) + OutData%CableCChanRqst(i1) = TRANSFER(IntKiBuf(Int_Xferred), OutData%CableCChanRqst(i1)) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackInitOutput + + SUBROUTINE SD_CopyInitType( SrcInitTypeData, DstInitTypeData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_InitType), INTENT(IN) :: SrcInitTypeData + TYPE(SD_InitType), INTENT(INOUT) :: DstInitTypeData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInitType' +! + ErrStat = ErrID_None + ErrMsg = "" + DstInitTypeData%RootName = SrcInitTypeData%RootName + DstInitTypeData%TP_RefPoint = SrcInitTypeData%TP_RefPoint + DstInitTypeData%SubRotateZ = SrcInitTypeData%SubRotateZ + DstInitTypeData%g = SrcInitTypeData%g + DstInitTypeData%DT = SrcInitTypeData%DT + DstInitTypeData%NJoints = SrcInitTypeData%NJoints + DstInitTypeData%NPropSetsX = SrcInitTypeData%NPropSetsX + DstInitTypeData%NPropSetsB = SrcInitTypeData%NPropSetsB + DstInitTypeData%NPropSetsC = SrcInitTypeData%NPropSetsC + DstInitTypeData%NPropSetsR = SrcInitTypeData%NPropSetsR + DstInitTypeData%NPropSetsS = SrcInitTypeData%NPropSetsS + DstInitTypeData%NCMass = SrcInitTypeData%NCMass + DstInitTypeData%NCOSMs = SrcInitTypeData%NCOSMs + DstInitTypeData%FEMMod = SrcInitTypeData%FEMMod + DstInitTypeData%NDiv = SrcInitTypeData%NDiv + DstInitTypeData%CBMod = SrcInitTypeData%CBMod +IF (ALLOCATED(SrcInitTypeData%Joints)) THEN + i1_l = LBOUND(SrcInitTypeData%Joints,1) + i1_u = UBOUND(SrcInitTypeData%Joints,1) + i2_l = LBOUND(SrcInitTypeData%Joints,2) + i2_u = UBOUND(SrcInitTypeData%Joints,2) + IF (.NOT. ALLOCATED(DstInitTypeData%Joints)) THEN + ALLOCATE(DstInitTypeData%Joints(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Joints.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Joints = SrcInitTypeData%Joints +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsB)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsB,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsB,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsB,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsB,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsB)) THEN + ALLOCATE(DstInitTypeData%PropSetsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsB = SrcInitTypeData%PropSetsB +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsC)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsC,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsC,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsC,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsC,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsC)) THEN + ALLOCATE(DstInitTypeData%PropSetsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsC.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsC = SrcInitTypeData%PropSetsC +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsR)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsR,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsR,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsR,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsR,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsR)) THEN + ALLOCATE(DstInitTypeData%PropSetsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsR = SrcInitTypeData%PropSetsR +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsS)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsS,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsS,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsS,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsS,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsS)) THEN + ALLOCATE(DstInitTypeData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsS = SrcInitTypeData%PropSetsS +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropSetsX)) THEN + i1_l = LBOUND(SrcInitTypeData%PropSetsX,1) + i1_u = UBOUND(SrcInitTypeData%PropSetsX,1) + i2_l = LBOUND(SrcInitTypeData%PropSetsX,2) + i2_u = UBOUND(SrcInitTypeData%PropSetsX,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropSetsX)) THEN + ALLOCATE(DstInitTypeData%PropSetsX(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropSetsX.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropSetsX = SrcInitTypeData%PropSetsX +ENDIF +IF (ALLOCATED(SrcInitTypeData%COSMs)) THEN + i1_l = LBOUND(SrcInitTypeData%COSMs,1) + i1_u = UBOUND(SrcInitTypeData%COSMs,1) + i2_l = LBOUND(SrcInitTypeData%COSMs,2) + i2_u = UBOUND(SrcInitTypeData%COSMs,2) + IF (.NOT. ALLOCATED(DstInitTypeData%COSMs)) THEN + ALLOCATE(DstInitTypeData%COSMs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%COSMs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%COSMs = SrcInitTypeData%COSMs +ENDIF +IF (ALLOCATED(SrcInitTypeData%CMass)) THEN + i1_l = LBOUND(SrcInitTypeData%CMass,1) + i1_u = UBOUND(SrcInitTypeData%CMass,1) + i2_l = LBOUND(SrcInitTypeData%CMass,2) + i2_u = UBOUND(SrcInitTypeData%CMass,2) + IF (.NOT. ALLOCATED(DstInitTypeData%CMass)) THEN + ALLOCATE(DstInitTypeData%CMass(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%CMass.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%CMass = SrcInitTypeData%CMass +ENDIF +IF (ALLOCATED(SrcInitTypeData%JDampings)) THEN + i1_l = LBOUND(SrcInitTypeData%JDampings,1) + i1_u = UBOUND(SrcInitTypeData%JDampings,1) + IF (.NOT. ALLOCATED(DstInitTypeData%JDampings)) THEN + ALLOCATE(DstInitTypeData%JDampings(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%JDampings.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%JDampings = SrcInitTypeData%JDampings +ENDIF + DstInitTypeData%GuyanDampMod = SrcInitTypeData%GuyanDampMod + DstInitTypeData%RayleighDamp = SrcInitTypeData%RayleighDamp + DstInitTypeData%GuyanDampMat = SrcInitTypeData%GuyanDampMat +IF (ALLOCATED(SrcInitTypeData%Members)) THEN + i1_l = LBOUND(SrcInitTypeData%Members,1) + i1_u = UBOUND(SrcInitTypeData%Members,1) + i2_l = LBOUND(SrcInitTypeData%Members,2) + i2_u = UBOUND(SrcInitTypeData%Members,2) + IF (.NOT. ALLOCATED(DstInitTypeData%Members)) THEN + ALLOCATE(DstInitTypeData%Members(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Members.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Members = SrcInitTypeData%Members +ENDIF +IF (ALLOCATED(SrcInitTypeData%SSOutList)) THEN + i1_l = LBOUND(SrcInitTypeData%SSOutList,1) + i1_u = UBOUND(SrcInitTypeData%SSOutList,1) + IF (.NOT. ALLOCATED(DstInitTypeData%SSOutList)) THEN + ALLOCATE(DstInitTypeData%SSOutList(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSOutList.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%SSOutList = SrcInitTypeData%SSOutList +ENDIF + DstInitTypeData%OutCOSM = SrcInitTypeData%OutCOSM + DstInitTypeData%TabDelim = SrcInitTypeData%TabDelim +IF (ALLOCATED(SrcInitTypeData%SSIK)) THEN + i1_l = LBOUND(SrcInitTypeData%SSIK,1) + i1_u = UBOUND(SrcInitTypeData%SSIK,1) + i2_l = LBOUND(SrcInitTypeData%SSIK,2) + i2_u = UBOUND(SrcInitTypeData%SSIK,2) + IF (.NOT. ALLOCATED(DstInitTypeData%SSIK)) THEN + ALLOCATE(DstInitTypeData%SSIK(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIK.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%SSIK = SrcInitTypeData%SSIK +ENDIF +IF (ALLOCATED(SrcInitTypeData%SSIM)) THEN + i1_l = LBOUND(SrcInitTypeData%SSIM,1) + i1_u = UBOUND(SrcInitTypeData%SSIM,1) + i2_l = LBOUND(SrcInitTypeData%SSIM,2) + i2_u = UBOUND(SrcInitTypeData%SSIM,2) + IF (.NOT. ALLOCATED(DstInitTypeData%SSIM)) THEN + ALLOCATE(DstInitTypeData%SSIM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%SSIM = SrcInitTypeData%SSIM +ENDIF +IF (ALLOCATED(SrcInitTypeData%SSIfile)) THEN + i1_l = LBOUND(SrcInitTypeData%SSIfile,1) + i1_u = UBOUND(SrcInitTypeData%SSIfile,1) + IF (.NOT. ALLOCATED(DstInitTypeData%SSIfile)) THEN + ALLOCATE(DstInitTypeData%SSIfile(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%SSIfile.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%SSIfile = SrcInitTypeData%SSIfile +ENDIF +IF (ALLOCATED(SrcInitTypeData%Soil_K)) THEN + i1_l = LBOUND(SrcInitTypeData%Soil_K,1) + i1_u = UBOUND(SrcInitTypeData%Soil_K,1) + i2_l = LBOUND(SrcInitTypeData%Soil_K,2) + i2_u = UBOUND(SrcInitTypeData%Soil_K,2) + i3_l = LBOUND(SrcInitTypeData%Soil_K,3) + i3_u = UBOUND(SrcInitTypeData%Soil_K,3) + IF (.NOT. ALLOCATED(DstInitTypeData%Soil_K)) THEN + ALLOCATE(DstInitTypeData%Soil_K(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_K.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Soil_K = SrcInitTypeData%Soil_K +ENDIF +IF (ALLOCATED(SrcInitTypeData%Soil_Points)) THEN + i1_l = LBOUND(SrcInitTypeData%Soil_Points,1) + i1_u = UBOUND(SrcInitTypeData%Soil_Points,1) + i2_l = LBOUND(SrcInitTypeData%Soil_Points,2) + i2_u = UBOUND(SrcInitTypeData%Soil_Points,2) + IF (.NOT. ALLOCATED(DstInitTypeData%Soil_Points)) THEN + ALLOCATE(DstInitTypeData%Soil_Points(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_Points.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Soil_Points = SrcInitTypeData%Soil_Points +ENDIF +IF (ALLOCATED(SrcInitTypeData%Soil_Nodes)) THEN + i1_l = LBOUND(SrcInitTypeData%Soil_Nodes,1) + i1_u = UBOUND(SrcInitTypeData%Soil_Nodes,1) + IF (.NOT. ALLOCATED(DstInitTypeData%Soil_Nodes)) THEN + ALLOCATE(DstInitTypeData%Soil_Nodes(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Soil_Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Soil_Nodes = SrcInitTypeData%Soil_Nodes +ENDIF + DstInitTypeData%NElem = SrcInitTypeData%NElem + DstInitTypeData%NPropB = SrcInitTypeData%NPropB + DstInitTypeData%NPropC = SrcInitTypeData%NPropC + DstInitTypeData%NPropR = SrcInitTypeData%NPropR + DstInitTypeData%NPropS = SrcInitTypeData%NPropS +IF (ALLOCATED(SrcInitTypeData%Nodes)) THEN + i1_l = LBOUND(SrcInitTypeData%Nodes,1) + i1_u = UBOUND(SrcInitTypeData%Nodes,1) + i2_l = LBOUND(SrcInitTypeData%Nodes,2) + i2_u = UBOUND(SrcInitTypeData%Nodes,2) + IF (.NOT. ALLOCATED(DstInitTypeData%Nodes)) THEN + ALLOCATE(DstInitTypeData%Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%Nodes = SrcInitTypeData%Nodes +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropsB)) THEN + i1_l = LBOUND(SrcInitTypeData%PropsB,1) + i1_u = UBOUND(SrcInitTypeData%PropsB,1) + i2_l = LBOUND(SrcInitTypeData%PropsB,2) + i2_u = UBOUND(SrcInitTypeData%PropsB,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropsB)) THEN + ALLOCATE(DstInitTypeData%PropsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropsB = SrcInitTypeData%PropsB +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropsC)) THEN + i1_l = LBOUND(SrcInitTypeData%PropsC,1) + i1_u = UBOUND(SrcInitTypeData%PropsC,1) + i2_l = LBOUND(SrcInitTypeData%PropsC,2) + i2_u = UBOUND(SrcInitTypeData%PropsC,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropsC)) THEN + ALLOCATE(DstInitTypeData%PropsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsC.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropsC = SrcInitTypeData%PropsC +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropsR)) THEN + i1_l = LBOUND(SrcInitTypeData%PropsR,1) + i1_u = UBOUND(SrcInitTypeData%PropsR,1) + i2_l = LBOUND(SrcInitTypeData%PropsR,2) + i2_u = UBOUND(SrcInitTypeData%PropsR,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropsR)) THEN + ALLOCATE(DstInitTypeData%PropsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropsR = SrcInitTypeData%PropsR +ENDIF +IF (ALLOCATED(SrcInitTypeData%PropsS)) THEN + i1_l = LBOUND(SrcInitTypeData%PropsS,1) + i1_u = UBOUND(SrcInitTypeData%PropsS,1) + i2_l = LBOUND(SrcInitTypeData%PropsS,2) + i2_u = UBOUND(SrcInitTypeData%PropsS,2) + IF (.NOT. ALLOCATED(DstInitTypeData%PropsS)) THEN + ALLOCATE(DstInitTypeData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%PropsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%PropsS = SrcInitTypeData%PropsS +ENDIF +IF (ALLOCATED(SrcInitTypeData%K)) THEN + i1_l = LBOUND(SrcInitTypeData%K,1) + i1_u = UBOUND(SrcInitTypeData%K,1) + i2_l = LBOUND(SrcInitTypeData%K,2) + i2_u = UBOUND(SrcInitTypeData%K,2) + IF (.NOT. ALLOCATED(DstInitTypeData%K)) THEN + ALLOCATE(DstInitTypeData%K(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%K.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%K = SrcInitTypeData%K +ENDIF +IF (ALLOCATED(SrcInitTypeData%M)) THEN + i1_l = LBOUND(SrcInitTypeData%M,1) + i1_u = UBOUND(SrcInitTypeData%M,1) + i2_l = LBOUND(SrcInitTypeData%M,2) + i2_u = UBOUND(SrcInitTypeData%M,2) + IF (.NOT. ALLOCATED(DstInitTypeData%M)) THEN + ALLOCATE(DstInitTypeData%M(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%M.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%M = SrcInitTypeData%M +ENDIF +IF (ALLOCATED(SrcInitTypeData%ElemProps)) THEN + i1_l = LBOUND(SrcInitTypeData%ElemProps,1) + i1_u = UBOUND(SrcInitTypeData%ElemProps,1) + i2_l = LBOUND(SrcInitTypeData%ElemProps,2) + i2_u = UBOUND(SrcInitTypeData%ElemProps,2) + IF (.NOT. ALLOCATED(DstInitTypeData%ElemProps)) THEN + ALLOCATE(DstInitTypeData%ElemProps(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%ElemProps.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%ElemProps = SrcInitTypeData%ElemProps +ENDIF +IF (ALLOCATED(SrcInitTypeData%MemberNodes)) THEN + i1_l = LBOUND(SrcInitTypeData%MemberNodes,1) + i1_u = UBOUND(SrcInitTypeData%MemberNodes,1) + i2_l = LBOUND(SrcInitTypeData%MemberNodes,2) + i2_u = UBOUND(SrcInitTypeData%MemberNodes,2) + IF (.NOT. ALLOCATED(DstInitTypeData%MemberNodes)) THEN + ALLOCATE(DstInitTypeData%MemberNodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%MemberNodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%MemberNodes = SrcInitTypeData%MemberNodes +ENDIF +IF (ALLOCATED(SrcInitTypeData%NodesConnN)) THEN + i1_l = LBOUND(SrcInitTypeData%NodesConnN,1) + i1_u = UBOUND(SrcInitTypeData%NodesConnN,1) + i2_l = LBOUND(SrcInitTypeData%NodesConnN,2) + i2_u = UBOUND(SrcInitTypeData%NodesConnN,2) + IF (.NOT. ALLOCATED(DstInitTypeData%NodesConnN)) THEN + ALLOCATE(DstInitTypeData%NodesConnN(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%NodesConnN.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%NodesConnN = SrcInitTypeData%NodesConnN +ENDIF +IF (ALLOCATED(SrcInitTypeData%NodesConnE)) THEN + i1_l = LBOUND(SrcInitTypeData%NodesConnE,1) + i1_u = UBOUND(SrcInitTypeData%NodesConnE,1) + i2_l = LBOUND(SrcInitTypeData%NodesConnE,2) + i2_u = UBOUND(SrcInitTypeData%NodesConnE,2) + IF (.NOT. ALLOCATED(DstInitTypeData%NodesConnE)) THEN + ALLOCATE(DstInitTypeData%NodesConnE(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInitTypeData%NodesConnE.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInitTypeData%NodesConnE = SrcInitTypeData%NodesConnE +ENDIF + DstInitTypeData%SSSum = SrcInitTypeData%SSSum + END SUBROUTINE SD_CopyInitType + + SUBROUTINE SD_DestroyInitType( InitTypeData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_InitType), INTENT(INOUT) :: InitTypeData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInitType' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(InitTypeData%Joints)) THEN + DEALLOCATE(InitTypeData%Joints) +ENDIF +IF (ALLOCATED(InitTypeData%PropSetsB)) THEN + DEALLOCATE(InitTypeData%PropSetsB) +ENDIF +IF (ALLOCATED(InitTypeData%PropSetsC)) THEN + DEALLOCATE(InitTypeData%PropSetsC) +ENDIF +IF (ALLOCATED(InitTypeData%PropSetsR)) THEN + DEALLOCATE(InitTypeData%PropSetsR) +ENDIF +IF (ALLOCATED(InitTypeData%PropSetsS)) THEN + DEALLOCATE(InitTypeData%PropSetsS) +ENDIF +IF (ALLOCATED(InitTypeData%PropSetsX)) THEN + DEALLOCATE(InitTypeData%PropSetsX) +ENDIF +IF (ALLOCATED(InitTypeData%COSMs)) THEN + DEALLOCATE(InitTypeData%COSMs) +ENDIF +IF (ALLOCATED(InitTypeData%CMass)) THEN + DEALLOCATE(InitTypeData%CMass) +ENDIF +IF (ALLOCATED(InitTypeData%JDampings)) THEN + DEALLOCATE(InitTypeData%JDampings) +ENDIF +IF (ALLOCATED(InitTypeData%Members)) THEN + DEALLOCATE(InitTypeData%Members) +ENDIF +IF (ALLOCATED(InitTypeData%SSOutList)) THEN + DEALLOCATE(InitTypeData%SSOutList) +ENDIF +IF (ALLOCATED(InitTypeData%SSIK)) THEN + DEALLOCATE(InitTypeData%SSIK) +ENDIF +IF (ALLOCATED(InitTypeData%SSIM)) THEN + DEALLOCATE(InitTypeData%SSIM) +ENDIF +IF (ALLOCATED(InitTypeData%SSIfile)) THEN + DEALLOCATE(InitTypeData%SSIfile) +ENDIF +IF (ALLOCATED(InitTypeData%Soil_K)) THEN + DEALLOCATE(InitTypeData%Soil_K) +ENDIF +IF (ALLOCATED(InitTypeData%Soil_Points)) THEN + DEALLOCATE(InitTypeData%Soil_Points) +ENDIF +IF (ALLOCATED(InitTypeData%Soil_Nodes)) THEN + DEALLOCATE(InitTypeData%Soil_Nodes) +ENDIF +IF (ALLOCATED(InitTypeData%Nodes)) THEN + DEALLOCATE(InitTypeData%Nodes) +ENDIF +IF (ALLOCATED(InitTypeData%PropsB)) THEN + DEALLOCATE(InitTypeData%PropsB) +ENDIF +IF (ALLOCATED(InitTypeData%PropsC)) THEN + DEALLOCATE(InitTypeData%PropsC) +ENDIF +IF (ALLOCATED(InitTypeData%PropsR)) THEN + DEALLOCATE(InitTypeData%PropsR) +ENDIF +IF (ALLOCATED(InitTypeData%PropsS)) THEN + DEALLOCATE(InitTypeData%PropsS) +ENDIF +IF (ALLOCATED(InitTypeData%K)) THEN + DEALLOCATE(InitTypeData%K) +ENDIF +IF (ALLOCATED(InitTypeData%M)) THEN + DEALLOCATE(InitTypeData%M) +ENDIF +IF (ALLOCATED(InitTypeData%ElemProps)) THEN + DEALLOCATE(InitTypeData%ElemProps) +ENDIF +IF (ALLOCATED(InitTypeData%MemberNodes)) THEN + DEALLOCATE(InitTypeData%MemberNodes) +ENDIF +IF (ALLOCATED(InitTypeData%NodesConnN)) THEN + DEALLOCATE(InitTypeData%NodesConnN) +ENDIF +IF (ALLOCATED(InitTypeData%NodesConnE)) THEN + DEALLOCATE(InitTypeData%NodesConnE) +ENDIF + END SUBROUTINE SD_DestroyInitType + + SUBROUTINE SD_PackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_InitType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInitType' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1*LEN(InData%RootName) ! RootName + Re_BufSz = Re_BufSz + SIZE(InData%TP_RefPoint) ! TP_RefPoint + Re_BufSz = Re_BufSz + 1 ! SubRotateZ + Re_BufSz = Re_BufSz + 1 ! g + Db_BufSz = Db_BufSz + 1 ! DT + Int_BufSz = Int_BufSz + 1 ! NJoints + Int_BufSz = Int_BufSz + 1 ! NPropSetsX + Int_BufSz = Int_BufSz + 1 ! NPropSetsB + Int_BufSz = Int_BufSz + 1 ! NPropSetsC + Int_BufSz = Int_BufSz + 1 ! NPropSetsR + Int_BufSz = Int_BufSz + 1 ! NPropSetsS + Int_BufSz = Int_BufSz + 1 ! NCMass + Int_BufSz = Int_BufSz + 1 ! NCOSMs + Int_BufSz = Int_BufSz + 1 ! FEMMod + Int_BufSz = Int_BufSz + 1 ! NDiv + Int_BufSz = Int_BufSz + 1 ! CBMod + Int_BufSz = Int_BufSz + 1 ! Joints allocated yes/no + IF ( ALLOCATED(InData%Joints) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Joints upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Joints) ! Joints + END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsB allocated yes/no + IF ( ALLOCATED(InData%PropSetsB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsB) ! PropSetsB + END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsC allocated yes/no + IF ( ALLOCATED(InData%PropSetsC) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsC upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsC) ! PropSetsC + END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsR allocated yes/no + IF ( ALLOCATED(InData%PropSetsR) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsR upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsR) ! PropSetsR + END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsS allocated yes/no + IF ( ALLOCATED(InData%PropSetsS) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsS) ! PropSetsS + END IF + Int_BufSz = Int_BufSz + 1 ! PropSetsX allocated yes/no + IF ( ALLOCATED(InData%PropSetsX) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropSetsX upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropSetsX) ! PropSetsX + END IF + Int_BufSz = Int_BufSz + 1 ! COSMs allocated yes/no + IF ( ALLOCATED(InData%COSMs) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! COSMs upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%COSMs) ! COSMs + END IF + Int_BufSz = Int_BufSz + 1 ! CMass allocated yes/no + IF ( ALLOCATED(InData%CMass) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! CMass upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%CMass) ! CMass + END IF + Int_BufSz = Int_BufSz + 1 ! JDampings allocated yes/no + IF ( ALLOCATED(InData%JDampings) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! JDampings upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%JDampings) ! JDampings + END IF + Int_BufSz = Int_BufSz + 1 ! GuyanDampMod + Re_BufSz = Re_BufSz + SIZE(InData%RayleighDamp) ! RayleighDamp + Re_BufSz = Re_BufSz + SIZE(InData%GuyanDampMat) ! GuyanDampMat + Int_BufSz = Int_BufSz + 1 ! Members allocated yes/no + IF ( ALLOCATED(InData%Members) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Members upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Members) ! Members + END IF + Int_BufSz = Int_BufSz + 1 ! SSOutList allocated yes/no + IF ( ALLOCATED(InData%SSOutList) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! SSOutList upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%SSOutList)*LEN(InData%SSOutList) ! SSOutList + END IF + Int_BufSz = Int_BufSz + 1 ! OutCOSM + Int_BufSz = Int_BufSz + 1 ! TabDelim + Int_BufSz = Int_BufSz + 1 ! SSIK allocated yes/no + IF ( ALLOCATED(InData%SSIK) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! SSIK upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%SSIK) ! SSIK + END IF + Int_BufSz = Int_BufSz + 1 ! SSIM allocated yes/no + IF ( ALLOCATED(InData%SSIM) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! SSIM upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%SSIM) ! SSIM + END IF + Int_BufSz = Int_BufSz + 1 ! SSIfile allocated yes/no + IF ( ALLOCATED(InData%SSIfile) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! SSIfile upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%SSIfile)*LEN(InData%SSIfile) ! SSIfile + END IF + Int_BufSz = Int_BufSz + 1 ! Soil_K allocated yes/no + IF ( ALLOCATED(InData%Soil_K) ) THEN + Int_BufSz = Int_BufSz + 2*3 ! Soil_K upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Soil_K) ! Soil_K + END IF + Int_BufSz = Int_BufSz + 1 ! Soil_Points allocated yes/no + IF ( ALLOCATED(InData%Soil_Points) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Soil_Points upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Soil_Points) ! Soil_Points + END IF + Int_BufSz = Int_BufSz + 1 ! Soil_Nodes allocated yes/no + IF ( ALLOCATED(InData%Soil_Nodes) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! Soil_Nodes upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Soil_Nodes) ! Soil_Nodes + END IF + Int_BufSz = Int_BufSz + 1 ! NElem + Int_BufSz = Int_BufSz + 1 ! NPropB + Int_BufSz = Int_BufSz + 1 ! NPropC + Int_BufSz = Int_BufSz + 1 ! NPropR + Int_BufSz = Int_BufSz + 1 ! NPropS + Int_BufSz = Int_BufSz + 1 ! Nodes allocated yes/no + IF ( ALLOCATED(InData%Nodes) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Nodes upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Nodes) ! Nodes + END IF + Int_BufSz = Int_BufSz + 1 ! PropsB allocated yes/no + IF ( ALLOCATED(InData%PropsB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropsB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropsB) ! PropsB + END IF + Int_BufSz = Int_BufSz + 1 ! PropsC allocated yes/no + IF ( ALLOCATED(InData%PropsC) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropsC upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropsC) ! PropsC + END IF + Int_BufSz = Int_BufSz + 1 ! PropsR allocated yes/no + IF ( ALLOCATED(InData%PropsR) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropsR upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropsR) ! PropsR + END IF + Int_BufSz = Int_BufSz + 1 ! PropsS allocated yes/no + IF ( ALLOCATED(InData%PropsS) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PropsS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PropsS) ! PropsS + END IF + Int_BufSz = Int_BufSz + 1 ! K allocated yes/no + IF ( ALLOCATED(InData%K) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! K upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%K) ! K + END IF + Int_BufSz = Int_BufSz + 1 ! M allocated yes/no + IF ( ALLOCATED(InData%M) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! M upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%M) ! M + END IF + Int_BufSz = Int_BufSz + 1 ! ElemProps allocated yes/no + IF ( ALLOCATED(InData%ElemProps) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! ElemProps upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%ElemProps) ! ElemProps + END IF + Int_BufSz = Int_BufSz + 1 ! MemberNodes allocated yes/no + IF ( ALLOCATED(InData%MemberNodes) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MemberNodes upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%MemberNodes) ! MemberNodes + END IF + Int_BufSz = Int_BufSz + 1 ! NodesConnN allocated yes/no + IF ( ALLOCATED(InData%NodesConnN) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! NodesConnN upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%NodesConnN) ! NodesConnN + END IF + Int_BufSz = Int_BufSz + 1 ! NodesConnE allocated yes/no + IF ( ALLOCATED(InData%NodesConnE) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! NodesConnE upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%NodesConnE) ! NodesConnE + END IF + Int_BufSz = Int_BufSz + 1 ! SSSum + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + DO I = 1, LEN(InData%RootName) + IntKiBuf(Int_Xferred) = ICHAR(InData%RootName(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO i1 = LBOUND(InData%TP_RefPoint,1), UBOUND(InData%TP_RefPoint,1) + ReKiBuf(Re_Xferred) = InData%TP_RefPoint(i1) + Re_Xferred = Re_Xferred + 1 + END DO + ReKiBuf(Re_Xferred) = InData%SubRotateZ + Re_Xferred = Re_Xferred + 1 + ReKiBuf(Re_Xferred) = InData%g + Re_Xferred = Re_Xferred + 1 + DbKiBuf(Db_Xferred) = InData%DT + Db_Xferred = Db_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NJoints + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsX + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsB + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsC + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsR + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropSetsS + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NCMass + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NCOSMs + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%FEMMod + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NDiv + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%CBMod, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Joints) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Joints,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Joints,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Joints,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Joints,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Joints,2), UBOUND(InData%Joints,2) + DO i1 = LBOUND(InData%Joints,1), UBOUND(InData%Joints,1) + ReKiBuf(Re_Xferred) = InData%Joints(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropSetsB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsB,2), UBOUND(InData%PropSetsB,2) + DO i1 = LBOUND(InData%PropSetsB,1), UBOUND(InData%PropSetsB,1) + ReKiBuf(Re_Xferred) = InData%PropSetsB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropSetsC) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsC,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsC,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsC,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsC,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsC,2), UBOUND(InData%PropSetsC,2) + DO i1 = LBOUND(InData%PropSetsC,1), UBOUND(InData%PropSetsC,1) + ReKiBuf(Re_Xferred) = InData%PropSetsC(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropSetsR) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsR,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsR,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsR,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsR,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsR,2), UBOUND(InData%PropSetsR,2) + DO i1 = LBOUND(InData%PropSetsR,1), UBOUND(InData%PropSetsR,1) + ReKiBuf(Re_Xferred) = InData%PropSetsR(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropSetsS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsS,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsS,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsS,2), UBOUND(InData%PropSetsS,2) + DO i1 = LBOUND(InData%PropSetsS,1), UBOUND(InData%PropSetsS,1) + ReKiBuf(Re_Xferred) = InData%PropSetsS(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropSetsX) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsX,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsX,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropSetsX,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropSetsX,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropSetsX,2), UBOUND(InData%PropSetsX,2) + DO i1 = LBOUND(InData%PropSetsX,1), UBOUND(InData%PropSetsX,1) + ReKiBuf(Re_Xferred) = InData%PropSetsX(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%COSMs) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%COSMs,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%COSMs,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%COSMs,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%COSMs,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%COSMs,2), UBOUND(InData%COSMs,2) + DO i1 = LBOUND(InData%COSMs,1), UBOUND(InData%COSMs,1) + DbKiBuf(Db_Xferred) = InData%COSMs(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CMass) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CMass,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMass,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CMass,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMass,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%CMass,2), UBOUND(InData%CMass,2) + DO i1 = LBOUND(InData%CMass,1), UBOUND(InData%CMass,1) + ReKiBuf(Re_Xferred) = InData%CMass(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%JDampings) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%JDampings,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%JDampings,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%JDampings,1), UBOUND(InData%JDampings,1) + ReKiBuf(Re_Xferred) = InData%JDampings(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IntKiBuf(Int_Xferred) = InData%GuyanDampMod + Int_Xferred = Int_Xferred + 1 + DO i1 = LBOUND(InData%RayleighDamp,1), UBOUND(InData%RayleighDamp,1) + ReKiBuf(Re_Xferred) = InData%RayleighDamp(i1) + Re_Xferred = Re_Xferred + 1 + END DO + DO i2 = LBOUND(InData%GuyanDampMat,2), UBOUND(InData%GuyanDampMat,2) + DO i1 = LBOUND(InData%GuyanDampMat,1), UBOUND(InData%GuyanDampMat,1) + ReKiBuf(Re_Xferred) = InData%GuyanDampMat(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + IF ( .NOT. ALLOCATED(InData%Members) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Members,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Members,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Members,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Members,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Members,2), UBOUND(InData%Members,2) + DO i1 = LBOUND(InData%Members,1), UBOUND(InData%Members,1) + IntKiBuf(Int_Xferred) = InData%Members(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%SSOutList) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSOutList,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSOutList,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%SSOutList,1), UBOUND(InData%SSOutList,1) + DO I = 1, LEN(InData%SSOutList) + IntKiBuf(Int_Xferred) = ICHAR(InData%SSOutList(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IntKiBuf(Int_Xferred) = TRANSFER(InData%OutCOSM, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%TabDelim, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%SSIK) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIK,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIK,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIK,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIK,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%SSIK,2), UBOUND(InData%SSIK,2) + DO i1 = LBOUND(InData%SSIK,1), UBOUND(InData%SSIK,1) + DbKiBuf(Db_Xferred) = InData%SSIK(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%SSIM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIM,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIM,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIM,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%SSIM,2), UBOUND(InData%SSIM,2) + DO i1 = LBOUND(InData%SSIM,1), UBOUND(InData%SSIM,1) + DbKiBuf(Db_Xferred) = InData%SSIM(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%SSIfile) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SSIfile,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SSIfile,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%SSIfile,1), UBOUND(InData%SSIfile,1) + DO I = 1, LEN(InData%SSIfile) + IntKiBuf(Int_Xferred) = ICHAR(InData%SSIfile(i1)(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Soil_K) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,2) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_K,3) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_K,3) + Int_Xferred = Int_Xferred + 2 + + DO i3 = LBOUND(InData%Soil_K,3), UBOUND(InData%Soil_K,3) + DO i2 = LBOUND(InData%Soil_K,2), UBOUND(InData%Soil_K,2) + DO i1 = LBOUND(InData%Soil_K,1), UBOUND(InData%Soil_K,1) + ReKiBuf(Re_Xferred) = InData%Soil_K(i1,i2,i3) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Soil_Points) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Points,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Points,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Points,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Points,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Soil_Points,2), UBOUND(InData%Soil_Points,2) + DO i1 = LBOUND(InData%Soil_Points,1), UBOUND(InData%Soil_Points,1) + ReKiBuf(Re_Xferred) = InData%Soil_Points(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Soil_Nodes) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Soil_Nodes,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Soil_Nodes,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%Soil_Nodes,1), UBOUND(InData%Soil_Nodes,1) + IntKiBuf(Int_Xferred) = InData%Soil_Nodes(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IntKiBuf(Int_Xferred) = InData%NElem + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropB + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropC + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropR + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NPropS + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Nodes) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Nodes,2), UBOUND(InData%Nodes,2) + DO i1 = LBOUND(InData%Nodes,1), UBOUND(InData%Nodes,1) + ReKiBuf(Re_Xferred) = InData%Nodes(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropsB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropsB,2), UBOUND(InData%PropsB,2) + DO i1 = LBOUND(InData%PropsB,1), UBOUND(InData%PropsB,1) + ReKiBuf(Re_Xferred) = InData%PropsB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropsC) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsC,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsC,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsC,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsC,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropsC,2), UBOUND(InData%PropsC,2) + DO i1 = LBOUND(InData%PropsC,1), UBOUND(InData%PropsC,1) + ReKiBuf(Re_Xferred) = InData%PropsC(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropsR) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsR,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsR,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsR,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsR,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropsR,2), UBOUND(InData%PropsR,2) + DO i1 = LBOUND(InData%PropsR,1), UBOUND(InData%PropsR,1) + ReKiBuf(Re_Xferred) = InData%PropsR(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PropsS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PropsS,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PropsS,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PropsS,2), UBOUND(InData%PropsS,2) + DO i1 = LBOUND(InData%PropsS,1), UBOUND(InData%PropsS,1) + ReKiBuf(Re_Xferred) = InData%PropsS(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%K) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%K,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%K,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%K,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%K,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%K,2), UBOUND(InData%K,2) + DO i1 = LBOUND(InData%K,1), UBOUND(InData%K,1) + DbKiBuf(Db_Xferred) = InData%K(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%M) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%M,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%M,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%M,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%M,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%M,2), UBOUND(InData%M,2) + DO i1 = LBOUND(InData%M,1), UBOUND(InData%M,1) + DbKiBuf(Db_Xferred) = InData%M(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ElemProps) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%ElemProps,2), UBOUND(InData%ElemProps,2) + DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) + ReKiBuf(Re_Xferred) = InData%ElemProps(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MemberNodes) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MemberNodes,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MemberNodes,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MemberNodes,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MemberNodes,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MemberNodes,2), UBOUND(InData%MemberNodes,2) + DO i1 = LBOUND(InData%MemberNodes,1), UBOUND(InData%MemberNodes,1) + IntKiBuf(Int_Xferred) = InData%MemberNodes(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodesConnN) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnN,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnN,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnN,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnN,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%NodesConnN,2), UBOUND(InData%NodesConnN,2) + DO i1 = LBOUND(InData%NodesConnN,1), UBOUND(InData%NodesConnN,1) + IntKiBuf(Int_Xferred) = InData%NodesConnN(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodesConnE) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnE,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnE,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesConnE,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesConnE,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%NodesConnE,2), UBOUND(InData%NodesConnE,2) + DO i1 = LBOUND(InData%NodesConnE,1), UBOUND(InData%NodesConnE,1) + IntKiBuf(Int_Xferred) = InData%NodesConnE(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IntKiBuf(Int_Xferred) = TRANSFER(InData%SSSum, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_PackInitType + + SUBROUTINE SD_UnPackInitType( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_InitType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: i3, i3_l, i3_u ! bounds (upper/lower) for an array dimension 3 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInitType' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + DO I = 1, LEN(OutData%RootName) + OutData%RootName(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + i1_l = LBOUND(OutData%TP_RefPoint,1) + i1_u = UBOUND(OutData%TP_RefPoint,1) + DO i1 = LBOUND(OutData%TP_RefPoint,1), UBOUND(OutData%TP_RefPoint,1) + OutData%TP_RefPoint(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + OutData%SubRotateZ = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%g = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + OutData%DT = DbKiBuf(Db_Xferred) + Db_Xferred = Db_Xferred + 1 + OutData%NJoints = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsX = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsB = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsC = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsR = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropSetsS = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NCMass = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NCOSMs = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%FEMMod = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NDiv = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%CBMod = TRANSFER(IntKiBuf(Int_Xferred), OutData%CBMod) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Joints not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Joints)) DEALLOCATE(OutData%Joints) + ALLOCATE(OutData%Joints(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Joints.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Joints,2), UBOUND(OutData%Joints,2) + DO i1 = LBOUND(OutData%Joints,1), UBOUND(OutData%Joints,1) + OutData%Joints(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsB)) DEALLOCATE(OutData%PropSetsB) + ALLOCATE(OutData%PropSetsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsB,2), UBOUND(OutData%PropSetsB,2) + DO i1 = LBOUND(OutData%PropSetsB,1), UBOUND(OutData%PropSetsB,1) + OutData%PropSetsB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsC not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsC)) DEALLOCATE(OutData%PropSetsC) + ALLOCATE(OutData%PropSetsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsC.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsC,2), UBOUND(OutData%PropSetsC,2) + DO i1 = LBOUND(OutData%PropSetsC,1), UBOUND(OutData%PropSetsC,1) + OutData%PropSetsC(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsR not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsR)) DEALLOCATE(OutData%PropSetsR) + ALLOCATE(OutData%PropSetsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsR,2), UBOUND(OutData%PropSetsR,2) + DO i1 = LBOUND(OutData%PropSetsR,1), UBOUND(OutData%PropSetsR,1) + OutData%PropSetsR(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsS)) DEALLOCATE(OutData%PropSetsS) + ALLOCATE(OutData%PropSetsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsS,2), UBOUND(OutData%PropSetsS,2) + DO i1 = LBOUND(OutData%PropSetsS,1), UBOUND(OutData%PropSetsS,1) + OutData%PropSetsS(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropSetsX not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropSetsX)) DEALLOCATE(OutData%PropSetsX) + ALLOCATE(OutData%PropSetsX(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropSetsX.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropSetsX,2), UBOUND(OutData%PropSetsX,2) + DO i1 = LBOUND(OutData%PropSetsX,1), UBOUND(OutData%PropSetsX,1) + OutData%PropSetsX(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! COSMs not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%COSMs)) DEALLOCATE(OutData%COSMs) + ALLOCATE(OutData%COSMs(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%COSMs.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%COSMs,2), UBOUND(OutData%COSMs,2) + DO i1 = LBOUND(OutData%COSMs,1), UBOUND(OutData%COSMs,1) + OutData%COSMs(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMass not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CMass)) DEALLOCATE(OutData%CMass) + ALLOCATE(OutData%CMass(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMass.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%CMass,2), UBOUND(OutData%CMass,2) + DO i1 = LBOUND(OutData%CMass,1), UBOUND(OutData%CMass,1) + OutData%CMass(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! JDampings not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%JDampings)) DEALLOCATE(OutData%JDampings) + ALLOCATE(OutData%JDampings(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%JDampings.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%JDampings,1), UBOUND(OutData%JDampings,1) + OutData%JDampings(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + OutData%GuyanDampMod = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + i1_l = LBOUND(OutData%RayleighDamp,1) + i1_u = UBOUND(OutData%RayleighDamp,1) + DO i1 = LBOUND(OutData%RayleighDamp,1), UBOUND(OutData%RayleighDamp,1) + OutData%RayleighDamp(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + i1_l = LBOUND(OutData%GuyanDampMat,1) + i1_u = UBOUND(OutData%GuyanDampMat,1) + i2_l = LBOUND(OutData%GuyanDampMat,2) + i2_u = UBOUND(OutData%GuyanDampMat,2) + DO i2 = LBOUND(OutData%GuyanDampMat,2), UBOUND(OutData%GuyanDampMat,2) + DO i1 = LBOUND(OutData%GuyanDampMat,1), UBOUND(OutData%GuyanDampMat,1) + OutData%GuyanDampMat(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Members not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Members)) DEALLOCATE(OutData%Members) + ALLOCATE(OutData%Members(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Members.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Members,2), UBOUND(OutData%Members,2) + DO i1 = LBOUND(OutData%Members,1), UBOUND(OutData%Members,1) + OutData%Members(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSOutList not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SSOutList)) DEALLOCATE(OutData%SSOutList) + ALLOCATE(OutData%SSOutList(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSOutList.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%SSOutList,1), UBOUND(OutData%SSOutList,1) + DO I = 1, LEN(OutData%SSOutList) + OutData%SSOutList(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + OutData%OutCOSM = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutCOSM) + Int_Xferred = Int_Xferred + 1 + OutData%TabDelim = TRANSFER(IntKiBuf(Int_Xferred), OutData%TabDelim) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIK not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SSIK)) DEALLOCATE(OutData%SSIK) + ALLOCATE(OutData%SSIK(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIK.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%SSIK,2), UBOUND(OutData%SSIK,2) + DO i1 = LBOUND(OutData%SSIK,1), UBOUND(OutData%SSIK,1) + OutData%SSIK(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SSIM)) DEALLOCATE(OutData%SSIM) + ALLOCATE(OutData%SSIM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%SSIM,2), UBOUND(OutData%SSIM,2) + DO i1 = LBOUND(OutData%SSIM,1), UBOUND(OutData%SSIM,1) + OutData%SSIM(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SSIfile not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SSIfile)) DEALLOCATE(OutData%SSIfile) + ALLOCATE(OutData%SSIfile(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SSIfile.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%SSIfile,1), UBOUND(OutData%SSIfile,1) + DO I = 1, LEN(OutData%SSIfile) + OutData%SSIfile(i1)(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_K not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i3_l = IntKiBuf( Int_Xferred ) + i3_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Soil_K)) DEALLOCATE(OutData%Soil_K) + ALLOCATE(OutData%Soil_K(i1_l:i1_u,i2_l:i2_u,i3_l:i3_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_K.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i3 = LBOUND(OutData%Soil_K,3), UBOUND(OutData%Soil_K,3) + DO i2 = LBOUND(OutData%Soil_K,2), UBOUND(OutData%Soil_K,2) + DO i1 = LBOUND(OutData%Soil_K,1), UBOUND(OutData%Soil_K,1) + OutData%Soil_K(i1,i2,i3) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_Points not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Soil_Points)) DEALLOCATE(OutData%Soil_Points) + ALLOCATE(OutData%Soil_Points(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_Points.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Soil_Points,2), UBOUND(OutData%Soil_Points,2) + DO i1 = LBOUND(OutData%Soil_Points,1), UBOUND(OutData%Soil_Points,1) + OutData%Soil_Points(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Soil_Nodes not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Soil_Nodes)) DEALLOCATE(OutData%Soil_Nodes) + ALLOCATE(OutData%Soil_Nodes(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Soil_Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%Soil_Nodes,1), UBOUND(OutData%Soil_Nodes,1) + OutData%Soil_Nodes(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + OutData%NElem = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropB = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropC = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropR = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NPropS = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Nodes)) DEALLOCATE(OutData%Nodes) + ALLOCATE(OutData%Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Nodes,2), UBOUND(OutData%Nodes,2) + DO i1 = LBOUND(OutData%Nodes,1), UBOUND(OutData%Nodes,1) + OutData%Nodes(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropsB)) DEALLOCATE(OutData%PropsB) + ALLOCATE(OutData%PropsB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropsB,2), UBOUND(OutData%PropsB,2) + DO i1 = LBOUND(OutData%PropsB,1), UBOUND(OutData%PropsB,1) + OutData%PropsB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsC not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropsC)) DEALLOCATE(OutData%PropsC) + ALLOCATE(OutData%PropsC(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsC.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropsC,2), UBOUND(OutData%PropsC,2) + DO i1 = LBOUND(OutData%PropsC,1), UBOUND(OutData%PropsC,1) + OutData%PropsC(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsR not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropsR)) DEALLOCATE(OutData%PropsR) + ALLOCATE(OutData%PropsR(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsR.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropsR,2), UBOUND(OutData%PropsR,2) + DO i1 = LBOUND(OutData%PropsR,1), UBOUND(OutData%PropsR,1) + OutData%PropsR(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PropsS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PropsS)) DEALLOCATE(OutData%PropsS) + ALLOCATE(OutData%PropsS(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PropsS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PropsS,2), UBOUND(OutData%PropsS,2) + DO i1 = LBOUND(OutData%PropsS,1), UBOUND(OutData%PropsS,1) + OutData%PropsS(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! K not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%K)) DEALLOCATE(OutData%K) + ALLOCATE(OutData%K(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%K.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%K,2), UBOUND(OutData%K,2) + DO i1 = LBOUND(OutData%K,1), UBOUND(OutData%K,1) + OutData%K(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! M not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%M)) DEALLOCATE(OutData%M) + ALLOCATE(OutData%M(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%M.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%M,2), UBOUND(OutData%M,2) + DO i1 = LBOUND(OutData%M,1), UBOUND(OutData%M,1) + OutData%M(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemProps not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ElemProps)) DEALLOCATE(OutData%ElemProps) + ALLOCATE(OutData%ElemProps(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemProps.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%ElemProps,2), UBOUND(OutData%ElemProps,2) + DO i1 = LBOUND(OutData%ElemProps,1), UBOUND(OutData%ElemProps,1) + OutData%ElemProps(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MemberNodes not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MemberNodes)) DEALLOCATE(OutData%MemberNodes) + ALLOCATE(OutData%MemberNodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MemberNodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MemberNodes,2), UBOUND(OutData%MemberNodes,2) + DO i1 = LBOUND(OutData%MemberNodes,1), UBOUND(OutData%MemberNodes,1) + OutData%MemberNodes(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesConnN not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodesConnN)) DEALLOCATE(OutData%NodesConnN) + ALLOCATE(OutData%NodesConnN(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesConnN.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%NodesConnN,2), UBOUND(OutData%NodesConnN,2) + DO i1 = LBOUND(OutData%NodesConnN,1), UBOUND(OutData%NodesConnN,1) + OutData%NodesConnN(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesConnE not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodesConnE)) DEALLOCATE(OutData%NodesConnE) + ALLOCATE(OutData%NodesConnE(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesConnE.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%NodesConnE,2), UBOUND(OutData%NodesConnE,2) + DO i1 = LBOUND(OutData%NodesConnE,1), UBOUND(OutData%NodesConnE,1) + OutData%NodesConnE(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + OutData%SSSum = TRANSFER(IntKiBuf(Int_Xferred), OutData%SSSum) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_UnPackInitType + + SUBROUTINE SD_CopyContState( SrcContStateData, DstContStateData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_ContinuousStateType), INTENT(IN) :: SrcContStateData + TYPE(SD_ContinuousStateType), INTENT(INOUT) :: DstContStateData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyContState' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcContStateData%qm)) THEN + i1_l = LBOUND(SrcContStateData%qm,1) + i1_u = UBOUND(SrcContStateData%qm,1) + IF (.NOT. ALLOCATED(DstContStateData%qm)) THEN + ALLOCATE(DstContStateData%qm(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstContStateData%qm.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstContStateData%qm = SrcContStateData%qm +ENDIF +IF (ALLOCATED(SrcContStateData%qmdot)) THEN + i1_l = LBOUND(SrcContStateData%qmdot,1) + i1_u = UBOUND(SrcContStateData%qmdot,1) + IF (.NOT. ALLOCATED(DstContStateData%qmdot)) THEN + ALLOCATE(DstContStateData%qmdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstContStateData%qmdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstContStateData%qmdot = SrcContStateData%qmdot +ENDIF + END SUBROUTINE SD_CopyContState + + SUBROUTINE SD_DestroyContState( ContStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_ContinuousStateType), INTENT(INOUT) :: ContStateData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyContState' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(ContStateData%qm)) THEN + DEALLOCATE(ContStateData%qm) +ENDIF +IF (ALLOCATED(ContStateData%qmdot)) THEN + DEALLOCATE(ContStateData%qmdot) +ENDIF + END SUBROUTINE SD_DestroyContState + + SUBROUTINE SD_PackContState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_ContinuousStateType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackContState' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! qm allocated yes/no + IF ( ALLOCATED(InData%qm) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! qm upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%qm) ! qm + END IF + Int_BufSz = Int_BufSz + 1 ! qmdot allocated yes/no + IF ( ALLOCATED(InData%qmdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! qmdot upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%qmdot) ! qmdot + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%qm) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%qm,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qm,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%qm,1), UBOUND(InData%qm,1) + DbKiBuf(Db_Xferred) = InData%qm(i1) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%qmdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%qmdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qmdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%qmdot,1), UBOUND(InData%qmdot,1) + DbKiBuf(Db_Xferred) = InData%qmdot(i1) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackContState + + SUBROUTINE SD_UnPackContState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_ContinuousStateType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackContState' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qm not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%qm)) DEALLOCATE(OutData%qm) + ALLOCATE(OutData%qm(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qm.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%qm,1), UBOUND(OutData%qm,1) + OutData%qm(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qmdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%qmdot)) DEALLOCATE(OutData%qmdot) + ALLOCATE(OutData%qmdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qmdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%qmdot,1), UBOUND(OutData%qmdot,1) + OutData%qmdot(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackContState + + SUBROUTINE SD_CopyDiscState( SrcDiscStateData, DstDiscStateData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_DiscreteStateType), INTENT(IN) :: SrcDiscStateData + TYPE(SD_DiscreteStateType), INTENT(INOUT) :: DstDiscStateData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyDiscState' +! + ErrStat = ErrID_None + ErrMsg = "" + DstDiscStateData%DummyDiscState = SrcDiscStateData%DummyDiscState + END SUBROUTINE SD_CopyDiscState + + SUBROUTINE SD_DestroyDiscState( DiscStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_DiscreteStateType), INTENT(INOUT) :: DiscStateData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyDiscState' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + + END SUBROUTINE SD_DestroyDiscState + + SUBROUTINE SD_PackDiscState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_DiscreteStateType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackDiscState' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Re_BufSz = Re_BufSz + 1 ! DummyDiscState + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + ReKiBuf(Re_Xferred) = InData%DummyDiscState + Re_Xferred = Re_Xferred + 1 + END SUBROUTINE SD_PackDiscState + + SUBROUTINE SD_UnPackDiscState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_DiscreteStateType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackDiscState' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + OutData%DummyDiscState = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END SUBROUTINE SD_UnPackDiscState + + SUBROUTINE SD_CopyConstrState( SrcConstrStateData, DstConstrStateData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_ConstraintStateType), INTENT(IN) :: SrcConstrStateData + TYPE(SD_ConstraintStateType), INTENT(INOUT) :: DstConstrStateData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyConstrState' +! + ErrStat = ErrID_None + ErrMsg = "" + DstConstrStateData%DummyConstrState = SrcConstrStateData%DummyConstrState + END SUBROUTINE SD_CopyConstrState + + SUBROUTINE SD_DestroyConstrState( ConstrStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_ConstraintStateType), INTENT(INOUT) :: ConstrStateData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyConstrState' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + + END SUBROUTINE SD_DestroyConstrState + + SUBROUTINE SD_PackConstrState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_ConstraintStateType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackConstrState' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Re_BufSz = Re_BufSz + 1 ! DummyConstrState + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + ReKiBuf(Re_Xferred) = InData%DummyConstrState + Re_Xferred = Re_Xferred + 1 + END SUBROUTINE SD_PackConstrState + + SUBROUTINE SD_UnPackConstrState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_ConstraintStateType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackConstrState' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + OutData%DummyConstrState = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END SUBROUTINE SD_UnPackConstrState + + SUBROUTINE SD_CopyOtherState( SrcOtherStateData, DstOtherStateData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_OtherStateType), INTENT(IN) :: SrcOtherStateData + TYPE(SD_OtherStateType), INTENT(INOUT) :: DstOtherStateData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyOtherState' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcOtherStateData%xdot)) THEN + i1_l = LBOUND(SrcOtherStateData%xdot,1) + i1_u = UBOUND(SrcOtherStateData%xdot,1) + IF (.NOT. ALLOCATED(DstOtherStateData%xdot)) THEN + ALLOCATE(DstOtherStateData%xdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstOtherStateData%xdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcOtherStateData%xdot,1), UBOUND(SrcOtherStateData%xdot,1) + CALL SD_CopyContState( SrcOtherStateData%xdot(i1), DstOtherStateData%xdot(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF + DstOtherStateData%n = SrcOtherStateData%n + END SUBROUTINE SD_CopyOtherState + + SUBROUTINE SD_DestroyOtherState( OtherStateData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_OtherStateType), INTENT(INOUT) :: OtherStateData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyOtherState' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(OtherStateData%xdot)) THEN +DO i1 = LBOUND(OtherStateData%xdot,1), UBOUND(OtherStateData%xdot,1) + CALL SD_DestroyContState( OtherStateData%xdot(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(OtherStateData%xdot) +ENDIF + END SUBROUTINE SD_DestroyOtherState + + SUBROUTINE SD_PackOtherState( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_OtherStateType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackOtherState' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! xdot allocated yes/no + IF ( ALLOCATED(InData%xdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! xdot upper/lower bounds for each dimension + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + DO i1 = LBOUND(InData%xdot,1), UBOUND(InData%xdot,1) + Int_BufSz = Int_BufSz + 3 ! xdot: size of buffers for each call to pack subtype + CALL SD_PackContState( Re_Buf, Db_Buf, Int_Buf, InData%xdot(i1), ErrStat2, ErrMsg2, .TRUE. ) ! xdot + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! xdot + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! xdot + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! xdot + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! n + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%xdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%xdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%xdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%xdot,1), UBOUND(InData%xdot,1) + CALL SD_PackContState( Re_Buf, Db_Buf, Int_Buf, InData%xdot(i1), ErrStat2, ErrMsg2, OnlySize ) ! xdot + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IntKiBuf(Int_Xferred) = InData%n + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_PackOtherState + + SUBROUTINE SD_UnPackOtherState( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_OtherStateType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackOtherState' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! xdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%xdot)) DEALLOCATE(OutData%xdot) + ALLOCATE(OutData%xdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%xdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%xdot,1), UBOUND(OutData%xdot,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_UnpackContState( Re_Buf, Db_Buf, Int_Buf, OutData%xdot(i1), ErrStat2, ErrMsg2 ) ! xdot + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + OutData%n = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_UnPackOtherState + + SUBROUTINE SD_CopyMisc( SrcMiscData, DstMiscData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_MiscVarType), INTENT(IN) :: SrcMiscData + TYPE(SD_MiscVarType), INTENT(INOUT) :: DstMiscData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyMisc' +! + ErrStat = ErrID_None + ErrMsg = "" +IF (ALLOCATED(SrcMiscData%qmdotdot)) THEN + i1_l = LBOUND(SrcMiscData%qmdotdot,1) + i1_u = UBOUND(SrcMiscData%qmdotdot,1) + IF (.NOT. ALLOCATED(DstMiscData%qmdotdot)) THEN + ALLOCATE(DstMiscData%qmdotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%qmdotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%qmdotdot = SrcMiscData%qmdotdot +ENDIF + DstMiscData%u_TP = SrcMiscData%u_TP + DstMiscData%udot_TP = SrcMiscData%udot_TP + DstMiscData%udotdot_TP = SrcMiscData%udotdot_TP +IF (ALLOCATED(SrcMiscData%F_L)) THEN + i1_l = LBOUND(SrcMiscData%F_L,1) + i1_u = UBOUND(SrcMiscData%F_L,1) + IF (.NOT. ALLOCATED(DstMiscData%F_L)) THEN + ALLOCATE(DstMiscData%F_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%F_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%F_L = SrcMiscData%F_L +ENDIF +IF (ALLOCATED(SrcMiscData%F_L2)) THEN + i1_l = LBOUND(SrcMiscData%F_L2,1) + i1_u = UBOUND(SrcMiscData%F_L2,1) + IF (.NOT. ALLOCATED(DstMiscData%F_L2)) THEN + ALLOCATE(DstMiscData%F_L2(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%F_L2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%F_L2 = SrcMiscData%F_L2 +ENDIF +IF (ALLOCATED(SrcMiscData%UR_bar)) THEN + i1_l = LBOUND(SrcMiscData%UR_bar,1) + i1_u = UBOUND(SrcMiscData%UR_bar,1) + IF (.NOT. ALLOCATED(DstMiscData%UR_bar)) THEN + ALLOCATE(DstMiscData%UR_bar(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UR_bar = SrcMiscData%UR_bar +ENDIF +IF (ALLOCATED(SrcMiscData%UR_bar_dot)) THEN + i1_l = LBOUND(SrcMiscData%UR_bar_dot,1) + i1_u = UBOUND(SrcMiscData%UR_bar_dot,1) + IF (.NOT. ALLOCATED(DstMiscData%UR_bar_dot)) THEN + ALLOCATE(DstMiscData%UR_bar_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UR_bar_dot = SrcMiscData%UR_bar_dot +ENDIF +IF (ALLOCATED(SrcMiscData%UR_bar_dotdot)) THEN + i1_l = LBOUND(SrcMiscData%UR_bar_dotdot,1) + i1_u = UBOUND(SrcMiscData%UR_bar_dotdot,1) + IF (.NOT. ALLOCATED(DstMiscData%UR_bar_dotdot)) THEN + ALLOCATE(DstMiscData%UR_bar_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UR_bar_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UR_bar_dotdot = SrcMiscData%UR_bar_dotdot +ENDIF +IF (ALLOCATED(SrcMiscData%UL)) THEN + i1_l = LBOUND(SrcMiscData%UL,1) + i1_u = UBOUND(SrcMiscData%UL,1) + IF (.NOT. ALLOCATED(DstMiscData%UL)) THEN + ALLOCATE(DstMiscData%UL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL = SrcMiscData%UL +ENDIF +IF (ALLOCATED(SrcMiscData%UL_NS)) THEN + i1_l = LBOUND(SrcMiscData%UL_NS,1) + i1_u = UBOUND(SrcMiscData%UL_NS,1) + IF (.NOT. ALLOCATED(DstMiscData%UL_NS)) THEN + ALLOCATE(DstMiscData%UL_NS(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_NS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL_NS = SrcMiscData%UL_NS +ENDIF +IF (ALLOCATED(SrcMiscData%UL_dot)) THEN + i1_l = LBOUND(SrcMiscData%UL_dot,1) + i1_u = UBOUND(SrcMiscData%UL_dot,1) + IF (.NOT. ALLOCATED(DstMiscData%UL_dot)) THEN + ALLOCATE(DstMiscData%UL_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL_dot = SrcMiscData%UL_dot +ENDIF +IF (ALLOCATED(SrcMiscData%UL_dotdot)) THEN + i1_l = LBOUND(SrcMiscData%UL_dotdot,1) + i1_u = UBOUND(SrcMiscData%UL_dotdot,1) + IF (.NOT. ALLOCATED(DstMiscData%UL_dotdot)) THEN + ALLOCATE(DstMiscData%UL_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL_dotdot = SrcMiscData%UL_dotdot +ENDIF +IF (ALLOCATED(SrcMiscData%DU_full)) THEN + i1_l = LBOUND(SrcMiscData%DU_full,1) + i1_u = UBOUND(SrcMiscData%DU_full,1) + IF (.NOT. ALLOCATED(DstMiscData%DU_full)) THEN + ALLOCATE(DstMiscData%DU_full(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%DU_full.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%DU_full = SrcMiscData%DU_full +ENDIF +IF (ALLOCATED(SrcMiscData%U_full)) THEN + i1_l = LBOUND(SrcMiscData%U_full,1) + i1_u = UBOUND(SrcMiscData%U_full,1) + IF (.NOT. ALLOCATED(DstMiscData%U_full)) THEN + ALLOCATE(DstMiscData%U_full(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_full = SrcMiscData%U_full +ENDIF +IF (ALLOCATED(SrcMiscData%U_full_NS)) THEN + i1_l = LBOUND(SrcMiscData%U_full_NS,1) + i1_u = UBOUND(SrcMiscData%U_full_NS,1) + IF (.NOT. ALLOCATED(DstMiscData%U_full_NS)) THEN + ALLOCATE(DstMiscData%U_full_NS(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_NS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_full_NS = SrcMiscData%U_full_NS +ENDIF +IF (ALLOCATED(SrcMiscData%U_full_dot)) THEN + i1_l = LBOUND(SrcMiscData%U_full_dot,1) + i1_u = UBOUND(SrcMiscData%U_full_dot,1) + IF (.NOT. ALLOCATED(DstMiscData%U_full_dot)) THEN + ALLOCATE(DstMiscData%U_full_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_full_dot = SrcMiscData%U_full_dot +ENDIF +IF (ALLOCATED(SrcMiscData%U_full_dotdot)) THEN + i1_l = LBOUND(SrcMiscData%U_full_dotdot,1) + i1_u = UBOUND(SrcMiscData%U_full_dotdot,1) + IF (.NOT. ALLOCATED(DstMiscData%U_full_dotdot)) THEN + ALLOCATE(DstMiscData%U_full_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_full_dotdot = SrcMiscData%U_full_dotdot +ENDIF +IF (ALLOCATED(SrcMiscData%U_full_elast)) THEN + i1_l = LBOUND(SrcMiscData%U_full_elast,1) + i1_u = UBOUND(SrcMiscData%U_full_elast,1) + IF (.NOT. ALLOCATED(DstMiscData%U_full_elast)) THEN + ALLOCATE(DstMiscData%U_full_elast(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_full_elast.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_full_elast = SrcMiscData%U_full_elast +ENDIF +IF (ALLOCATED(SrcMiscData%U_red)) THEN + i1_l = LBOUND(SrcMiscData%U_red,1) + i1_u = UBOUND(SrcMiscData%U_red,1) + IF (.NOT. ALLOCATED(DstMiscData%U_red)) THEN + ALLOCATE(DstMiscData%U_red(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%U_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%U_red = SrcMiscData%U_red +ENDIF +IF (ALLOCATED(SrcMiscData%FC_unit)) THEN + i1_l = LBOUND(SrcMiscData%FC_unit,1) + i1_u = UBOUND(SrcMiscData%FC_unit,1) + IF (.NOT. ALLOCATED(DstMiscData%FC_unit)) THEN + ALLOCATE(DstMiscData%FC_unit(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%FC_unit.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%FC_unit = SrcMiscData%FC_unit +ENDIF +IF (ALLOCATED(SrcMiscData%SDWrOutput)) THEN + i1_l = LBOUND(SrcMiscData%SDWrOutput,1) + i1_u = UBOUND(SrcMiscData%SDWrOutput,1) + IF (.NOT. ALLOCATED(DstMiscData%SDWrOutput)) THEN + ALLOCATE(DstMiscData%SDWrOutput(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%SDWrOutput.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%SDWrOutput = SrcMiscData%SDWrOutput +ENDIF +IF (ALLOCATED(SrcMiscData%AllOuts)) THEN + i1_l = LBOUND(SrcMiscData%AllOuts,1) + i1_u = UBOUND(SrcMiscData%AllOuts,1) + IF (.NOT. ALLOCATED(DstMiscData%AllOuts)) THEN + ALLOCATE(DstMiscData%AllOuts(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%AllOuts.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%AllOuts = SrcMiscData%AllOuts +ENDIF + DstMiscData%LastOutTime = SrcMiscData%LastOutTime + DstMiscData%Decimat = SrcMiscData%Decimat +IF (ALLOCATED(SrcMiscData%Fext)) THEN + i1_l = LBOUND(SrcMiscData%Fext,1) + i1_u = UBOUND(SrcMiscData%Fext,1) + IF (.NOT. ALLOCATED(DstMiscData%Fext)) THEN + ALLOCATE(DstMiscData%Fext(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%Fext.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%Fext = SrcMiscData%Fext +ENDIF +IF (ALLOCATED(SrcMiscData%Fext_red)) THEN + i1_l = LBOUND(SrcMiscData%Fext_red,1) + i1_u = UBOUND(SrcMiscData%Fext_red,1) + IF (.NOT. ALLOCATED(DstMiscData%Fext_red)) THEN + ALLOCATE(DstMiscData%Fext_red(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%Fext_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%Fext_red = SrcMiscData%Fext_red +ENDIF +IF (ALLOCATED(SrcMiscData%UL_SIM)) THEN + i1_l = LBOUND(SrcMiscData%UL_SIM,1) + i1_u = UBOUND(SrcMiscData%UL_SIM,1) + IF (.NOT. ALLOCATED(DstMiscData%UL_SIM)) THEN + ALLOCATE(DstMiscData%UL_SIM(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_SIM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL_SIM = SrcMiscData%UL_SIM +ENDIF +IF (ALLOCATED(SrcMiscData%UL_0m)) THEN + i1_l = LBOUND(SrcMiscData%UL_0m,1) + i1_u = UBOUND(SrcMiscData%UL_0m,1) + IF (.NOT. ALLOCATED(DstMiscData%UL_0m)) THEN + ALLOCATE(DstMiscData%UL_0m(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstMiscData%UL_0m.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstMiscData%UL_0m = SrcMiscData%UL_0m +ENDIF + END SUBROUTINE SD_CopyMisc + + SUBROUTINE SD_DestroyMisc( MiscData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_MiscVarType), INTENT(INOUT) :: MiscData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyMisc' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(MiscData%qmdotdot)) THEN + DEALLOCATE(MiscData%qmdotdot) +ENDIF +IF (ALLOCATED(MiscData%F_L)) THEN + DEALLOCATE(MiscData%F_L) +ENDIF +IF (ALLOCATED(MiscData%F_L2)) THEN + DEALLOCATE(MiscData%F_L2) +ENDIF +IF (ALLOCATED(MiscData%UR_bar)) THEN + DEALLOCATE(MiscData%UR_bar) +ENDIF +IF (ALLOCATED(MiscData%UR_bar_dot)) THEN + DEALLOCATE(MiscData%UR_bar_dot) +ENDIF +IF (ALLOCATED(MiscData%UR_bar_dotdot)) THEN + DEALLOCATE(MiscData%UR_bar_dotdot) +ENDIF +IF (ALLOCATED(MiscData%UL)) THEN + DEALLOCATE(MiscData%UL) +ENDIF +IF (ALLOCATED(MiscData%UL_NS)) THEN + DEALLOCATE(MiscData%UL_NS) +ENDIF +IF (ALLOCATED(MiscData%UL_dot)) THEN + DEALLOCATE(MiscData%UL_dot) +ENDIF +IF (ALLOCATED(MiscData%UL_dotdot)) THEN + DEALLOCATE(MiscData%UL_dotdot) +ENDIF +IF (ALLOCATED(MiscData%DU_full)) THEN + DEALLOCATE(MiscData%DU_full) +ENDIF +IF (ALLOCATED(MiscData%U_full)) THEN + DEALLOCATE(MiscData%U_full) +ENDIF +IF (ALLOCATED(MiscData%U_full_NS)) THEN + DEALLOCATE(MiscData%U_full_NS) +ENDIF +IF (ALLOCATED(MiscData%U_full_dot)) THEN + DEALLOCATE(MiscData%U_full_dot) +ENDIF +IF (ALLOCATED(MiscData%U_full_dotdot)) THEN + DEALLOCATE(MiscData%U_full_dotdot) +ENDIF +IF (ALLOCATED(MiscData%U_full_elast)) THEN + DEALLOCATE(MiscData%U_full_elast) +ENDIF +IF (ALLOCATED(MiscData%U_red)) THEN + DEALLOCATE(MiscData%U_red) +ENDIF +IF (ALLOCATED(MiscData%FC_unit)) THEN + DEALLOCATE(MiscData%FC_unit) +ENDIF +IF (ALLOCATED(MiscData%SDWrOutput)) THEN + DEALLOCATE(MiscData%SDWrOutput) +ENDIF +IF (ALLOCATED(MiscData%AllOuts)) THEN + DEALLOCATE(MiscData%AllOuts) +ENDIF +IF (ALLOCATED(MiscData%Fext)) THEN + DEALLOCATE(MiscData%Fext) +ENDIF +IF (ALLOCATED(MiscData%Fext_red)) THEN + DEALLOCATE(MiscData%Fext_red) +ENDIF +IF (ALLOCATED(MiscData%UL_SIM)) THEN + DEALLOCATE(MiscData%UL_SIM) +ENDIF +IF (ALLOCATED(MiscData%UL_0m)) THEN + DEALLOCATE(MiscData%UL_0m) +ENDIF + END SUBROUTINE SD_DestroyMisc + + SUBROUTINE SD_PackMisc( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_MiscVarType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackMisc' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Int_BufSz = Int_BufSz + 1 ! qmdotdot allocated yes/no + IF ( ALLOCATED(InData%qmdotdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! qmdotdot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%qmdotdot) ! qmdotdot + END IF + Re_BufSz = Re_BufSz + SIZE(InData%u_TP) ! u_TP + Re_BufSz = Re_BufSz + SIZE(InData%udot_TP) ! udot_TP + Re_BufSz = Re_BufSz + SIZE(InData%udotdot_TP) ! udotdot_TP + Int_BufSz = Int_BufSz + 1 ! F_L allocated yes/no + IF ( ALLOCATED(InData%F_L) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! F_L upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%F_L) ! F_L + END IF + Int_BufSz = Int_BufSz + 1 ! F_L2 allocated yes/no + IF ( ALLOCATED(InData%F_L2) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! F_L2 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%F_L2) ! F_L2 + END IF + Int_BufSz = Int_BufSz + 1 ! UR_bar allocated yes/no + IF ( ALLOCATED(InData%UR_bar) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UR_bar upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UR_bar) ! UR_bar + END IF + Int_BufSz = Int_BufSz + 1 ! UR_bar_dot allocated yes/no + IF ( ALLOCATED(InData%UR_bar_dot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UR_bar_dot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UR_bar_dot) ! UR_bar_dot + END IF + Int_BufSz = Int_BufSz + 1 ! UR_bar_dotdot allocated yes/no + IF ( ALLOCATED(InData%UR_bar_dotdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UR_bar_dotdot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UR_bar_dotdot) ! UR_bar_dotdot + END IF + Int_BufSz = Int_BufSz + 1 ! UL allocated yes/no + IF ( ALLOCATED(InData%UL) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL) ! UL + END IF + Int_BufSz = Int_BufSz + 1 ! UL_NS allocated yes/no + IF ( ALLOCATED(InData%UL_NS) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL_NS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL_NS) ! UL_NS + END IF + Int_BufSz = Int_BufSz + 1 ! UL_dot allocated yes/no + IF ( ALLOCATED(InData%UL_dot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL_dot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL_dot) ! UL_dot + END IF + Int_BufSz = Int_BufSz + 1 ! UL_dotdot allocated yes/no + IF ( ALLOCATED(InData%UL_dotdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL_dotdot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL_dotdot) ! UL_dotdot + END IF + Int_BufSz = Int_BufSz + 1 ! DU_full allocated yes/no + IF ( ALLOCATED(InData%DU_full) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! DU_full upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%DU_full) ! DU_full + END IF + Int_BufSz = Int_BufSz + 1 ! U_full allocated yes/no + IF ( ALLOCATED(InData%U_full) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_full upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_full) ! U_full + END IF + Int_BufSz = Int_BufSz + 1 ! U_full_NS allocated yes/no + IF ( ALLOCATED(InData%U_full_NS) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_full_NS upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_full_NS) ! U_full_NS + END IF + Int_BufSz = Int_BufSz + 1 ! U_full_dot allocated yes/no + IF ( ALLOCATED(InData%U_full_dot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_full_dot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_full_dot) ! U_full_dot + END IF + Int_BufSz = Int_BufSz + 1 ! U_full_dotdot allocated yes/no + IF ( ALLOCATED(InData%U_full_dotdot) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_full_dotdot upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_full_dotdot) ! U_full_dotdot + END IF + Int_BufSz = Int_BufSz + 1 ! U_full_elast allocated yes/no + IF ( ALLOCATED(InData%U_full_elast) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_full_elast upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_full_elast) ! U_full_elast + END IF + Int_BufSz = Int_BufSz + 1 ! U_red allocated yes/no + IF ( ALLOCATED(InData%U_red) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! U_red upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%U_red) ! U_red + END IF + Int_BufSz = Int_BufSz + 1 ! FC_unit allocated yes/no + IF ( ALLOCATED(InData%FC_unit) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! FC_unit upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%FC_unit) ! FC_unit + END IF + Int_BufSz = Int_BufSz + 1 ! SDWrOutput allocated yes/no + IF ( ALLOCATED(InData%SDWrOutput) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! SDWrOutput upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%SDWrOutput) ! SDWrOutput + END IF + Int_BufSz = Int_BufSz + 1 ! AllOuts allocated yes/no + IF ( ALLOCATED(InData%AllOuts) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! AllOuts upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%AllOuts) ! AllOuts + END IF + Db_BufSz = Db_BufSz + 1 ! LastOutTime + Int_BufSz = Int_BufSz + 1 ! Decimat + Int_BufSz = Int_BufSz + 1 ! Fext allocated yes/no + IF ( ALLOCATED(InData%Fext) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! Fext upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Fext) ! Fext + END IF + Int_BufSz = Int_BufSz + 1 ! Fext_red allocated yes/no + IF ( ALLOCATED(InData%Fext_red) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! Fext_red upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%Fext_red) ! Fext_red + END IF + Int_BufSz = Int_BufSz + 1 ! UL_SIM allocated yes/no + IF ( ALLOCATED(InData%UL_SIM) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL_SIM upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL_SIM) ! UL_SIM + END IF + Int_BufSz = Int_BufSz + 1 ! UL_0m allocated yes/no + IF ( ALLOCATED(InData%UL_0m) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! UL_0m upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%UL_0m) ! UL_0m + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + IF ( .NOT. ALLOCATED(InData%qmdotdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%qmdotdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%qmdotdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%qmdotdot,1), UBOUND(InData%qmdotdot,1) + ReKiBuf(Re_Xferred) = InData%qmdotdot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + DO i1 = LBOUND(InData%u_TP,1), UBOUND(InData%u_TP,1) + ReKiBuf(Re_Xferred) = InData%u_TP(i1) + Re_Xferred = Re_Xferred + 1 + END DO + DO i1 = LBOUND(InData%udot_TP,1), UBOUND(InData%udot_TP,1) + ReKiBuf(Re_Xferred) = InData%udot_TP(i1) + Re_Xferred = Re_Xferred + 1 + END DO + DO i1 = LBOUND(InData%udotdot_TP,1), UBOUND(InData%udotdot_TP,1) + ReKiBuf(Re_Xferred) = InData%udotdot_TP(i1) + Re_Xferred = Re_Xferred + 1 + END DO + IF ( .NOT. ALLOCATED(InData%F_L) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%F_L,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%F_L,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%F_L,1), UBOUND(InData%F_L,1) + ReKiBuf(Re_Xferred) = InData%F_L(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%F_L2) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%F_L2,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%F_L2,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%F_L2,1), UBOUND(InData%F_L2,1) + ReKiBuf(Re_Xferred) = InData%F_L2(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UR_bar) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UR_bar,1), UBOUND(InData%UR_bar,1) + ReKiBuf(Re_Xferred) = InData%UR_bar(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UR_bar_dot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar_dot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar_dot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UR_bar_dot,1), UBOUND(InData%UR_bar_dot,1) + ReKiBuf(Re_Xferred) = InData%UR_bar_dot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UR_bar_dotdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UR_bar_dotdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UR_bar_dotdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UR_bar_dotdot,1), UBOUND(InData%UR_bar_dotdot,1) + ReKiBuf(Re_Xferred) = InData%UR_bar_dotdot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL,1), UBOUND(InData%UL,1) + ReKiBuf(Re_Xferred) = InData%UL(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL_NS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_NS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_NS,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL_NS,1), UBOUND(InData%UL_NS,1) + ReKiBuf(Re_Xferred) = InData%UL_NS(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL_dot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_dot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_dot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL_dot,1), UBOUND(InData%UL_dot,1) + ReKiBuf(Re_Xferred) = InData%UL_dot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL_dotdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_dotdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_dotdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL_dotdot,1), UBOUND(InData%UL_dotdot,1) + ReKiBuf(Re_Xferred) = InData%UL_dotdot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%DU_full) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DU_full,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DU_full,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%DU_full,1), UBOUND(InData%DU_full,1) + ReKiBuf(Re_Xferred) = InData%DU_full(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_full) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_full,1), UBOUND(InData%U_full,1) + ReKiBuf(Re_Xferred) = InData%U_full(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_full_NS) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_NS,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_NS,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_full_NS,1), UBOUND(InData%U_full_NS,1) + ReKiBuf(Re_Xferred) = InData%U_full_NS(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_full_dot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_dot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_dot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_full_dot,1), UBOUND(InData%U_full_dot,1) + ReKiBuf(Re_Xferred) = InData%U_full_dot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_full_dotdot) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_dotdot,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_dotdot,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_full_dotdot,1), UBOUND(InData%U_full_dotdot,1) + ReKiBuf(Re_Xferred) = InData%U_full_dotdot(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_full_elast) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_full_elast,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_full_elast,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_full_elast,1), UBOUND(InData%U_full_elast,1) + ReKiBuf(Re_Xferred) = InData%U_full_elast(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%U_red) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%U_red,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%U_red,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%U_red,1), UBOUND(InData%U_red,1) + ReKiBuf(Re_Xferred) = InData%U_red(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%FC_unit) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%FC_unit,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%FC_unit,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%FC_unit,1), UBOUND(InData%FC_unit,1) + ReKiBuf(Re_Xferred) = InData%FC_unit(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%SDWrOutput) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%SDWrOutput,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%SDWrOutput,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%SDWrOutput,1), UBOUND(InData%SDWrOutput,1) + ReKiBuf(Re_Xferred) = InData%SDWrOutput(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%AllOuts) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%AllOuts,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AllOuts,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%AllOuts,1), UBOUND(InData%AllOuts,1) + ReKiBuf(Re_Xferred) = InData%AllOuts(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + DbKiBuf(Db_Xferred) = InData%LastOutTime + Db_Xferred = Db_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%Decimat + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Fext) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Fext,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fext,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%Fext,1), UBOUND(InData%Fext,1) + ReKiBuf(Re_Xferred) = InData%Fext(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Fext_red) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Fext_red,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Fext_red,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%Fext_red,1), UBOUND(InData%Fext_red,1) + ReKiBuf(Re_Xferred) = InData%Fext_red(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL_SIM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_SIM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_SIM,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL_SIM,1), UBOUND(InData%UL_SIM,1) + ReKiBuf(Re_Xferred) = InData%UL_SIM(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%UL_0m) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%UL_0m,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%UL_0m,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%UL_0m,1), UBOUND(InData%UL_0m,1) + ReKiBuf(Re_Xferred) = InData%UL_0m(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackMisc + + SUBROUTINE SD_UnPackMisc( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_MiscVarType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackMisc' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! qmdotdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%qmdotdot)) DEALLOCATE(OutData%qmdotdot) + ALLOCATE(OutData%qmdotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%qmdotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%qmdotdot,1), UBOUND(OutData%qmdotdot,1) + OutData%qmdotdot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + i1_l = LBOUND(OutData%u_TP,1) + i1_u = UBOUND(OutData%u_TP,1) + DO i1 = LBOUND(OutData%u_TP,1), UBOUND(OutData%u_TP,1) + OutData%u_TP(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + i1_l = LBOUND(OutData%udot_TP,1) + i1_u = UBOUND(OutData%udot_TP,1) + DO i1 = LBOUND(OutData%udot_TP,1), UBOUND(OutData%udot_TP,1) + OutData%udot_TP(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + i1_l = LBOUND(OutData%udotdot_TP,1) + i1_u = UBOUND(OutData%udotdot_TP,1) + DO i1 = LBOUND(OutData%udotdot_TP,1), UBOUND(OutData%udotdot_TP,1) + OutData%udotdot_TP(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! F_L not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%F_L)) DEALLOCATE(OutData%F_L) + ALLOCATE(OutData%F_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%F_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%F_L,1), UBOUND(OutData%F_L,1) + OutData%F_L(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! F_L2 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%F_L2)) DEALLOCATE(OutData%F_L2) + ALLOCATE(OutData%F_L2(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%F_L2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%F_L2,1), UBOUND(OutData%F_L2,1) + OutData%F_L2(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UR_bar)) DEALLOCATE(OutData%UR_bar) + ALLOCATE(OutData%UR_bar(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UR_bar,1), UBOUND(OutData%UR_bar,1) + OutData%UR_bar(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar_dot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UR_bar_dot)) DEALLOCATE(OutData%UR_bar_dot) + ALLOCATE(OutData%UR_bar_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UR_bar_dot,1), UBOUND(OutData%UR_bar_dot,1) + OutData%UR_bar_dot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UR_bar_dotdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UR_bar_dotdot)) DEALLOCATE(OutData%UR_bar_dotdot) + ALLOCATE(OutData%UR_bar_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UR_bar_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UR_bar_dotdot,1), UBOUND(OutData%UR_bar_dotdot,1) + OutData%UR_bar_dotdot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL)) DEALLOCATE(OutData%UL) + ALLOCATE(OutData%UL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL,1), UBOUND(OutData%UL,1) + OutData%UL(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_NS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL_NS)) DEALLOCATE(OutData%UL_NS) + ALLOCATE(OutData%UL_NS(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_NS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL_NS,1), UBOUND(OutData%UL_NS,1) + OutData%UL_NS(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_dot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL_dot)) DEALLOCATE(OutData%UL_dot) + ALLOCATE(OutData%UL_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL_dot,1), UBOUND(OutData%UL_dot,1) + OutData%UL_dot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_dotdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL_dotdot)) DEALLOCATE(OutData%UL_dotdot) + ALLOCATE(OutData%UL_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL_dotdot,1), UBOUND(OutData%UL_dotdot,1) + OutData%UL_dotdot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DU_full not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%DU_full)) DEALLOCATE(OutData%DU_full) + ALLOCATE(OutData%DU_full(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DU_full.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%DU_full,1), UBOUND(OutData%DU_full,1) + OutData%DU_full(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_full)) DEALLOCATE(OutData%U_full) + ALLOCATE(OutData%U_full(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_full,1), UBOUND(OutData%U_full,1) + OutData%U_full(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_NS not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_full_NS)) DEALLOCATE(OutData%U_full_NS) + ALLOCATE(OutData%U_full_NS(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_NS.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_full_NS,1), UBOUND(OutData%U_full_NS,1) + OutData%U_full_NS(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_dot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_full_dot)) DEALLOCATE(OutData%U_full_dot) + ALLOCATE(OutData%U_full_dot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_dot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_full_dot,1), UBOUND(OutData%U_full_dot,1) + OutData%U_full_dot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_dotdot not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_full_dotdot)) DEALLOCATE(OutData%U_full_dotdot) + ALLOCATE(OutData%U_full_dotdot(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_dotdot.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_full_dotdot,1), UBOUND(OutData%U_full_dotdot,1) + OutData%U_full_dotdot(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_full_elast not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_full_elast)) DEALLOCATE(OutData%U_full_elast) + ALLOCATE(OutData%U_full_elast(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_full_elast.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_full_elast,1), UBOUND(OutData%U_full_elast,1) + OutData%U_full_elast(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! U_red not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%U_red)) DEALLOCATE(OutData%U_red) + ALLOCATE(OutData%U_red(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%U_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%U_red,1), UBOUND(OutData%U_red,1) + OutData%U_red(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! FC_unit not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%FC_unit)) DEALLOCATE(OutData%FC_unit) + ALLOCATE(OutData%FC_unit(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%FC_unit.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%FC_unit,1), UBOUND(OutData%FC_unit,1) + OutData%FC_unit(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! SDWrOutput not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%SDWrOutput)) DEALLOCATE(OutData%SDWrOutput) + ALLOCATE(OutData%SDWrOutput(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%SDWrOutput.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%SDWrOutput,1), UBOUND(OutData%SDWrOutput,1) + OutData%SDWrOutput(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AllOuts not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%AllOuts)) DEALLOCATE(OutData%AllOuts) + ALLOCATE(OutData%AllOuts(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AllOuts.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%AllOuts,1), UBOUND(OutData%AllOuts,1) + OutData%AllOuts(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + OutData%LastOutTime = DbKiBuf(Db_Xferred) + Db_Xferred = Db_Xferred + 1 + OutData%Decimat = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fext not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Fext)) DEALLOCATE(OutData%Fext) + ALLOCATE(OutData%Fext(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fext.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%Fext,1), UBOUND(OutData%Fext,1) + OutData%Fext(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Fext_red not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Fext_red)) DEALLOCATE(OutData%Fext_red) + ALLOCATE(OutData%Fext_red(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Fext_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%Fext_red,1), UBOUND(OutData%Fext_red,1) + OutData%Fext_red(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_SIM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL_SIM)) DEALLOCATE(OutData%UL_SIM) + ALLOCATE(OutData%UL_SIM(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_SIM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL_SIM,1), UBOUND(OutData%UL_SIM,1) + OutData%UL_SIM(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! UL_0m not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%UL_0m)) DEALLOCATE(OutData%UL_0m) + ALLOCATE(OutData%UL_0m(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%UL_0m.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%UL_0m,1), UBOUND(OutData%UL_0m,1) + OutData%UL_0m(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackMisc + + SUBROUTINE SD_CopyParam( SrcParamData, DstParamData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_ParameterType), INTENT(IN) :: SrcParamData + TYPE(SD_ParameterType), INTENT(INOUT) :: DstParamData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyParam' +! + ErrStat = ErrID_None + ErrMsg = "" + DstParamData%SDDeltaT = SrcParamData%SDDeltaT + DstParamData%IntMethod = SrcParamData%IntMethod + DstParamData%nDOF = SrcParamData%nDOF + DstParamData%nDOF_red = SrcParamData%nDOF_red + DstParamData%Nmembers = SrcParamData%Nmembers +IF (ALLOCATED(SrcParamData%Elems)) THEN + i1_l = LBOUND(SrcParamData%Elems,1) + i1_u = UBOUND(SrcParamData%Elems,1) + i2_l = LBOUND(SrcParamData%Elems,2) + i2_u = UBOUND(SrcParamData%Elems,2) + IF (.NOT. ALLOCATED(DstParamData%Elems)) THEN + ALLOCATE(DstParamData%Elems(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Elems.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%Elems = SrcParamData%Elems +ENDIF +IF (ALLOCATED(SrcParamData%ElemProps)) THEN + i1_l = LBOUND(SrcParamData%ElemProps,1) + i1_u = UBOUND(SrcParamData%ElemProps,1) + IF (.NOT. ALLOCATED(DstParamData%ElemProps)) THEN + ALLOCATE(DstParamData%ElemProps(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ElemProps.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%ElemProps,1), UBOUND(SrcParamData%ElemProps,1) + CALL SD_Copyelemproptype( SrcParamData%ElemProps(i1), DstParamData%ElemProps(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%FG)) THEN + i1_l = LBOUND(SrcParamData%FG,1) + i1_u = UBOUND(SrcParamData%FG,1) + IF (.NOT. ALLOCATED(DstParamData%FG)) THEN + ALLOCATE(DstParamData%FG(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%FG.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%FG = SrcParamData%FG +ENDIF +IF (ALLOCATED(SrcParamData%DP0)) THEN + i1_l = LBOUND(SrcParamData%DP0,1) + i1_u = UBOUND(SrcParamData%DP0,1) + i2_l = LBOUND(SrcParamData%DP0,2) + i2_u = UBOUND(SrcParamData%DP0,2) + IF (.NOT. ALLOCATED(DstParamData%DP0)) THEN + ALLOCATE(DstParamData%DP0(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%DP0.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%DP0 = SrcParamData%DP0 +ENDIF +IF (ALLOCATED(SrcParamData%NodeID2JointID)) THEN + i1_l = LBOUND(SrcParamData%NodeID2JointID,1) + i1_u = UBOUND(SrcParamData%NodeID2JointID,1) + IF (.NOT. ALLOCATED(DstParamData%NodeID2JointID)) THEN + ALLOCATE(DstParamData%NodeID2JointID(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodeID2JointID.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%NodeID2JointID = SrcParamData%NodeID2JointID +ENDIF + DstParamData%reduced = SrcParamData%reduced +IF (ALLOCATED(SrcParamData%T_red)) THEN + i1_l = LBOUND(SrcParamData%T_red,1) + i1_u = UBOUND(SrcParamData%T_red,1) + i2_l = LBOUND(SrcParamData%T_red,2) + i2_u = UBOUND(SrcParamData%T_red,2) + IF (.NOT. ALLOCATED(DstParamData%T_red)) THEN + ALLOCATE(DstParamData%T_red(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%T_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%T_red = SrcParamData%T_red +ENDIF +IF (ALLOCATED(SrcParamData%T_red_T)) THEN + i1_l = LBOUND(SrcParamData%T_red_T,1) + i1_u = UBOUND(SrcParamData%T_red_T,1) + i2_l = LBOUND(SrcParamData%T_red_T,2) + i2_u = UBOUND(SrcParamData%T_red_T,2) + IF (.NOT. ALLOCATED(DstParamData%T_red_T)) THEN + ALLOCATE(DstParamData%T_red_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%T_red_T.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%T_red_T = SrcParamData%T_red_T +ENDIF +IF (ALLOCATED(SrcParamData%NodesDOF)) THEN + i1_l = LBOUND(SrcParamData%NodesDOF,1) + i1_u = UBOUND(SrcParamData%NodesDOF,1) + IF (.NOT. ALLOCATED(DstParamData%NodesDOF)) THEN + ALLOCATE(DstParamData%NodesDOF(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodesDOF.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%NodesDOF,1), UBOUND(SrcParamData%NodesDOF,1) + CALL SD_Copyilist( SrcParamData%NodesDOF(i1), DstParamData%NodesDOF(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%NodesDOFred)) THEN + i1_l = LBOUND(SrcParamData%NodesDOFred,1) + i1_u = UBOUND(SrcParamData%NodesDOFred,1) + IF (.NOT. ALLOCATED(DstParamData%NodesDOFred)) THEN + ALLOCATE(DstParamData%NodesDOFred(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%NodesDOFred.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%NodesDOFred,1), UBOUND(SrcParamData%NodesDOFred,1) + CALL SD_Copyilist( SrcParamData%NodesDOFred(i1), DstParamData%NodesDOFred(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%ElemsDOF)) THEN + i1_l = LBOUND(SrcParamData%ElemsDOF,1) + i1_u = UBOUND(SrcParamData%ElemsDOF,1) + i2_l = LBOUND(SrcParamData%ElemsDOF,2) + i2_u = UBOUND(SrcParamData%ElemsDOF,2) + IF (.NOT. ALLOCATED(DstParamData%ElemsDOF)) THEN + ALLOCATE(DstParamData%ElemsDOF(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ElemsDOF.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%ElemsDOF = SrcParamData%ElemsDOF +ENDIF +IF (ALLOCATED(SrcParamData%DOFred2Nodes)) THEN + i1_l = LBOUND(SrcParamData%DOFred2Nodes,1) + i1_u = UBOUND(SrcParamData%DOFred2Nodes,1) + i2_l = LBOUND(SrcParamData%DOFred2Nodes,2) + i2_u = UBOUND(SrcParamData%DOFred2Nodes,2) + IF (.NOT. ALLOCATED(DstParamData%DOFred2Nodes)) THEN + ALLOCATE(DstParamData%DOFred2Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%DOFred2Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%DOFred2Nodes = SrcParamData%DOFred2Nodes +ENDIF +IF (ALLOCATED(SrcParamData%CtrlElem2Channel)) THEN + i1_l = LBOUND(SrcParamData%CtrlElem2Channel,1) + i1_u = UBOUND(SrcParamData%CtrlElem2Channel,1) + i2_l = LBOUND(SrcParamData%CtrlElem2Channel,2) + i2_u = UBOUND(SrcParamData%CtrlElem2Channel,2) + IF (.NOT. ALLOCATED(DstParamData%CtrlElem2Channel)) THEN + ALLOCATE(DstParamData%CtrlElem2Channel(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CtrlElem2Channel.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%CtrlElem2Channel = SrcParamData%CtrlElem2Channel +ENDIF + DstParamData%nDOFM = SrcParamData%nDOFM + DstParamData%SttcSolve = SrcParamData%SttcSolve + DstParamData%GuyanLoadCorrection = SrcParamData%GuyanLoadCorrection + DstParamData%Floating = SrcParamData%Floating +IF (ALLOCATED(SrcParamData%KMMDiag)) THEN + i1_l = LBOUND(SrcParamData%KMMDiag,1) + i1_u = UBOUND(SrcParamData%KMMDiag,1) + IF (.NOT. ALLOCATED(DstParamData%KMMDiag)) THEN + ALLOCATE(DstParamData%KMMDiag(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KMMDiag.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%KMMDiag = SrcParamData%KMMDiag +ENDIF +IF (ALLOCATED(SrcParamData%CMMDiag)) THEN + i1_l = LBOUND(SrcParamData%CMMDiag,1) + i1_u = UBOUND(SrcParamData%CMMDiag,1) + IF (.NOT. ALLOCATED(DstParamData%CMMDiag)) THEN + ALLOCATE(DstParamData%CMMDiag(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CMMDiag.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%CMMDiag = SrcParamData%CMMDiag +ENDIF +IF (ALLOCATED(SrcParamData%MMB)) THEN + i1_l = LBOUND(SrcParamData%MMB,1) + i1_u = UBOUND(SrcParamData%MMB,1) + i2_l = LBOUND(SrcParamData%MMB,2) + i2_u = UBOUND(SrcParamData%MMB,2) + IF (.NOT. ALLOCATED(DstParamData%MMB)) THEN + ALLOCATE(DstParamData%MMB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MMB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%MMB = SrcParamData%MMB +ENDIF +IF (ALLOCATED(SrcParamData%MBmmB)) THEN + i1_l = LBOUND(SrcParamData%MBmmB,1) + i1_u = UBOUND(SrcParamData%MBmmB,1) + i2_l = LBOUND(SrcParamData%MBmmB,2) + i2_u = UBOUND(SrcParamData%MBmmB,2) + IF (.NOT. ALLOCATED(DstParamData%MBmmB)) THEN + ALLOCATE(DstParamData%MBmmB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBmmB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%MBmmB = SrcParamData%MBmmB +ENDIF +IF (ALLOCATED(SrcParamData%C1_11)) THEN + i1_l = LBOUND(SrcParamData%C1_11,1) + i1_u = UBOUND(SrcParamData%C1_11,1) + i2_l = LBOUND(SrcParamData%C1_11,2) + i2_u = UBOUND(SrcParamData%C1_11,2) + IF (.NOT. ALLOCATED(DstParamData%C1_11)) THEN + ALLOCATE(DstParamData%C1_11(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C1_11.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%C1_11 = SrcParamData%C1_11 +ENDIF +IF (ALLOCATED(SrcParamData%C1_12)) THEN + i1_l = LBOUND(SrcParamData%C1_12,1) + i1_u = UBOUND(SrcParamData%C1_12,1) + i2_l = LBOUND(SrcParamData%C1_12,2) + i2_u = UBOUND(SrcParamData%C1_12,2) + IF (.NOT. ALLOCATED(DstParamData%C1_12)) THEN + ALLOCATE(DstParamData%C1_12(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C1_12.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%C1_12 = SrcParamData%C1_12 +ENDIF +IF (ALLOCATED(SrcParamData%D1_141)) THEN + i1_l = LBOUND(SrcParamData%D1_141,1) + i1_u = UBOUND(SrcParamData%D1_141,1) + i2_l = LBOUND(SrcParamData%D1_141,2) + i2_u = UBOUND(SrcParamData%D1_141,2) + IF (.NOT. ALLOCATED(DstParamData%D1_141)) THEN + ALLOCATE(DstParamData%D1_141(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D1_141.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%D1_141 = SrcParamData%D1_141 +ENDIF +IF (ALLOCATED(SrcParamData%D1_142)) THEN + i1_l = LBOUND(SrcParamData%D1_142,1) + i1_u = UBOUND(SrcParamData%D1_142,1) + i2_l = LBOUND(SrcParamData%D1_142,2) + i2_u = UBOUND(SrcParamData%D1_142,2) + IF (.NOT. ALLOCATED(DstParamData%D1_142)) THEN + ALLOCATE(DstParamData%D1_142(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D1_142.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%D1_142 = SrcParamData%D1_142 +ENDIF +IF (ALLOCATED(SrcParamData%PhiM)) THEN + i1_l = LBOUND(SrcParamData%PhiM,1) + i1_u = UBOUND(SrcParamData%PhiM,1) + i2_l = LBOUND(SrcParamData%PhiM,2) + i2_u = UBOUND(SrcParamData%PhiM,2) + IF (.NOT. ALLOCATED(DstParamData%PhiM)) THEN + ALLOCATE(DstParamData%PhiM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%PhiM = SrcParamData%PhiM +ENDIF +IF (ALLOCATED(SrcParamData%C2_61)) THEN + i1_l = LBOUND(SrcParamData%C2_61,1) + i1_u = UBOUND(SrcParamData%C2_61,1) + i2_l = LBOUND(SrcParamData%C2_61,2) + i2_u = UBOUND(SrcParamData%C2_61,2) + IF (.NOT. ALLOCATED(DstParamData%C2_61)) THEN + ALLOCATE(DstParamData%C2_61(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C2_61.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%C2_61 = SrcParamData%C2_61 +ENDIF +IF (ALLOCATED(SrcParamData%C2_62)) THEN + i1_l = LBOUND(SrcParamData%C2_62,1) + i1_u = UBOUND(SrcParamData%C2_62,1) + i2_l = LBOUND(SrcParamData%C2_62,2) + i2_u = UBOUND(SrcParamData%C2_62,2) + IF (.NOT. ALLOCATED(DstParamData%C2_62)) THEN + ALLOCATE(DstParamData%C2_62(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%C2_62.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%C2_62 = SrcParamData%C2_62 +ENDIF +IF (ALLOCATED(SrcParamData%PhiRb_TI)) THEN + i1_l = LBOUND(SrcParamData%PhiRb_TI,1) + i1_u = UBOUND(SrcParamData%PhiRb_TI,1) + i2_l = LBOUND(SrcParamData%PhiRb_TI,2) + i2_u = UBOUND(SrcParamData%PhiRb_TI,2) + IF (.NOT. ALLOCATED(DstParamData%PhiRb_TI)) THEN + ALLOCATE(DstParamData%PhiRb_TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiRb_TI.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%PhiRb_TI = SrcParamData%PhiRb_TI +ENDIF +IF (ALLOCATED(SrcParamData%D2_63)) THEN + i1_l = LBOUND(SrcParamData%D2_63,1) + i1_u = UBOUND(SrcParamData%D2_63,1) + i2_l = LBOUND(SrcParamData%D2_63,2) + i2_u = UBOUND(SrcParamData%D2_63,2) + IF (.NOT. ALLOCATED(DstParamData%D2_63)) THEN + ALLOCATE(DstParamData%D2_63(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D2_63.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%D2_63 = SrcParamData%D2_63 +ENDIF +IF (ALLOCATED(SrcParamData%D2_64)) THEN + i1_l = LBOUND(SrcParamData%D2_64,1) + i1_u = UBOUND(SrcParamData%D2_64,1) + i2_l = LBOUND(SrcParamData%D2_64,2) + i2_u = UBOUND(SrcParamData%D2_64,2) + IF (.NOT. ALLOCATED(DstParamData%D2_64)) THEN + ALLOCATE(DstParamData%D2_64(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%D2_64.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%D2_64 = SrcParamData%D2_64 +ENDIF +IF (ALLOCATED(SrcParamData%MBB)) THEN + i1_l = LBOUND(SrcParamData%MBB,1) + i1_u = UBOUND(SrcParamData%MBB,1) + i2_l = LBOUND(SrcParamData%MBB,2) + i2_u = UBOUND(SrcParamData%MBB,2) + IF (.NOT. ALLOCATED(DstParamData%MBB)) THEN + ALLOCATE(DstParamData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%MBB = SrcParamData%MBB +ENDIF +IF (ALLOCATED(SrcParamData%KBB)) THEN + i1_l = LBOUND(SrcParamData%KBB,1) + i1_u = UBOUND(SrcParamData%KBB,1) + i2_l = LBOUND(SrcParamData%KBB,2) + i2_u = UBOUND(SrcParamData%KBB,2) + IF (.NOT. ALLOCATED(DstParamData%KBB)) THEN + ALLOCATE(DstParamData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%KBB = SrcParamData%KBB +ENDIF +IF (ALLOCATED(SrcParamData%CBB)) THEN + i1_l = LBOUND(SrcParamData%CBB,1) + i1_u = UBOUND(SrcParamData%CBB,1) + i2_l = LBOUND(SrcParamData%CBB,2) + i2_u = UBOUND(SrcParamData%CBB,2) + IF (.NOT. ALLOCATED(DstParamData%CBB)) THEN + ALLOCATE(DstParamData%CBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%CBB = SrcParamData%CBB +ENDIF +IF (ALLOCATED(SrcParamData%CMM)) THEN + i1_l = LBOUND(SrcParamData%CMM,1) + i1_u = UBOUND(SrcParamData%CMM,1) + i2_l = LBOUND(SrcParamData%CMM,2) + i2_u = UBOUND(SrcParamData%CMM,2) + IF (.NOT. ALLOCATED(DstParamData%CMM)) THEN + ALLOCATE(DstParamData%CMM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%CMM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%CMM = SrcParamData%CMM +ENDIF +IF (ALLOCATED(SrcParamData%MBM)) THEN + i1_l = LBOUND(SrcParamData%MBM,1) + i1_u = UBOUND(SrcParamData%MBM,1) + i2_l = LBOUND(SrcParamData%MBM,2) + i2_u = UBOUND(SrcParamData%MBM,2) + IF (.NOT. ALLOCATED(DstParamData%MBM)) THEN + ALLOCATE(DstParamData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MBM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%MBM = SrcParamData%MBM +ENDIF +IF (ALLOCATED(SrcParamData%PhiL_T)) THEN + i1_l = LBOUND(SrcParamData%PhiL_T,1) + i1_u = UBOUND(SrcParamData%PhiL_T,1) + i2_l = LBOUND(SrcParamData%PhiL_T,2) + i2_u = UBOUND(SrcParamData%PhiL_T,2) + IF (.NOT. ALLOCATED(DstParamData%PhiL_T)) THEN + ALLOCATE(DstParamData%PhiL_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiL_T.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%PhiL_T = SrcParamData%PhiL_T +ENDIF +IF (ALLOCATED(SrcParamData%PhiLInvOmgL2)) THEN + i1_l = LBOUND(SrcParamData%PhiLInvOmgL2,1) + i1_u = UBOUND(SrcParamData%PhiLInvOmgL2,1) + i2_l = LBOUND(SrcParamData%PhiLInvOmgL2,2) + i2_u = UBOUND(SrcParamData%PhiLInvOmgL2,2) + IF (.NOT. ALLOCATED(DstParamData%PhiLInvOmgL2)) THEN + ALLOCATE(DstParamData%PhiLInvOmgL2(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%PhiLInvOmgL2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%PhiLInvOmgL2 = SrcParamData%PhiLInvOmgL2 +ENDIF +IF (ALLOCATED(SrcParamData%KLLm1)) THEN + i1_l = LBOUND(SrcParamData%KLLm1,1) + i1_u = UBOUND(SrcParamData%KLLm1,1) + i2_l = LBOUND(SrcParamData%KLLm1,2) + i2_u = UBOUND(SrcParamData%KLLm1,2) + IF (.NOT. ALLOCATED(DstParamData%KLLm1)) THEN + ALLOCATE(DstParamData%KLLm1(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%KLLm1.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%KLLm1 = SrcParamData%KLLm1 +ENDIF +IF (ALLOCATED(SrcParamData%AM2Jac)) THEN + i1_l = LBOUND(SrcParamData%AM2Jac,1) + i1_u = UBOUND(SrcParamData%AM2Jac,1) + i2_l = LBOUND(SrcParamData%AM2Jac,2) + i2_u = UBOUND(SrcParamData%AM2Jac,2) + IF (.NOT. ALLOCATED(DstParamData%AM2Jac)) THEN + ALLOCATE(DstParamData%AM2Jac(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%AM2Jac.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%AM2Jac = SrcParamData%AM2Jac +ENDIF +IF (ALLOCATED(SrcParamData%AM2JacPiv)) THEN + i1_l = LBOUND(SrcParamData%AM2JacPiv,1) + i1_u = UBOUND(SrcParamData%AM2JacPiv,1) + IF (.NOT. ALLOCATED(DstParamData%AM2JacPiv)) THEN + ALLOCATE(DstParamData%AM2JacPiv(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%AM2JacPiv.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%AM2JacPiv = SrcParamData%AM2JacPiv +ENDIF +IF (ALLOCATED(SrcParamData%TI)) THEN + i1_l = LBOUND(SrcParamData%TI,1) + i1_u = UBOUND(SrcParamData%TI,1) + i2_l = LBOUND(SrcParamData%TI,2) + i2_u = UBOUND(SrcParamData%TI,2) + IF (.NOT. ALLOCATED(DstParamData%TI)) THEN + ALLOCATE(DstParamData%TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%TI.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%TI = SrcParamData%TI +ENDIF +IF (ALLOCATED(SrcParamData%TIreact)) THEN + i1_l = LBOUND(SrcParamData%TIreact,1) + i1_u = UBOUND(SrcParamData%TIreact,1) + i2_l = LBOUND(SrcParamData%TIreact,2) + i2_u = UBOUND(SrcParamData%TIreact,2) + IF (.NOT. ALLOCATED(DstParamData%TIreact)) THEN + ALLOCATE(DstParamData%TIreact(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%TIreact.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%TIreact = SrcParamData%TIreact +ENDIF + DstParamData%nNodes = SrcParamData%nNodes + DstParamData%nNodes_I = SrcParamData%nNodes_I + DstParamData%nNodes_L = SrcParamData%nNodes_L + DstParamData%nNodes_C = SrcParamData%nNodes_C +IF (ALLOCATED(SrcParamData%Nodes_I)) THEN + i1_l = LBOUND(SrcParamData%Nodes_I,1) + i1_u = UBOUND(SrcParamData%Nodes_I,1) + i2_l = LBOUND(SrcParamData%Nodes_I,2) + i2_u = UBOUND(SrcParamData%Nodes_I,2) + IF (.NOT. ALLOCATED(DstParamData%Nodes_I)) THEN + ALLOCATE(DstParamData%Nodes_I(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_I.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%Nodes_I = SrcParamData%Nodes_I +ENDIF +IF (ALLOCATED(SrcParamData%Nodes_L)) THEN + i1_l = LBOUND(SrcParamData%Nodes_L,1) + i1_u = UBOUND(SrcParamData%Nodes_L,1) + i2_l = LBOUND(SrcParamData%Nodes_L,2) + i2_u = UBOUND(SrcParamData%Nodes_L,2) + IF (.NOT. ALLOCATED(DstParamData%Nodes_L)) THEN + ALLOCATE(DstParamData%Nodes_L(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%Nodes_L = SrcParamData%Nodes_L +ENDIF +IF (ALLOCATED(SrcParamData%Nodes_C)) THEN + i1_l = LBOUND(SrcParamData%Nodes_C,1) + i1_u = UBOUND(SrcParamData%Nodes_C,1) + i2_l = LBOUND(SrcParamData%Nodes_C,2) + i2_u = UBOUND(SrcParamData%Nodes_C,2) + IF (.NOT. ALLOCATED(DstParamData%Nodes_C)) THEN + ALLOCATE(DstParamData%Nodes_C(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Nodes_C.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%Nodes_C = SrcParamData%Nodes_C +ENDIF + DstParamData%nDOFI__ = SrcParamData%nDOFI__ + DstParamData%nDOFI_Rb = SrcParamData%nDOFI_Rb + DstParamData%nDOFI_F = SrcParamData%nDOFI_F + DstParamData%nDOFL_L = SrcParamData%nDOFL_L + DstParamData%nDOFC__ = SrcParamData%nDOFC__ + DstParamData%nDOFC_Rb = SrcParamData%nDOFC_Rb + DstParamData%nDOFC_L = SrcParamData%nDOFC_L + DstParamData%nDOFC_F = SrcParamData%nDOFC_F + DstParamData%nDOFR__ = SrcParamData%nDOFR__ + DstParamData%nDOF__Rb = SrcParamData%nDOF__Rb + DstParamData%nDOF__L = SrcParamData%nDOF__L + DstParamData%nDOF__F = SrcParamData%nDOF__F +IF (ALLOCATED(SrcParamData%IDI__)) THEN + i1_l = LBOUND(SrcParamData%IDI__,1) + i1_u = UBOUND(SrcParamData%IDI__,1) + IF (.NOT. ALLOCATED(DstParamData%IDI__)) THEN + ALLOCATE(DstParamData%IDI__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDI__ = SrcParamData%IDI__ +ENDIF +IF (ALLOCATED(SrcParamData%IDI_Rb)) THEN + i1_l = LBOUND(SrcParamData%IDI_Rb,1) + i1_u = UBOUND(SrcParamData%IDI_Rb,1) + IF (.NOT. ALLOCATED(DstParamData%IDI_Rb)) THEN + ALLOCATE(DstParamData%IDI_Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI_Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDI_Rb = SrcParamData%IDI_Rb +ENDIF +IF (ALLOCATED(SrcParamData%IDI_F)) THEN + i1_l = LBOUND(SrcParamData%IDI_F,1) + i1_u = UBOUND(SrcParamData%IDI_F,1) + IF (.NOT. ALLOCATED(DstParamData%IDI_F)) THEN + ALLOCATE(DstParamData%IDI_F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDI_F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDI_F = SrcParamData%IDI_F +ENDIF +IF (ALLOCATED(SrcParamData%IDL_L)) THEN + i1_l = LBOUND(SrcParamData%IDL_L,1) + i1_u = UBOUND(SrcParamData%IDL_L,1) + IF (.NOT. ALLOCATED(DstParamData%IDL_L)) THEN + ALLOCATE(DstParamData%IDL_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDL_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDL_L = SrcParamData%IDL_L +ENDIF +IF (ALLOCATED(SrcParamData%IDC__)) THEN + i1_l = LBOUND(SrcParamData%IDC__,1) + i1_u = UBOUND(SrcParamData%IDC__,1) + IF (.NOT. ALLOCATED(DstParamData%IDC__)) THEN + ALLOCATE(DstParamData%IDC__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDC__ = SrcParamData%IDC__ +ENDIF +IF (ALLOCATED(SrcParamData%IDC_Rb)) THEN + i1_l = LBOUND(SrcParamData%IDC_Rb,1) + i1_u = UBOUND(SrcParamData%IDC_Rb,1) + IF (.NOT. ALLOCATED(DstParamData%IDC_Rb)) THEN + ALLOCATE(DstParamData%IDC_Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDC_Rb = SrcParamData%IDC_Rb +ENDIF +IF (ALLOCATED(SrcParamData%IDC_L)) THEN + i1_l = LBOUND(SrcParamData%IDC_L,1) + i1_u = UBOUND(SrcParamData%IDC_L,1) + IF (.NOT. ALLOCATED(DstParamData%IDC_L)) THEN + ALLOCATE(DstParamData%IDC_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDC_L = SrcParamData%IDC_L +ENDIF +IF (ALLOCATED(SrcParamData%IDC_F)) THEN + i1_l = LBOUND(SrcParamData%IDC_F,1) + i1_u = UBOUND(SrcParamData%IDC_F,1) + IF (.NOT. ALLOCATED(DstParamData%IDC_F)) THEN + ALLOCATE(DstParamData%IDC_F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDC_F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDC_F = SrcParamData%IDC_F +ENDIF +IF (ALLOCATED(SrcParamData%IDR__)) THEN + i1_l = LBOUND(SrcParamData%IDR__,1) + i1_u = UBOUND(SrcParamData%IDR__,1) + IF (.NOT. ALLOCATED(DstParamData%IDR__)) THEN + ALLOCATE(DstParamData%IDR__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%IDR__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%IDR__ = SrcParamData%IDR__ +ENDIF +IF (ALLOCATED(SrcParamData%ID__Rb)) THEN + i1_l = LBOUND(SrcParamData%ID__Rb,1) + i1_u = UBOUND(SrcParamData%ID__Rb,1) + IF (.NOT. ALLOCATED(DstParamData%ID__Rb)) THEN + ALLOCATE(DstParamData%ID__Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%ID__Rb = SrcParamData%ID__Rb +ENDIF +IF (ALLOCATED(SrcParamData%ID__L)) THEN + i1_l = LBOUND(SrcParamData%ID__L,1) + i1_u = UBOUND(SrcParamData%ID__L,1) + IF (.NOT. ALLOCATED(DstParamData%ID__L)) THEN + ALLOCATE(DstParamData%ID__L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%ID__L = SrcParamData%ID__L +ENDIF +IF (ALLOCATED(SrcParamData%ID__F)) THEN + i1_l = LBOUND(SrcParamData%ID__F,1) + i1_u = UBOUND(SrcParamData%ID__F,1) + IF (.NOT. ALLOCATED(DstParamData%ID__F)) THEN + ALLOCATE(DstParamData%ID__F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%ID__F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%ID__F = SrcParamData%ID__F +ENDIF + DstParamData%NMOutputs = SrcParamData%NMOutputs + DstParamData%NumOuts = SrcParamData%NumOuts + DstParamData%OutSwtch = SrcParamData%OutSwtch + DstParamData%UnJckF = SrcParamData%UnJckF + DstParamData%Delim = SrcParamData%Delim + DstParamData%OutFmt = SrcParamData%OutFmt + DstParamData%OutSFmt = SrcParamData%OutSFmt +IF (ALLOCATED(SrcParamData%MoutLst)) THEN + i1_l = LBOUND(SrcParamData%MoutLst,1) + i1_u = UBOUND(SrcParamData%MoutLst,1) + IF (.NOT. ALLOCATED(DstParamData%MoutLst)) THEN + ALLOCATE(DstParamData%MoutLst(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%MoutLst,1), UBOUND(SrcParamData%MoutLst,1) + CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst(i1), DstParamData%MoutLst(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%MoutLst2)) THEN + i1_l = LBOUND(SrcParamData%MoutLst2,1) + i1_u = UBOUND(SrcParamData%MoutLst2,1) + IF (.NOT. ALLOCATED(DstParamData%MoutLst2)) THEN + ALLOCATE(DstParamData%MoutLst2(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%MoutLst2,1), UBOUND(SrcParamData%MoutLst2,1) + CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst2(i1), DstParamData%MoutLst2(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%MoutLst3)) THEN + i1_l = LBOUND(SrcParamData%MoutLst3,1) + i1_u = UBOUND(SrcParamData%MoutLst3,1) + IF (.NOT. ALLOCATED(DstParamData%MoutLst3)) THEN + ALLOCATE(DstParamData%MoutLst3(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%MoutLst3.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%MoutLst3,1), UBOUND(SrcParamData%MoutLst3,1) + CALL SD_Copymeshauxdatatype( SrcParamData%MoutLst3(i1), DstParamData%MoutLst3(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF +IF (ALLOCATED(SrcParamData%OutParam)) THEN + i1_l = LBOUND(SrcParamData%OutParam,1) + i1_u = UBOUND(SrcParamData%OutParam,1) + IF (.NOT. ALLOCATED(DstParamData%OutParam)) THEN + ALLOCATE(DstParamData%OutParam(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%OutParam.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DO i1 = LBOUND(SrcParamData%OutParam,1), UBOUND(SrcParamData%OutParam,1) + CALL NWTC_Library_Copyoutparmtype( SrcParamData%OutParam(i1), DstParamData%OutParam(i1), CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + ENDDO +ENDIF + DstParamData%OutAll = SrcParamData%OutAll + DstParamData%OutCBModes = SrcParamData%OutCBModes + DstParamData%OutFEMModes = SrcParamData%OutFEMModes + DstParamData%OutReact = SrcParamData%OutReact + DstParamData%OutAllInt = SrcParamData%OutAllInt + DstParamData%OutAllDims = SrcParamData%OutAllDims + DstParamData%OutDec = SrcParamData%OutDec +IF (ALLOCATED(SrcParamData%Jac_u_indx)) THEN + i1_l = LBOUND(SrcParamData%Jac_u_indx,1) + i1_u = UBOUND(SrcParamData%Jac_u_indx,1) + i2_l = LBOUND(SrcParamData%Jac_u_indx,2) + i2_u = UBOUND(SrcParamData%Jac_u_indx,2) + IF (.NOT. ALLOCATED(DstParamData%Jac_u_indx)) THEN + ALLOCATE(DstParamData%Jac_u_indx(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%Jac_u_indx.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%Jac_u_indx = SrcParamData%Jac_u_indx +ENDIF +IF (ALLOCATED(SrcParamData%du)) THEN + i1_l = LBOUND(SrcParamData%du,1) + i1_u = UBOUND(SrcParamData%du,1) + IF (.NOT. ALLOCATED(DstParamData%du)) THEN + ALLOCATE(DstParamData%du(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstParamData%du.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstParamData%du = SrcParamData%du +ENDIF + DstParamData%dx = SrcParamData%dx + DstParamData%Jac_ny = SrcParamData%Jac_ny + DstParamData%Jac_nx = SrcParamData%Jac_nx + DstParamData%RotStates = SrcParamData%RotStates + END SUBROUTINE SD_CopyParam + + SUBROUTINE SD_DestroyParam( ParamData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_ParameterType), INTENT(INOUT) :: ParamData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyParam' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + +IF (ALLOCATED(ParamData%Elems)) THEN + DEALLOCATE(ParamData%Elems) +ENDIF +IF (ALLOCATED(ParamData%ElemProps)) THEN +DO i1 = LBOUND(ParamData%ElemProps,1), UBOUND(ParamData%ElemProps,1) + CALL SD_Destroyelemproptype( ParamData%ElemProps(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%ElemProps) +ENDIF +IF (ALLOCATED(ParamData%FG)) THEN + DEALLOCATE(ParamData%FG) +ENDIF +IF (ALLOCATED(ParamData%DP0)) THEN + DEALLOCATE(ParamData%DP0) +ENDIF +IF (ALLOCATED(ParamData%NodeID2JointID)) THEN + DEALLOCATE(ParamData%NodeID2JointID) +ENDIF +IF (ALLOCATED(ParamData%T_red)) THEN + DEALLOCATE(ParamData%T_red) +ENDIF +IF (ALLOCATED(ParamData%T_red_T)) THEN + DEALLOCATE(ParamData%T_red_T) +ENDIF +IF (ALLOCATED(ParamData%NodesDOF)) THEN +DO i1 = LBOUND(ParamData%NodesDOF,1), UBOUND(ParamData%NodesDOF,1) + CALL SD_Destroyilist( ParamData%NodesDOF(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%NodesDOF) +ENDIF +IF (ALLOCATED(ParamData%NodesDOFred)) THEN +DO i1 = LBOUND(ParamData%NodesDOFred,1), UBOUND(ParamData%NodesDOFred,1) + CALL SD_Destroyilist( ParamData%NodesDOFred(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%NodesDOFred) +ENDIF +IF (ALLOCATED(ParamData%ElemsDOF)) THEN + DEALLOCATE(ParamData%ElemsDOF) +ENDIF +IF (ALLOCATED(ParamData%DOFred2Nodes)) THEN + DEALLOCATE(ParamData%DOFred2Nodes) +ENDIF +IF (ALLOCATED(ParamData%CtrlElem2Channel)) THEN + DEALLOCATE(ParamData%CtrlElem2Channel) +ENDIF +IF (ALLOCATED(ParamData%KMMDiag)) THEN + DEALLOCATE(ParamData%KMMDiag) +ENDIF +IF (ALLOCATED(ParamData%CMMDiag)) THEN + DEALLOCATE(ParamData%CMMDiag) +ENDIF +IF (ALLOCATED(ParamData%MMB)) THEN + DEALLOCATE(ParamData%MMB) +ENDIF +IF (ALLOCATED(ParamData%MBmmB)) THEN + DEALLOCATE(ParamData%MBmmB) +ENDIF +IF (ALLOCATED(ParamData%C1_11)) THEN + DEALLOCATE(ParamData%C1_11) +ENDIF +IF (ALLOCATED(ParamData%C1_12)) THEN + DEALLOCATE(ParamData%C1_12) +ENDIF +IF (ALLOCATED(ParamData%D1_141)) THEN + DEALLOCATE(ParamData%D1_141) +ENDIF +IF (ALLOCATED(ParamData%D1_142)) THEN + DEALLOCATE(ParamData%D1_142) +ENDIF +IF (ALLOCATED(ParamData%PhiM)) THEN + DEALLOCATE(ParamData%PhiM) +ENDIF +IF (ALLOCATED(ParamData%C2_61)) THEN + DEALLOCATE(ParamData%C2_61) +ENDIF +IF (ALLOCATED(ParamData%C2_62)) THEN + DEALLOCATE(ParamData%C2_62) +ENDIF +IF (ALLOCATED(ParamData%PhiRb_TI)) THEN + DEALLOCATE(ParamData%PhiRb_TI) +ENDIF +IF (ALLOCATED(ParamData%D2_63)) THEN + DEALLOCATE(ParamData%D2_63) +ENDIF +IF (ALLOCATED(ParamData%D2_64)) THEN + DEALLOCATE(ParamData%D2_64) +ENDIF +IF (ALLOCATED(ParamData%MBB)) THEN + DEALLOCATE(ParamData%MBB) +ENDIF +IF (ALLOCATED(ParamData%KBB)) THEN + DEALLOCATE(ParamData%KBB) +ENDIF +IF (ALLOCATED(ParamData%CBB)) THEN + DEALLOCATE(ParamData%CBB) +ENDIF +IF (ALLOCATED(ParamData%CMM)) THEN + DEALLOCATE(ParamData%CMM) +ENDIF +IF (ALLOCATED(ParamData%MBM)) THEN + DEALLOCATE(ParamData%MBM) +ENDIF +IF (ALLOCATED(ParamData%PhiL_T)) THEN + DEALLOCATE(ParamData%PhiL_T) +ENDIF +IF (ALLOCATED(ParamData%PhiLInvOmgL2)) THEN + DEALLOCATE(ParamData%PhiLInvOmgL2) +ENDIF +IF (ALLOCATED(ParamData%KLLm1)) THEN + DEALLOCATE(ParamData%KLLm1) +ENDIF +IF (ALLOCATED(ParamData%AM2Jac)) THEN + DEALLOCATE(ParamData%AM2Jac) +ENDIF +IF (ALLOCATED(ParamData%AM2JacPiv)) THEN + DEALLOCATE(ParamData%AM2JacPiv) +ENDIF +IF (ALLOCATED(ParamData%TI)) THEN + DEALLOCATE(ParamData%TI) +ENDIF +IF (ALLOCATED(ParamData%TIreact)) THEN + DEALLOCATE(ParamData%TIreact) +ENDIF +IF (ALLOCATED(ParamData%Nodes_I)) THEN + DEALLOCATE(ParamData%Nodes_I) +ENDIF +IF (ALLOCATED(ParamData%Nodes_L)) THEN + DEALLOCATE(ParamData%Nodes_L) +ENDIF +IF (ALLOCATED(ParamData%Nodes_C)) THEN + DEALLOCATE(ParamData%Nodes_C) +ENDIF +IF (ALLOCATED(ParamData%IDI__)) THEN + DEALLOCATE(ParamData%IDI__) +ENDIF +IF (ALLOCATED(ParamData%IDI_Rb)) THEN + DEALLOCATE(ParamData%IDI_Rb) +ENDIF +IF (ALLOCATED(ParamData%IDI_F)) THEN + DEALLOCATE(ParamData%IDI_F) +ENDIF +IF (ALLOCATED(ParamData%IDL_L)) THEN + DEALLOCATE(ParamData%IDL_L) +ENDIF +IF (ALLOCATED(ParamData%IDC__)) THEN + DEALLOCATE(ParamData%IDC__) +ENDIF +IF (ALLOCATED(ParamData%IDC_Rb)) THEN + DEALLOCATE(ParamData%IDC_Rb) +ENDIF +IF (ALLOCATED(ParamData%IDC_L)) THEN + DEALLOCATE(ParamData%IDC_L) +ENDIF +IF (ALLOCATED(ParamData%IDC_F)) THEN + DEALLOCATE(ParamData%IDC_F) +ENDIF +IF (ALLOCATED(ParamData%IDR__)) THEN + DEALLOCATE(ParamData%IDR__) +ENDIF +IF (ALLOCATED(ParamData%ID__Rb)) THEN + DEALLOCATE(ParamData%ID__Rb) +ENDIF +IF (ALLOCATED(ParamData%ID__L)) THEN + DEALLOCATE(ParamData%ID__L) +ENDIF +IF (ALLOCATED(ParamData%ID__F)) THEN + DEALLOCATE(ParamData%ID__F) +ENDIF +IF (ALLOCATED(ParamData%MoutLst)) THEN +DO i1 = LBOUND(ParamData%MoutLst,1), UBOUND(ParamData%MoutLst,1) + CALL SD_Destroymeshauxdatatype( ParamData%MoutLst(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%MoutLst) +ENDIF +IF (ALLOCATED(ParamData%MoutLst2)) THEN +DO i1 = LBOUND(ParamData%MoutLst2,1), UBOUND(ParamData%MoutLst2,1) + CALL SD_Destroymeshauxdatatype( ParamData%MoutLst2(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%MoutLst2) +ENDIF +IF (ALLOCATED(ParamData%MoutLst3)) THEN +DO i1 = LBOUND(ParamData%MoutLst3,1), UBOUND(ParamData%MoutLst3,1) + CALL SD_Destroymeshauxdatatype( ParamData%MoutLst3(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%MoutLst3) +ENDIF +IF (ALLOCATED(ParamData%OutParam)) THEN +DO i1 = LBOUND(ParamData%OutParam,1), UBOUND(ParamData%OutParam,1) + CALL NWTC_Library_Destroyoutparmtype( ParamData%OutParam(i1), ErrStat2, ErrMsg2, DEALLOCATEpointers_local ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +ENDDO + DEALLOCATE(ParamData%OutParam) +ENDIF +IF (ALLOCATED(ParamData%Jac_u_indx)) THEN + DEALLOCATE(ParamData%Jac_u_indx) +ENDIF +IF (ALLOCATED(ParamData%du)) THEN + DEALLOCATE(ParamData%du) +ENDIF + END SUBROUTINE SD_DestroyParam + + SUBROUTINE SD_PackParam( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_ParameterType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackParam' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + Db_BufSz = Db_BufSz + 1 ! SDDeltaT + Int_BufSz = Int_BufSz + 1 ! IntMethod + Int_BufSz = Int_BufSz + 1 ! nDOF + Int_BufSz = Int_BufSz + 1 ! nDOF_red + Int_BufSz = Int_BufSz + 1 ! Nmembers + Int_BufSz = Int_BufSz + 1 ! Elems allocated yes/no + IF ( ALLOCATED(InData%Elems) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Elems upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Elems) ! Elems + END IF + Int_BufSz = Int_BufSz + 1 ! ElemProps allocated yes/no + IF ( ALLOCATED(InData%ElemProps) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! ElemProps upper/lower bounds for each dimension + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) + Int_BufSz = Int_BufSz + 3 ! ElemProps: size of buffers for each call to pack subtype + CALL SD_Packelemproptype( Re_Buf, Db_Buf, Int_Buf, InData%ElemProps(i1), ErrStat2, ErrMsg2, .TRUE. ) ! ElemProps + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! ElemProps + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! ElemProps + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! ElemProps + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! FG allocated yes/no + IF ( ALLOCATED(InData%FG) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! FG upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%FG) ! FG + END IF + Int_BufSz = Int_BufSz + 1 ! DP0 allocated yes/no + IF ( ALLOCATED(InData%DP0) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! DP0 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%DP0) ! DP0 + END IF + Int_BufSz = Int_BufSz + 1 ! NodeID2JointID allocated yes/no + IF ( ALLOCATED(InData%NodeID2JointID) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! NodeID2JointID upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%NodeID2JointID) ! NodeID2JointID + END IF + Int_BufSz = Int_BufSz + 1 ! reduced + Int_BufSz = Int_BufSz + 1 ! T_red allocated yes/no + IF ( ALLOCATED(InData%T_red) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! T_red upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%T_red) ! T_red + END IF + Int_BufSz = Int_BufSz + 1 ! T_red_T allocated yes/no + IF ( ALLOCATED(InData%T_red_T) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! T_red_T upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%T_red_T) ! T_red_T + END IF + Int_BufSz = Int_BufSz + 1 ! NodesDOF allocated yes/no + IF ( ALLOCATED(InData%NodesDOF) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! NodesDOF upper/lower bounds for each dimension + DO i1 = LBOUND(InData%NodesDOF,1), UBOUND(InData%NodesDOF,1) + Int_BufSz = Int_BufSz + 3 ! NodesDOF: size of buffers for each call to pack subtype + CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOF(i1), ErrStat2, ErrMsg2, .TRUE. ) ! NodesDOF + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! NodesDOF + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! NodesDOF + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! NodesDOF + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! NodesDOFred allocated yes/no + IF ( ALLOCATED(InData%NodesDOFred) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! NodesDOFred upper/lower bounds for each dimension + DO i1 = LBOUND(InData%NodesDOFred,1), UBOUND(InData%NodesDOFred,1) + Int_BufSz = Int_BufSz + 3 ! NodesDOFred: size of buffers for each call to pack subtype + CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOFred(i1), ErrStat2, ErrMsg2, .TRUE. ) ! NodesDOFred + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! NodesDOFred + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! NodesDOFred + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! NodesDOFred + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! ElemsDOF allocated yes/no + IF ( ALLOCATED(InData%ElemsDOF) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! ElemsDOF upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ElemsDOF) ! ElemsDOF + END IF + Int_BufSz = Int_BufSz + 1 ! DOFred2Nodes allocated yes/no + IF ( ALLOCATED(InData%DOFred2Nodes) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! DOFred2Nodes upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%DOFred2Nodes) ! DOFred2Nodes + END IF + Int_BufSz = Int_BufSz + 1 ! CtrlElem2Channel allocated yes/no + IF ( ALLOCATED(InData%CtrlElem2Channel) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! CtrlElem2Channel upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%CtrlElem2Channel) ! CtrlElem2Channel + END IF + Int_BufSz = Int_BufSz + 1 ! nDOFM + Int_BufSz = Int_BufSz + 1 ! SttcSolve + Int_BufSz = Int_BufSz + 1 ! GuyanLoadCorrection + Int_BufSz = Int_BufSz + 1 ! Floating + Int_BufSz = Int_BufSz + 1 ! KMMDiag allocated yes/no + IF ( ALLOCATED(InData%KMMDiag) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! KMMDiag upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%KMMDiag) ! KMMDiag + END IF + Int_BufSz = Int_BufSz + 1 ! CMMDiag allocated yes/no + IF ( ALLOCATED(InData%CMMDiag) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! CMMDiag upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%CMMDiag) ! CMMDiag + END IF + Int_BufSz = Int_BufSz + 1 ! MMB allocated yes/no + IF ( ALLOCATED(InData%MMB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MMB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%MMB) ! MMB + END IF + Int_BufSz = Int_BufSz + 1 ! MBmmB allocated yes/no + IF ( ALLOCATED(InData%MBmmB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MBmmB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%MBmmB) ! MBmmB + END IF + Int_BufSz = Int_BufSz + 1 ! C1_11 allocated yes/no + IF ( ALLOCATED(InData%C1_11) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! C1_11 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%C1_11) ! C1_11 + END IF + Int_BufSz = Int_BufSz + 1 ! C1_12 allocated yes/no + IF ( ALLOCATED(InData%C1_12) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! C1_12 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%C1_12) ! C1_12 + END IF + Int_BufSz = Int_BufSz + 1 ! D1_141 allocated yes/no + IF ( ALLOCATED(InData%D1_141) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! D1_141 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%D1_141) ! D1_141 + END IF + Int_BufSz = Int_BufSz + 1 ! D1_142 allocated yes/no + IF ( ALLOCATED(InData%D1_142) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! D1_142 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%D1_142) ! D1_142 + END IF + Int_BufSz = Int_BufSz + 1 ! PhiM allocated yes/no + IF ( ALLOCATED(InData%PhiM) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiM upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PhiM) ! PhiM + END IF + Int_BufSz = Int_BufSz + 1 ! C2_61 allocated yes/no + IF ( ALLOCATED(InData%C2_61) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! C2_61 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%C2_61) ! C2_61 + END IF + Int_BufSz = Int_BufSz + 1 ! C2_62 allocated yes/no + IF ( ALLOCATED(InData%C2_62) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! C2_62 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%C2_62) ! C2_62 + END IF + Int_BufSz = Int_BufSz + 1 ! PhiRb_TI allocated yes/no + IF ( ALLOCATED(InData%PhiRb_TI) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiRb_TI upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PhiRb_TI) ! PhiRb_TI + END IF + Int_BufSz = Int_BufSz + 1 ! D2_63 allocated yes/no + IF ( ALLOCATED(InData%D2_63) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! D2_63 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%D2_63) ! D2_63 + END IF + Int_BufSz = Int_BufSz + 1 ! D2_64 allocated yes/no + IF ( ALLOCATED(InData%D2_64) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! D2_64 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%D2_64) ! D2_64 + END IF + Int_BufSz = Int_BufSz + 1 ! MBB allocated yes/no + IF ( ALLOCATED(InData%MBB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MBB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%MBB) ! MBB + END IF + Int_BufSz = Int_BufSz + 1 ! KBB allocated yes/no + IF ( ALLOCATED(InData%KBB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! KBB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%KBB) ! KBB + END IF + Int_BufSz = Int_BufSz + 1 ! CBB allocated yes/no + IF ( ALLOCATED(InData%CBB) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! CBB upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%CBB) ! CBB + END IF + Int_BufSz = Int_BufSz + 1 ! CMM allocated yes/no + IF ( ALLOCATED(InData%CMM) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! CMM upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%CMM) ! CMM + END IF + Int_BufSz = Int_BufSz + 1 ! MBM allocated yes/no + IF ( ALLOCATED(InData%MBM) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! MBM upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%MBM) ! MBM + END IF + Int_BufSz = Int_BufSz + 1 ! PhiL_T allocated yes/no + IF ( ALLOCATED(InData%PhiL_T) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiL_T upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PhiL_T) ! PhiL_T + END IF + Int_BufSz = Int_BufSz + 1 ! PhiLInvOmgL2 allocated yes/no + IF ( ALLOCATED(InData%PhiLInvOmgL2) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! PhiLInvOmgL2 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%PhiLInvOmgL2) ! PhiLInvOmgL2 + END IF + Int_BufSz = Int_BufSz + 1 ! KLLm1 allocated yes/no + IF ( ALLOCATED(InData%KLLm1) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! KLLm1 upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%KLLm1) ! KLLm1 + END IF + Int_BufSz = Int_BufSz + 1 ! AM2Jac allocated yes/no + IF ( ALLOCATED(InData%AM2Jac) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! AM2Jac upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%AM2Jac) ! AM2Jac + END IF + Int_BufSz = Int_BufSz + 1 ! AM2JacPiv allocated yes/no + IF ( ALLOCATED(InData%AM2JacPiv) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! AM2JacPiv upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%AM2JacPiv) ! AM2JacPiv + END IF + Int_BufSz = Int_BufSz + 1 ! TI allocated yes/no + IF ( ALLOCATED(InData%TI) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! TI upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%TI) ! TI + END IF + Int_BufSz = Int_BufSz + 1 ! TIreact allocated yes/no + IF ( ALLOCATED(InData%TIreact) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! TIreact upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%TIreact) ! TIreact + END IF + Int_BufSz = Int_BufSz + 1 ! nNodes + Int_BufSz = Int_BufSz + 1 ! nNodes_I + Int_BufSz = Int_BufSz + 1 ! nNodes_L + Int_BufSz = Int_BufSz + 1 ! nNodes_C + Int_BufSz = Int_BufSz + 1 ! Nodes_I allocated yes/no + IF ( ALLOCATED(InData%Nodes_I) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Nodes_I upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Nodes_I) ! Nodes_I + END IF + Int_BufSz = Int_BufSz + 1 ! Nodes_L allocated yes/no + IF ( ALLOCATED(InData%Nodes_L) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Nodes_L upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Nodes_L) ! Nodes_L + END IF + Int_BufSz = Int_BufSz + 1 ! Nodes_C allocated yes/no + IF ( ALLOCATED(InData%Nodes_C) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Nodes_C upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Nodes_C) ! Nodes_C + END IF + Int_BufSz = Int_BufSz + 1 ! nDOFI__ + Int_BufSz = Int_BufSz + 1 ! nDOFI_Rb + Int_BufSz = Int_BufSz + 1 ! nDOFI_F + Int_BufSz = Int_BufSz + 1 ! nDOFL_L + Int_BufSz = Int_BufSz + 1 ! nDOFC__ + Int_BufSz = Int_BufSz + 1 ! nDOFC_Rb + Int_BufSz = Int_BufSz + 1 ! nDOFC_L + Int_BufSz = Int_BufSz + 1 ! nDOFC_F + Int_BufSz = Int_BufSz + 1 ! nDOFR__ + Int_BufSz = Int_BufSz + 1 ! nDOF__Rb + Int_BufSz = Int_BufSz + 1 ! nDOF__L + Int_BufSz = Int_BufSz + 1 ! nDOF__F + Int_BufSz = Int_BufSz + 1 ! IDI__ allocated yes/no + IF ( ALLOCATED(InData%IDI__) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDI__ upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDI__) ! IDI__ + END IF + Int_BufSz = Int_BufSz + 1 ! IDI_Rb allocated yes/no + IF ( ALLOCATED(InData%IDI_Rb) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDI_Rb upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDI_Rb) ! IDI_Rb + END IF + Int_BufSz = Int_BufSz + 1 ! IDI_F allocated yes/no + IF ( ALLOCATED(InData%IDI_F) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDI_F upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDI_F) ! IDI_F + END IF + Int_BufSz = Int_BufSz + 1 ! IDL_L allocated yes/no + IF ( ALLOCATED(InData%IDL_L) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDL_L upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDL_L) ! IDL_L + END IF + Int_BufSz = Int_BufSz + 1 ! IDC__ allocated yes/no + IF ( ALLOCATED(InData%IDC__) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDC__ upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDC__) ! IDC__ + END IF + Int_BufSz = Int_BufSz + 1 ! IDC_Rb allocated yes/no + IF ( ALLOCATED(InData%IDC_Rb) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDC_Rb upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDC_Rb) ! IDC_Rb + END IF + Int_BufSz = Int_BufSz + 1 ! IDC_L allocated yes/no + IF ( ALLOCATED(InData%IDC_L) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDC_L upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDC_L) ! IDC_L + END IF + Int_BufSz = Int_BufSz + 1 ! IDC_F allocated yes/no + IF ( ALLOCATED(InData%IDC_F) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDC_F upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDC_F) ! IDC_F + END IF + Int_BufSz = Int_BufSz + 1 ! IDR__ allocated yes/no + IF ( ALLOCATED(InData%IDR__) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! IDR__ upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%IDR__) ! IDR__ + END IF + Int_BufSz = Int_BufSz + 1 ! ID__Rb allocated yes/no + IF ( ALLOCATED(InData%ID__Rb) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! ID__Rb upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ID__Rb) ! ID__Rb + END IF + Int_BufSz = Int_BufSz + 1 ! ID__L allocated yes/no + IF ( ALLOCATED(InData%ID__L) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! ID__L upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ID__L) ! ID__L + END IF + Int_BufSz = Int_BufSz + 1 ! ID__F allocated yes/no + IF ( ALLOCATED(InData%ID__F) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! ID__F upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%ID__F) ! ID__F + END IF + Int_BufSz = Int_BufSz + 1 ! NMOutputs + Int_BufSz = Int_BufSz + 1 ! NumOuts + Int_BufSz = Int_BufSz + 1 ! OutSwtch + Int_BufSz = Int_BufSz + 1 ! UnJckF + Int_BufSz = Int_BufSz + 1*LEN(InData%Delim) ! Delim + Int_BufSz = Int_BufSz + 1*LEN(InData%OutFmt) ! OutFmt + Int_BufSz = Int_BufSz + 1*LEN(InData%OutSFmt) ! OutSFmt + Int_BufSz = Int_BufSz + 1 ! MoutLst allocated yes/no + IF ( ALLOCATED(InData%MoutLst) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! MoutLst upper/lower bounds for each dimension + DO i1 = LBOUND(InData%MoutLst,1), UBOUND(InData%MoutLst,1) + Int_BufSz = Int_BufSz + 3 ! MoutLst: size of buffers for each call to pack subtype + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! MoutLst + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! MoutLst + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! MoutLst + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! MoutLst2 allocated yes/no + IF ( ALLOCATED(InData%MoutLst2) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! MoutLst2 upper/lower bounds for each dimension + DO i1 = LBOUND(InData%MoutLst2,1), UBOUND(InData%MoutLst2,1) + Int_BufSz = Int_BufSz + 3 ! MoutLst2: size of buffers for each call to pack subtype + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst2(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst2 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! MoutLst2 + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! MoutLst2 + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! MoutLst2 + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! MoutLst3 allocated yes/no + IF ( ALLOCATED(InData%MoutLst3) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! MoutLst3 upper/lower bounds for each dimension + DO i1 = LBOUND(InData%MoutLst3,1), UBOUND(InData%MoutLst3,1) + Int_BufSz = Int_BufSz + 3 ! MoutLst3: size of buffers for each call to pack subtype + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst3(i1), ErrStat2, ErrMsg2, .TRUE. ) ! MoutLst3 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! MoutLst3 + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! MoutLst3 + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! MoutLst3 + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! OutParam allocated yes/no + IF ( ALLOCATED(InData%OutParam) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! OutParam upper/lower bounds for each dimension + DO i1 = LBOUND(InData%OutParam,1), UBOUND(InData%OutParam,1) + Int_BufSz = Int_BufSz + 3 ! OutParam: size of buffers for each call to pack subtype + CALL NWTC_Library_Packoutparmtype( Re_Buf, Db_Buf, Int_Buf, InData%OutParam(i1), ErrStat2, ErrMsg2, .TRUE. ) ! OutParam + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! OutParam + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! OutParam + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! OutParam + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + END DO + END IF + Int_BufSz = Int_BufSz + 1 ! OutAll + Int_BufSz = Int_BufSz + 1 ! OutCBModes + Int_BufSz = Int_BufSz + 1 ! OutFEMModes + Int_BufSz = Int_BufSz + 1 ! OutReact + Int_BufSz = Int_BufSz + 1 ! OutAllInt + Int_BufSz = Int_BufSz + 1 ! OutAllDims + Int_BufSz = Int_BufSz + 1 ! OutDec + Int_BufSz = Int_BufSz + 1 ! Jac_u_indx allocated yes/no + IF ( ALLOCATED(InData%Jac_u_indx) ) THEN + Int_BufSz = Int_BufSz + 2*2 ! Jac_u_indx upper/lower bounds for each dimension + Int_BufSz = Int_BufSz + SIZE(InData%Jac_u_indx) ! Jac_u_indx + END IF + Int_BufSz = Int_BufSz + 1 ! du allocated yes/no + IF ( ALLOCATED(InData%du) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! du upper/lower bounds for each dimension + Db_BufSz = Db_BufSz + SIZE(InData%du) ! du + END IF + Db_BufSz = Db_BufSz + SIZE(InData%dx) ! dx + Int_BufSz = Int_BufSz + 1 ! Jac_ny + Int_BufSz = Int_BufSz + 1 ! Jac_nx + Int_BufSz = Int_BufSz + 1 ! RotStates + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + DbKiBuf(Db_Xferred) = InData%SDDeltaT + Db_Xferred = Db_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%IntMethod + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOF + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOF_red + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%Nmembers + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Elems) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Elems,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Elems,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Elems,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Elems,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Elems,2), UBOUND(InData%Elems,2) + DO i1 = LBOUND(InData%Elems,1), UBOUND(InData%Elems,1) + IntKiBuf(Int_Xferred) = InData%Elems(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ElemProps) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemProps,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemProps,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%ElemProps,1), UBOUND(InData%ElemProps,1) + CALL SD_Packelemproptype( Re_Buf, Db_Buf, Int_Buf, InData%ElemProps(i1), ErrStat2, ErrMsg2, OnlySize ) ! ElemProps + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%FG) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%FG,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%FG,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%FG,1), UBOUND(InData%FG,1) + DbKiBuf(Db_Xferred) = InData%FG(i1) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%DP0) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DP0,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DP0,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DP0,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DP0,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%DP0,2), UBOUND(InData%DP0,2) + DO i1 = LBOUND(InData%DP0,1), UBOUND(InData%DP0,1) + ReKiBuf(Re_Xferred) = InData%DP0(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodeID2JointID) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodeID2JointID,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodeID2JointID,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%NodeID2JointID,1), UBOUND(InData%NodeID2JointID,1) + IntKiBuf(Int_Xferred) = InData%NodeID2JointID(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IntKiBuf(Int_Xferred) = TRANSFER(InData%reduced, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%T_red) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%T_red,2), UBOUND(InData%T_red,2) + DO i1 = LBOUND(InData%T_red,1), UBOUND(InData%T_red,1) + DbKiBuf(Db_Xferred) = InData%T_red(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%T_red_T) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red_T,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red_T,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%T_red_T,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%T_red_T,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%T_red_T,2), UBOUND(InData%T_red_T,2) + DO i1 = LBOUND(InData%T_red_T,1), UBOUND(InData%T_red_T,1) + DbKiBuf(Db_Xferred) = InData%T_red_T(i1,i2) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodesDOF) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesDOF,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesDOF,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%NodesDOF,1), UBOUND(InData%NodesDOF,1) + CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOF(i1), ErrStat2, ErrMsg2, OnlySize ) ! NodesDOF + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%NodesDOFred) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%NodesDOFred,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%NodesDOFred,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%NodesDOFred,1), UBOUND(InData%NodesDOFred,1) + CALL SD_Packilist( Re_Buf, Db_Buf, Int_Buf, InData%NodesDOFred(i1), ErrStat2, ErrMsg2, OnlySize ) ! NodesDOFred + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ElemsDOF) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemsDOF,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemsDOF,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ElemsDOF,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ElemsDOF,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%ElemsDOF,2), UBOUND(InData%ElemsDOF,2) + DO i1 = LBOUND(InData%ElemsDOF,1), UBOUND(InData%ElemsDOF,1) + IntKiBuf(Int_Xferred) = InData%ElemsDOF(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%DOFred2Nodes) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DOFred2Nodes,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DOFred2Nodes,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%DOFred2Nodes,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%DOFred2Nodes,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%DOFred2Nodes,2), UBOUND(InData%DOFred2Nodes,2) + DO i1 = LBOUND(InData%DOFred2Nodes,1), UBOUND(InData%DOFred2Nodes,1) + IntKiBuf(Int_Xferred) = InData%DOFred2Nodes(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CtrlElem2Channel) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CtrlElem2Channel,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CtrlElem2Channel,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CtrlElem2Channel,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CtrlElem2Channel,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%CtrlElem2Channel,2), UBOUND(InData%CtrlElem2Channel,2) + DO i1 = LBOUND(InData%CtrlElem2Channel,1), UBOUND(InData%CtrlElem2Channel,1) + IntKiBuf(Int_Xferred) = InData%CtrlElem2Channel(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IntKiBuf(Int_Xferred) = InData%nDOFM + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%SttcSolve + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%GuyanLoadCorrection, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%Floating, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%KMMDiag) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KMMDiag,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KMMDiag,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%KMMDiag,1), UBOUND(InData%KMMDiag,1) + ReKiBuf(Re_Xferred) = InData%KMMDiag(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CMMDiag) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CMMDiag,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMMDiag,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%CMMDiag,1), UBOUND(InData%CMMDiag,1) + ReKiBuf(Re_Xferred) = InData%CMMDiag(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MMB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MMB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MMB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MMB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MMB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MMB,2), UBOUND(InData%MMB,2) + DO i1 = LBOUND(InData%MMB,1), UBOUND(InData%MMB,1) + ReKiBuf(Re_Xferred) = InData%MMB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MBmmB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBmmB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBmmB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBmmB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBmmB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MBmmB,2), UBOUND(InData%MBmmB,2) + DO i1 = LBOUND(InData%MBmmB,1), UBOUND(InData%MBmmB,1) + ReKiBuf(Re_Xferred) = InData%MBmmB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%C1_11) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_11,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_11,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_11,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_11,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%C1_11,2), UBOUND(InData%C1_11,2) + DO i1 = LBOUND(InData%C1_11,1), UBOUND(InData%C1_11,1) + ReKiBuf(Re_Xferred) = InData%C1_11(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%C1_12) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_12,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_12,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C1_12,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C1_12,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%C1_12,2), UBOUND(InData%C1_12,2) + DO i1 = LBOUND(InData%C1_12,1), UBOUND(InData%C1_12,1) + ReKiBuf(Re_Xferred) = InData%C1_12(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%D1_141) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_141,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_141,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_141,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_141,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%D1_141,2), UBOUND(InData%D1_141,2) + DO i1 = LBOUND(InData%D1_141,1), UBOUND(InData%D1_141,1) + ReKiBuf(Re_Xferred) = InData%D1_141(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%D1_142) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_142,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_142,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D1_142,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D1_142,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%D1_142,2), UBOUND(InData%D1_142,2) + DO i1 = LBOUND(InData%D1_142,1), UBOUND(InData%D1_142,1) + ReKiBuf(Re_Xferred) = InData%D1_142(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiM,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiM,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiM,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiM,2), UBOUND(InData%PhiM,2) + DO i1 = LBOUND(InData%PhiM,1), UBOUND(InData%PhiM,1) + ReKiBuf(Re_Xferred) = InData%PhiM(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%C2_61) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_61,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_61,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_61,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_61,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%C2_61,2), UBOUND(InData%C2_61,2) + DO i1 = LBOUND(InData%C2_61,1), UBOUND(InData%C2_61,1) + ReKiBuf(Re_Xferred) = InData%C2_61(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%C2_62) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_62,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_62,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%C2_62,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%C2_62,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%C2_62,2), UBOUND(InData%C2_62,2) + DO i1 = LBOUND(InData%C2_62,1), UBOUND(InData%C2_62,1) + ReKiBuf(Re_Xferred) = InData%C2_62(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiRb_TI) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiRb_TI,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiRb_TI,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiRb_TI,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiRb_TI,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiRb_TI,2), UBOUND(InData%PhiRb_TI,2) + DO i1 = LBOUND(InData%PhiRb_TI,1), UBOUND(InData%PhiRb_TI,1) + ReKiBuf(Re_Xferred) = InData%PhiRb_TI(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%D2_63) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_63,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_63,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_63,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_63,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%D2_63,2), UBOUND(InData%D2_63,2) + DO i1 = LBOUND(InData%D2_63,1), UBOUND(InData%D2_63,1) + ReKiBuf(Re_Xferred) = InData%D2_63(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%D2_64) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_64,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_64,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%D2_64,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%D2_64,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%D2_64,2), UBOUND(InData%D2_64,2) + DO i1 = LBOUND(InData%D2_64,1), UBOUND(InData%D2_64,1) + ReKiBuf(Re_Xferred) = InData%D2_64(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MBB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MBB,2), UBOUND(InData%MBB,2) + DO i1 = LBOUND(InData%MBB,1), UBOUND(InData%MBB,1) + ReKiBuf(Re_Xferred) = InData%MBB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%KBB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KBB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KBB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%KBB,2), UBOUND(InData%KBB,2) + DO i1 = LBOUND(InData%KBB,1), UBOUND(InData%KBB,1) + ReKiBuf(Re_Xferred) = InData%KBB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CBB) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CBB,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CBB,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CBB,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CBB,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%CBB,2), UBOUND(InData%CBB,2) + DO i1 = LBOUND(InData%CBB,1), UBOUND(InData%CBB,1) + ReKiBuf(Re_Xferred) = InData%CBB(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%CMM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CMM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMM,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CMM,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CMM,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%CMM,2), UBOUND(InData%CMM,2) + DO i1 = LBOUND(InData%CMM,1), UBOUND(InData%CMM,1) + ReKiBuf(Re_Xferred) = InData%CMM(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MBM) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MBM,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MBM,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%MBM,2), UBOUND(InData%MBM,2) + DO i1 = LBOUND(InData%MBM,1), UBOUND(InData%MBM,1) + ReKiBuf(Re_Xferred) = InData%MBM(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiL_T) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL_T,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL_T,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiL_T,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiL_T,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiL_T,2), UBOUND(InData%PhiL_T,2) + DO i1 = LBOUND(InData%PhiL_T,1), UBOUND(InData%PhiL_T,1) + ReKiBuf(Re_Xferred) = InData%PhiL_T(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%PhiLInvOmgL2) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiLInvOmgL2,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiLInvOmgL2,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%PhiLInvOmgL2,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%PhiLInvOmgL2,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%PhiLInvOmgL2,2), UBOUND(InData%PhiLInvOmgL2,2) + DO i1 = LBOUND(InData%PhiLInvOmgL2,1), UBOUND(InData%PhiLInvOmgL2,1) + ReKiBuf(Re_Xferred) = InData%PhiLInvOmgL2(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%KLLm1) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KLLm1,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KLLm1,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%KLLm1,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%KLLm1,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%KLLm1,2), UBOUND(InData%KLLm1,2) + DO i1 = LBOUND(InData%KLLm1,1), UBOUND(InData%KLLm1,1) + ReKiBuf(Re_Xferred) = InData%KLLm1(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%AM2Jac) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2Jac,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2Jac,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2Jac,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2Jac,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%AM2Jac,2), UBOUND(InData%AM2Jac,2) + DO i1 = LBOUND(InData%AM2Jac,1), UBOUND(InData%AM2Jac,1) + ReKiBuf(Re_Xferred) = InData%AM2Jac(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%AM2JacPiv) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%AM2JacPiv,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%AM2JacPiv,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%AM2JacPiv,1), UBOUND(InData%AM2JacPiv,1) + IntKiBuf(Int_Xferred) = InData%AM2JacPiv(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%TI) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%TI,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TI,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%TI,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TI,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%TI,2), UBOUND(InData%TI,2) + DO i1 = LBOUND(InData%TI,1), UBOUND(InData%TI,1) + ReKiBuf(Re_Xferred) = InData%TI(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%TIreact) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%TIreact,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TIreact,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%TIreact,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%TIreact,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%TIreact,2), UBOUND(InData%TIreact,2) + DO i1 = LBOUND(InData%TIreact,1), UBOUND(InData%TIreact,1) + ReKiBuf(Re_Xferred) = InData%TIreact(i1,i2) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IntKiBuf(Int_Xferred) = InData%nNodes + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nNodes_I + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nNodes_L + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nNodes_C + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Nodes_I) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_I,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_I,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_I,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_I,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Nodes_I,2), UBOUND(InData%Nodes_I,2) + DO i1 = LBOUND(InData%Nodes_I,1), UBOUND(InData%Nodes_I,1) + IntKiBuf(Int_Xferred) = InData%Nodes_I(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Nodes_L) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_L,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_L,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_L,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_L,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Nodes_L,2), UBOUND(InData%Nodes_L,2) + DO i1 = LBOUND(InData%Nodes_L,1), UBOUND(InData%Nodes_L,1) + IntKiBuf(Int_Xferred) = InData%Nodes_L(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%Nodes_C) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_C,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_C,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Nodes_C,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Nodes_C,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Nodes_C,2), UBOUND(InData%Nodes_C,2) + DO i1 = LBOUND(InData%Nodes_C,1), UBOUND(InData%Nodes_C,1) + IntKiBuf(Int_Xferred) = InData%Nodes_C(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IntKiBuf(Int_Xferred) = InData%nDOFI__ + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFI_Rb + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFI_F + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFL_L + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFC__ + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFC_Rb + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFC_L + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFC_F + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOFR__ + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOF__Rb + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOF__L + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%nDOF__F + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%IDI__) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI__,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI__,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDI__,1), UBOUND(InData%IDI__,1) + IntKiBuf(Int_Xferred) = InData%IDI__(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDI_Rb) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI_Rb,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI_Rb,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDI_Rb,1), UBOUND(InData%IDI_Rb,1) + IntKiBuf(Int_Xferred) = InData%IDI_Rb(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDI_F) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDI_F,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDI_F,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDI_F,1), UBOUND(InData%IDI_F,1) + IntKiBuf(Int_Xferred) = InData%IDI_F(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDL_L) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDL_L,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDL_L,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDL_L,1), UBOUND(InData%IDL_L,1) + IntKiBuf(Int_Xferred) = InData%IDL_L(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDC__) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC__,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC__,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDC__,1), UBOUND(InData%IDC__,1) + IntKiBuf(Int_Xferred) = InData%IDC__(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDC_Rb) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_Rb,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_Rb,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDC_Rb,1), UBOUND(InData%IDC_Rb,1) + IntKiBuf(Int_Xferred) = InData%IDC_Rb(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDC_L) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_L,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_L,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDC_L,1), UBOUND(InData%IDC_L,1) + IntKiBuf(Int_Xferred) = InData%IDC_L(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDC_F) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDC_F,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDC_F,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDC_F,1), UBOUND(InData%IDC_F,1) + IntKiBuf(Int_Xferred) = InData%IDC_F(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%IDR__) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%IDR__,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%IDR__,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%IDR__,1), UBOUND(InData%IDR__,1) + IntKiBuf(Int_Xferred) = InData%IDR__(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ID__Rb) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__Rb,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__Rb,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%ID__Rb,1), UBOUND(InData%ID__Rb,1) + IntKiBuf(Int_Xferred) = InData%ID__Rb(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ID__L) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__L,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__L,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%ID__L,1), UBOUND(InData%ID__L,1) + IntKiBuf(Int_Xferred) = InData%ID__L(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( .NOT. ALLOCATED(InData%ID__F) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%ID__F,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%ID__F,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%ID__F,1), UBOUND(InData%ID__F,1) + IntKiBuf(Int_Xferred) = InData%ID__F(i1) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IntKiBuf(Int_Xferred) = InData%NMOutputs + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%NumOuts + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutSwtch + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%UnJckF + Int_Xferred = Int_Xferred + 1 + DO I = 1, LEN(InData%Delim) + IntKiBuf(Int_Xferred) = ICHAR(InData%Delim(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(InData%OutFmt) + IntKiBuf(Int_Xferred) = ICHAR(InData%OutFmt(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(InData%OutSFmt) + IntKiBuf(Int_Xferred) = ICHAR(InData%OutSFmt(I:I), IntKi) + Int_Xferred = Int_Xferred + 1 + END DO ! I + IF ( .NOT. ALLOCATED(InData%MoutLst) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%MoutLst,1), UBOUND(InData%MoutLst,1) + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MoutLst2) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst2,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst2,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%MoutLst2,1), UBOUND(InData%MoutLst2,1) + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst2(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst2 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%MoutLst3) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%MoutLst3,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%MoutLst3,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%MoutLst3,1), UBOUND(InData%MoutLst3,1) + CALL SD_Packmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, InData%MoutLst3(i1), ErrStat2, ErrMsg2, OnlySize ) ! MoutLst3 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IF ( .NOT. ALLOCATED(InData%OutParam) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%OutParam,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%OutParam,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%OutParam,1), UBOUND(InData%OutParam,1) + CALL NWTC_Library_Packoutparmtype( Re_Buf, Db_Buf, Int_Buf, InData%OutParam(i1), ErrStat2, ErrMsg2, OnlySize ) ! OutParam + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + END DO + END IF + IntKiBuf(Int_Xferred) = TRANSFER(InData%OutAll, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutCBModes + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutFEMModes + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%OutReact, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutAllInt + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutAllDims + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%OutDec + Int_Xferred = Int_Xferred + 1 + IF ( .NOT. ALLOCATED(InData%Jac_u_indx) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Jac_u_indx,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Jac_u_indx,1) + Int_Xferred = Int_Xferred + 2 + IntKiBuf( Int_Xferred ) = LBOUND(InData%Jac_u_indx,2) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%Jac_u_indx,2) + Int_Xferred = Int_Xferred + 2 + + DO i2 = LBOUND(InData%Jac_u_indx,2), UBOUND(InData%Jac_u_indx,2) + DO i1 = LBOUND(InData%Jac_u_indx,1), UBOUND(InData%Jac_u_indx,1) + IntKiBuf(Int_Xferred) = InData%Jac_u_indx(i1,i2) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( .NOT. ALLOCATED(InData%du) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%du,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%du,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%du,1), UBOUND(InData%du,1) + DbKiBuf(Db_Xferred) = InData%du(i1) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + DO i1 = LBOUND(InData%dx,1), UBOUND(InData%dx,1) + DbKiBuf(Db_Xferred) = InData%dx(i1) + Db_Xferred = Db_Xferred + 1 + END DO + IntKiBuf(Int_Xferred) = InData%Jac_ny + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = InData%Jac_nx + Int_Xferred = Int_Xferred + 1 + IntKiBuf(Int_Xferred) = TRANSFER(InData%RotStates, IntKiBuf(1)) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_PackParam + + SUBROUTINE SD_UnPackParam( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_ParameterType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: i2, i2_l, i2_u ! bounds (upper/lower) for an array dimension 2 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackParam' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + OutData%SDDeltaT = DbKiBuf(Db_Xferred) + Db_Xferred = Db_Xferred + 1 + OutData%IntMethod = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOF = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOF_red = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%Nmembers = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Elems not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Elems)) DEALLOCATE(OutData%Elems) + ALLOCATE(OutData%Elems(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Elems.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Elems,2), UBOUND(OutData%Elems,2) + DO i1 = LBOUND(OutData%Elems,1), UBOUND(OutData%Elems,1) + OutData%Elems(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemProps not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ElemProps)) DEALLOCATE(OutData%ElemProps) + ALLOCATE(OutData%ElemProps(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemProps.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%ElemProps,1), UBOUND(OutData%ElemProps,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackelemproptype( Re_Buf, Db_Buf, Int_Buf, OutData%ElemProps(i1), ErrStat2, ErrMsg2 ) ! ElemProps + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! FG not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%FG)) DEALLOCATE(OutData%FG) + ALLOCATE(OutData%FG(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%FG.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%FG,1), UBOUND(OutData%FG,1) + OutData%FG(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DP0 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%DP0)) DEALLOCATE(OutData%DP0) + ALLOCATE(OutData%DP0(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DP0.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%DP0,2), UBOUND(OutData%DP0,2) + DO i1 = LBOUND(OutData%DP0,1), UBOUND(OutData%DP0,1) + OutData%DP0(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodeID2JointID not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodeID2JointID)) DEALLOCATE(OutData%NodeID2JointID) + ALLOCATE(OutData%NodeID2JointID(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodeID2JointID.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%NodeID2JointID,1), UBOUND(OutData%NodeID2JointID,1) + OutData%NodeID2JointID(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + OutData%reduced = TRANSFER(IntKiBuf(Int_Xferred), OutData%reduced) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! T_red not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%T_red)) DEALLOCATE(OutData%T_red) + ALLOCATE(OutData%T_red(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%T_red.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%T_red,2), UBOUND(OutData%T_red,2) + DO i1 = LBOUND(OutData%T_red,1), UBOUND(OutData%T_red,1) + OutData%T_red(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! T_red_T not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%T_red_T)) DEALLOCATE(OutData%T_red_T) + ALLOCATE(OutData%T_red_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%T_red_T.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%T_red_T,2), UBOUND(OutData%T_red_T,2) + DO i1 = LBOUND(OutData%T_red_T,1), UBOUND(OutData%T_red_T,1) + OutData%T_red_T(i1,i2) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesDOF not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodesDOF)) DEALLOCATE(OutData%NodesDOF) + ALLOCATE(OutData%NodesDOF(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesDOF.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%NodesDOF,1), UBOUND(OutData%NodesDOF,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackilist( Re_Buf, Db_Buf, Int_Buf, OutData%NodesDOF(i1), ErrStat2, ErrMsg2 ) ! NodesDOF + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! NodesDOFred not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%NodesDOFred)) DEALLOCATE(OutData%NodesDOFred) + ALLOCATE(OutData%NodesDOFred(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%NodesDOFred.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%NodesDOFred,1), UBOUND(OutData%NodesDOFred,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackilist( Re_Buf, Db_Buf, Int_Buf, OutData%NodesDOFred(i1), ErrStat2, ErrMsg2 ) ! NodesDOFred + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ElemsDOF not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ElemsDOF)) DEALLOCATE(OutData%ElemsDOF) + ALLOCATE(OutData%ElemsDOF(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ElemsDOF.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%ElemsDOF,2), UBOUND(OutData%ElemsDOF,2) + DO i1 = LBOUND(OutData%ElemsDOF,1), UBOUND(OutData%ElemsDOF,1) + OutData%ElemsDOF(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! DOFred2Nodes not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%DOFred2Nodes)) DEALLOCATE(OutData%DOFred2Nodes) + ALLOCATE(OutData%DOFred2Nodes(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%DOFred2Nodes.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%DOFred2Nodes,2), UBOUND(OutData%DOFred2Nodes,2) + DO i1 = LBOUND(OutData%DOFred2Nodes,1), UBOUND(OutData%DOFred2Nodes,1) + OutData%DOFred2Nodes(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CtrlElem2Channel not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CtrlElem2Channel)) DEALLOCATE(OutData%CtrlElem2Channel) + ALLOCATE(OutData%CtrlElem2Channel(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CtrlElem2Channel.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%CtrlElem2Channel,2), UBOUND(OutData%CtrlElem2Channel,2) + DO i1 = LBOUND(OutData%CtrlElem2Channel,1), UBOUND(OutData%CtrlElem2Channel,1) + OutData%CtrlElem2Channel(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + OutData%nDOFM = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%SttcSolve = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%GuyanLoadCorrection = TRANSFER(IntKiBuf(Int_Xferred), OutData%GuyanLoadCorrection) + Int_Xferred = Int_Xferred + 1 + OutData%Floating = TRANSFER(IntKiBuf(Int_Xferred), OutData%Floating) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KMMDiag not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%KMMDiag)) DEALLOCATE(OutData%KMMDiag) + ALLOCATE(OutData%KMMDiag(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KMMDiag.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%KMMDiag,1), UBOUND(OutData%KMMDiag,1) + OutData%KMMDiag(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMMDiag not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CMMDiag)) DEALLOCATE(OutData%CMMDiag) + ALLOCATE(OutData%CMMDiag(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMMDiag.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%CMMDiag,1), UBOUND(OutData%CMMDiag,1) + OutData%CMMDiag(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MMB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MMB)) DEALLOCATE(OutData%MMB) + ALLOCATE(OutData%MMB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MMB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MMB,2), UBOUND(OutData%MMB,2) + DO i1 = LBOUND(OutData%MMB,1), UBOUND(OutData%MMB,1) + OutData%MMB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBmmB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MBmmB)) DEALLOCATE(OutData%MBmmB) + ALLOCATE(OutData%MBmmB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBmmB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MBmmB,2), UBOUND(OutData%MBmmB,2) + DO i1 = LBOUND(OutData%MBmmB,1), UBOUND(OutData%MBmmB,1) + OutData%MBmmB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C1_11 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%C1_11)) DEALLOCATE(OutData%C1_11) + ALLOCATE(OutData%C1_11(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C1_11.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%C1_11,2), UBOUND(OutData%C1_11,2) + DO i1 = LBOUND(OutData%C1_11,1), UBOUND(OutData%C1_11,1) + OutData%C1_11(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C1_12 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%C1_12)) DEALLOCATE(OutData%C1_12) + ALLOCATE(OutData%C1_12(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C1_12.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%C1_12,2), UBOUND(OutData%C1_12,2) + DO i1 = LBOUND(OutData%C1_12,1), UBOUND(OutData%C1_12,1) + OutData%C1_12(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D1_141 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%D1_141)) DEALLOCATE(OutData%D1_141) + ALLOCATE(OutData%D1_141(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D1_141.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%D1_141,2), UBOUND(OutData%D1_141,2) + DO i1 = LBOUND(OutData%D1_141,1), UBOUND(OutData%D1_141,1) + OutData%D1_141(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D1_142 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%D1_142)) DEALLOCATE(OutData%D1_142) + ALLOCATE(OutData%D1_142(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D1_142.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%D1_142,2), UBOUND(OutData%D1_142,2) + DO i1 = LBOUND(OutData%D1_142,1), UBOUND(OutData%D1_142,1) + OutData%D1_142(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiM)) DEALLOCATE(OutData%PhiM) + ALLOCATE(OutData%PhiM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiM,2), UBOUND(OutData%PhiM,2) + DO i1 = LBOUND(OutData%PhiM,1), UBOUND(OutData%PhiM,1) + OutData%PhiM(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C2_61 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%C2_61)) DEALLOCATE(OutData%C2_61) + ALLOCATE(OutData%C2_61(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C2_61.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%C2_61,2), UBOUND(OutData%C2_61,2) + DO i1 = LBOUND(OutData%C2_61,1), UBOUND(OutData%C2_61,1) + OutData%C2_61(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! C2_62 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%C2_62)) DEALLOCATE(OutData%C2_62) + ALLOCATE(OutData%C2_62(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%C2_62.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%C2_62,2), UBOUND(OutData%C2_62,2) + DO i1 = LBOUND(OutData%C2_62,1), UBOUND(OutData%C2_62,1) + OutData%C2_62(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiRb_TI not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiRb_TI)) DEALLOCATE(OutData%PhiRb_TI) + ALLOCATE(OutData%PhiRb_TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiRb_TI.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiRb_TI,2), UBOUND(OutData%PhiRb_TI,2) + DO i1 = LBOUND(OutData%PhiRb_TI,1), UBOUND(OutData%PhiRb_TI,1) + OutData%PhiRb_TI(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D2_63 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%D2_63)) DEALLOCATE(OutData%D2_63) + ALLOCATE(OutData%D2_63(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D2_63.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%D2_63,2), UBOUND(OutData%D2_63,2) + DO i1 = LBOUND(OutData%D2_63,1), UBOUND(OutData%D2_63,1) + OutData%D2_63(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! D2_64 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%D2_64)) DEALLOCATE(OutData%D2_64) + ALLOCATE(OutData%D2_64(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%D2_64.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%D2_64,2), UBOUND(OutData%D2_64,2) + DO i1 = LBOUND(OutData%D2_64,1), UBOUND(OutData%D2_64,1) + OutData%D2_64(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MBB)) DEALLOCATE(OutData%MBB) + ALLOCATE(OutData%MBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MBB,2), UBOUND(OutData%MBB,2) + DO i1 = LBOUND(OutData%MBB,1), UBOUND(OutData%MBB,1) + OutData%MBB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KBB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%KBB)) DEALLOCATE(OutData%KBB) + ALLOCATE(OutData%KBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%KBB,2), UBOUND(OutData%KBB,2) + DO i1 = LBOUND(OutData%KBB,1), UBOUND(OutData%KBB,1) + OutData%KBB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CBB not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CBB)) DEALLOCATE(OutData%CBB) + ALLOCATE(OutData%CBB(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CBB.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%CBB,2), UBOUND(OutData%CBB,2) + DO i1 = LBOUND(OutData%CBB,1), UBOUND(OutData%CBB,1) + OutData%CBB(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CMM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CMM)) DEALLOCATE(OutData%CMM) + ALLOCATE(OutData%CMM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CMM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%CMM,2), UBOUND(OutData%CMM,2) + DO i1 = LBOUND(OutData%CMM,1), UBOUND(OutData%CMM,1) + OutData%CMM(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MBM not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MBM)) DEALLOCATE(OutData%MBM) + ALLOCATE(OutData%MBM(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MBM.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%MBM,2), UBOUND(OutData%MBM,2) + DO i1 = LBOUND(OutData%MBM,1), UBOUND(OutData%MBM,1) + OutData%MBM(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiL_T not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiL_T)) DEALLOCATE(OutData%PhiL_T) + ALLOCATE(OutData%PhiL_T(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiL_T.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiL_T,2), UBOUND(OutData%PhiL_T,2) + DO i1 = LBOUND(OutData%PhiL_T,1), UBOUND(OutData%PhiL_T,1) + OutData%PhiL_T(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! PhiLInvOmgL2 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%PhiLInvOmgL2)) DEALLOCATE(OutData%PhiLInvOmgL2) + ALLOCATE(OutData%PhiLInvOmgL2(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%PhiLInvOmgL2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%PhiLInvOmgL2,2), UBOUND(OutData%PhiLInvOmgL2,2) + DO i1 = LBOUND(OutData%PhiLInvOmgL2,1), UBOUND(OutData%PhiLInvOmgL2,1) + OutData%PhiLInvOmgL2(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! KLLm1 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%KLLm1)) DEALLOCATE(OutData%KLLm1) + ALLOCATE(OutData%KLLm1(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%KLLm1.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%KLLm1,2), UBOUND(OutData%KLLm1,2) + DO i1 = LBOUND(OutData%KLLm1,1), UBOUND(OutData%KLLm1,1) + OutData%KLLm1(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AM2Jac not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%AM2Jac)) DEALLOCATE(OutData%AM2Jac) + ALLOCATE(OutData%AM2Jac(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AM2Jac.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%AM2Jac,2), UBOUND(OutData%AM2Jac,2) + DO i1 = LBOUND(OutData%AM2Jac,1), UBOUND(OutData%AM2Jac,1) + OutData%AM2Jac(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! AM2JacPiv not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%AM2JacPiv)) DEALLOCATE(OutData%AM2JacPiv) + ALLOCATE(OutData%AM2JacPiv(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%AM2JacPiv.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%AM2JacPiv,1), UBOUND(OutData%AM2JacPiv,1) + OutData%AM2JacPiv(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! TI not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%TI)) DEALLOCATE(OutData%TI) + ALLOCATE(OutData%TI(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%TI.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%TI,2), UBOUND(OutData%TI,2) + DO i1 = LBOUND(OutData%TI,1), UBOUND(OutData%TI,1) + OutData%TI(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! TIreact not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%TIreact)) DEALLOCATE(OutData%TIreact) + ALLOCATE(OutData%TIreact(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%TIreact.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%TIreact,2), UBOUND(OutData%TIreact,2) + DO i1 = LBOUND(OutData%TIreact,1), UBOUND(OutData%TIreact,1) + OutData%TIreact(i1,i2) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END DO + END IF + OutData%nNodes = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nNodes_I = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nNodes_L = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nNodes_C = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_I not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Nodes_I)) DEALLOCATE(OutData%Nodes_I) + ALLOCATE(OutData%Nodes_I(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_I.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Nodes_I,2), UBOUND(OutData%Nodes_I,2) + DO i1 = LBOUND(OutData%Nodes_I,1), UBOUND(OutData%Nodes_I,1) + OutData%Nodes_I(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_L not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Nodes_L)) DEALLOCATE(OutData%Nodes_L) + ALLOCATE(OutData%Nodes_L(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Nodes_L,2), UBOUND(OutData%Nodes_L,2) + DO i1 = LBOUND(OutData%Nodes_L,1), UBOUND(OutData%Nodes_L,1) + OutData%Nodes_L(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Nodes_C not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Nodes_C)) DEALLOCATE(OutData%Nodes_C) + ALLOCATE(OutData%Nodes_C(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Nodes_C.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Nodes_C,2), UBOUND(OutData%Nodes_C,2) + DO i1 = LBOUND(OutData%Nodes_C,1), UBOUND(OutData%Nodes_C,1) + OutData%Nodes_C(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + OutData%nDOFI__ = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFI_Rb = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFI_F = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFL_L = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFC__ = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFC_Rb = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFC_L = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFC_F = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOFR__ = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOF__Rb = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOF__L = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%nDOF__F = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI__ not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDI__)) DEALLOCATE(OutData%IDI__) + ALLOCATE(OutData%IDI__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDI__,1), UBOUND(OutData%IDI__,1) + OutData%IDI__(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI_Rb not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDI_Rb)) DEALLOCATE(OutData%IDI_Rb) + ALLOCATE(OutData%IDI_Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI_Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDI_Rb,1), UBOUND(OutData%IDI_Rb,1) + OutData%IDI_Rb(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDI_F not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDI_F)) DEALLOCATE(OutData%IDI_F) + ALLOCATE(OutData%IDI_F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDI_F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDI_F,1), UBOUND(OutData%IDI_F,1) + OutData%IDI_F(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDL_L not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDL_L)) DEALLOCATE(OutData%IDL_L) + ALLOCATE(OutData%IDL_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDL_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDL_L,1), UBOUND(OutData%IDL_L,1) + OutData%IDL_L(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC__ not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDC__)) DEALLOCATE(OutData%IDC__) + ALLOCATE(OutData%IDC__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDC__,1), UBOUND(OutData%IDC__,1) + OutData%IDC__(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_Rb not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDC_Rb)) DEALLOCATE(OutData%IDC_Rb) + ALLOCATE(OutData%IDC_Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDC_Rb,1), UBOUND(OutData%IDC_Rb,1) + OutData%IDC_Rb(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_L not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDC_L)) DEALLOCATE(OutData%IDC_L) + ALLOCATE(OutData%IDC_L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDC_L,1), UBOUND(OutData%IDC_L,1) + OutData%IDC_L(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDC_F not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDC_F)) DEALLOCATE(OutData%IDC_F) + ALLOCATE(OutData%IDC_F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDC_F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDC_F,1), UBOUND(OutData%IDC_F,1) + OutData%IDC_F(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! IDR__ not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%IDR__)) DEALLOCATE(OutData%IDR__) + ALLOCATE(OutData%IDR__(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%IDR__.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%IDR__,1), UBOUND(OutData%IDR__,1) + OutData%IDR__(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__Rb not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ID__Rb)) DEALLOCATE(OutData%ID__Rb) + ALLOCATE(OutData%ID__Rb(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__Rb.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%ID__Rb,1), UBOUND(OutData%ID__Rb,1) + OutData%ID__Rb(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__L not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ID__L)) DEALLOCATE(OutData%ID__L) + ALLOCATE(OutData%ID__L(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__L.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%ID__L,1), UBOUND(OutData%ID__L,1) + OutData%ID__L(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! ID__F not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%ID__F)) DEALLOCATE(OutData%ID__F) + ALLOCATE(OutData%ID__F(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%ID__F.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%ID__F,1), UBOUND(OutData%ID__F,1) + OutData%ID__F(i1) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END IF + OutData%NMOutputs = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%NumOuts = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%OutSwtch = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%UnJckF = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + DO I = 1, LEN(OutData%Delim) + OutData%Delim(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(OutData%OutFmt) + OutData%OutFmt(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + DO I = 1, LEN(OutData%OutSFmt) + OutData%OutSFmt(I:I) = CHAR(IntKiBuf(Int_Xferred)) + Int_Xferred = Int_Xferred + 1 + END DO ! I + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MoutLst)) DEALLOCATE(OutData%MoutLst) + ALLOCATE(OutData%MoutLst(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%MoutLst,1), UBOUND(OutData%MoutLst,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst(i1), ErrStat2, ErrMsg2 ) ! MoutLst + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst2 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MoutLst2)) DEALLOCATE(OutData%MoutLst2) + ALLOCATE(OutData%MoutLst2(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst2.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%MoutLst2,1), UBOUND(OutData%MoutLst2,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst2(i1), ErrStat2, ErrMsg2 ) ! MoutLst2 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! MoutLst3 not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%MoutLst3)) DEALLOCATE(OutData%MoutLst3) + ALLOCATE(OutData%MoutLst3(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%MoutLst3.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%MoutLst3,1), UBOUND(OutData%MoutLst3,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL SD_Unpackmeshauxdatatype( Re_Buf, Db_Buf, Int_Buf, OutData%MoutLst3(i1), ErrStat2, ErrMsg2 ) ! MoutLst3 + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! OutParam not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%OutParam)) DEALLOCATE(OutData%OutParam) + ALLOCATE(OutData%OutParam(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%OutParam.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%OutParam,1), UBOUND(OutData%OutParam,1) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL NWTC_Library_Unpackoutparmtype( Re_Buf, Db_Buf, Int_Buf, OutData%OutParam(i1), ErrStat2, ErrMsg2 ) ! OutParam + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + END DO + END IF + OutData%OutAll = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutAll) + Int_Xferred = Int_Xferred + 1 + OutData%OutCBModes = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%OutFEMModes = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%OutReact = TRANSFER(IntKiBuf(Int_Xferred), OutData%OutReact) + Int_Xferred = Int_Xferred + 1 + OutData%OutAllInt = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%OutAllDims = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%OutDec = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! Jac_u_indx not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + i2_l = IntKiBuf( Int_Xferred ) + i2_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%Jac_u_indx)) DEALLOCATE(OutData%Jac_u_indx) + ALLOCATE(OutData%Jac_u_indx(i1_l:i1_u,i2_l:i2_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%Jac_u_indx.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i2 = LBOUND(OutData%Jac_u_indx,2), UBOUND(OutData%Jac_u_indx,2) + DO i1 = LBOUND(OutData%Jac_u_indx,1), UBOUND(OutData%Jac_u_indx,1) + OutData%Jac_u_indx(i1,i2) = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + END DO + END DO + END IF + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! du not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%du)) DEALLOCATE(OutData%du) + ALLOCATE(OutData%du(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%du.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%du,1), UBOUND(OutData%du,1) + OutData%du(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + END IF + i1_l = LBOUND(OutData%dx,1) + i1_u = UBOUND(OutData%dx,1) + DO i1 = LBOUND(OutData%dx,1), UBOUND(OutData%dx,1) + OutData%dx(i1) = REAL(DbKiBuf(Db_Xferred), R8Ki) + Db_Xferred = Db_Xferred + 1 + END DO + OutData%Jac_ny = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%Jac_nx = IntKiBuf(Int_Xferred) + Int_Xferred = Int_Xferred + 1 + OutData%RotStates = TRANSFER(IntKiBuf(Int_Xferred), OutData%RotStates) + Int_Xferred = Int_Xferred + 1 + END SUBROUTINE SD_UnPackParam + + SUBROUTINE SD_CopyInput( SrcInputData, DstInputData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_InputType), INTENT(INOUT) :: SrcInputData + TYPE(SD_InputType), INTENT(INOUT) :: DstInputData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyInput' +! + ErrStat = ErrID_None + ErrMsg = "" + CALL MeshCopy( SrcInputData%TPMesh, DstInputData%TPMesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + CALL MeshCopy( SrcInputData%LMesh, DstInputData%LMesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN +IF (ALLOCATED(SrcInputData%CableDeltaL)) THEN + i1_l = LBOUND(SrcInputData%CableDeltaL,1) + i1_u = UBOUND(SrcInputData%CableDeltaL,1) + IF (.NOT. ALLOCATED(DstInputData%CableDeltaL)) THEN + ALLOCATE(DstInputData%CableDeltaL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstInputData%CableDeltaL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstInputData%CableDeltaL = SrcInputData%CableDeltaL +ENDIF + END SUBROUTINE SD_CopyInput + + SUBROUTINE SD_DestroyInput( InputData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_InputType), INTENT(INOUT) :: InputData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyInput' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + + CALL MeshDestroy( InputData%TPMesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + CALL MeshDestroy( InputData%LMesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +IF (ALLOCATED(InputData%CableDeltaL)) THEN + DEALLOCATE(InputData%CableDeltaL) +ENDIF + END SUBROUTINE SD_DestroyInput + + SUBROUTINE SD_PackInput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_InputType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackInput' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + Int_BufSz = Int_BufSz + 3 ! TPMesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! TPMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! TPMesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! TPMesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! TPMesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 3 ! LMesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! LMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! LMesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! LMesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! LMesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 1 ! CableDeltaL allocated yes/no + IF ( ALLOCATED(InData%CableDeltaL) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! CableDeltaL upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%CableDeltaL) ! CableDeltaL + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + CALL MeshPack( InData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! TPMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + CALL MeshPack( InData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! LMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF ( .NOT. ALLOCATED(InData%CableDeltaL) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%CableDeltaL,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%CableDeltaL,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%CableDeltaL,1), UBOUND(InData%CableDeltaL,1) + ReKiBuf(Re_Xferred) = InData%CableDeltaL(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackInput + + SUBROUTINE SD_UnPackInput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_InputType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackInput' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%TPMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! TPMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%LMesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! LMesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! CableDeltaL not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%CableDeltaL)) DEALLOCATE(OutData%CableDeltaL) + ALLOCATE(OutData%CableDeltaL(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%CableDeltaL.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%CableDeltaL,1), UBOUND(OutData%CableDeltaL,1) + OutData%CableDeltaL(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackInput + + SUBROUTINE SD_CopyOutput( SrcOutputData, DstOutputData, CtrlCode, ErrStat, ErrMsg ) + TYPE(SD_OutputType), INTENT(INOUT) :: SrcOutputData + TYPE(SD_OutputType), INTENT(INOUT) :: DstOutputData + INTEGER(IntKi), INTENT(IN ) :: CtrlCode + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg +! Local + INTEGER(IntKi) :: i,j,k + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_CopyOutput' +! + ErrStat = ErrID_None + ErrMsg = "" + CALL MeshCopy( SrcOutputData%Y1Mesh, DstOutputData%Y1Mesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + CALL MeshCopy( SrcOutputData%Y2Mesh, DstOutputData%Y2Mesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN + CALL MeshCopy( SrcOutputData%Y3Mesh, DstOutputData%Y3Mesh, CtrlCode, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat>=AbortErrLev) RETURN +IF (ALLOCATED(SrcOutputData%WriteOutput)) THEN + i1_l = LBOUND(SrcOutputData%WriteOutput,1) + i1_u = UBOUND(SrcOutputData%WriteOutput,1) + IF (.NOT. ALLOCATED(DstOutputData%WriteOutput)) THEN + ALLOCATE(DstOutputData%WriteOutput(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DstOutputData%WriteOutput.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + DstOutputData%WriteOutput = SrcOutputData%WriteOutput +ENDIF + END SUBROUTINE SD_CopyOutput + + SUBROUTINE SD_DestroyOutput( OutputData, ErrStat, ErrMsg, DEALLOCATEpointers ) + TYPE(SD_OutputType), INTENT(INOUT) :: OutputData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL,INTENT(IN ) :: DEALLOCATEpointers + + INTEGER(IntKi) :: i, i1, i2, i3, i4, i5 + LOGICAL :: DEALLOCATEpointers_local + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_DestroyOutput' + + ErrStat = ErrID_None + ErrMsg = "" + + IF (PRESENT(DEALLOCATEpointers)) THEN + DEALLOCATEpointers_local = DEALLOCATEpointers + ELSE + DEALLOCATEpointers_local = .true. + END IF + + CALL MeshDestroy( OutputData%Y1Mesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + CALL MeshDestroy( OutputData%Y2Mesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + CALL MeshDestroy( OutputData%Y3Mesh, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) +IF (ALLOCATED(OutputData%WriteOutput)) THEN + DEALLOCATE(OutputData%WriteOutput) +ENDIF + END SUBROUTINE SD_DestroyOutput + + SUBROUTINE SD_PackOutput( ReKiBuf, DbKiBuf, IntKiBuf, Indata, ErrStat, ErrMsg, SizeOnly ) + REAL(ReKi), ALLOCATABLE, INTENT( OUT) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT( OUT) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT( OUT) :: IntKiBuf(:) + TYPE(SD_OutputType), INTENT(IN) :: InData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + LOGICAL,OPTIONAL, INTENT(IN ) :: SizeOnly + ! Local variables + INTEGER(IntKi) :: Re_BufSz + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_BufSz + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_BufSz + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i,i1,i2,i3,i4,i5 + LOGICAL :: OnlySize ! if present and true, do not pack, just allocate buffers + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_PackOutput' + ! buffers to store subtypes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + + OnlySize = .FALSE. + IF ( PRESENT(SizeOnly) ) THEN + OnlySize = SizeOnly + ENDIF + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_BufSz = 0 + Db_BufSz = 0 + Int_BufSz = 0 + ! Allocate buffers for subtypes, if any (we'll get sizes from these) + Int_BufSz = Int_BufSz + 3 ! Y1Mesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y1Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! Y1Mesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! Y1Mesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! Y1Mesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 3 ! Y2Mesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y2Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! Y2Mesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! Y2Mesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! Y2Mesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 3 ! Y3Mesh: size of buffers for each call to pack subtype + CALL MeshPack( InData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, .TRUE. ) ! Y3Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN ! Y3Mesh + Re_BufSz = Re_BufSz + SIZE( Re_Buf ) + DEALLOCATE(Re_Buf) + END IF + IF(ALLOCATED(Db_Buf)) THEN ! Y3Mesh + Db_BufSz = Db_BufSz + SIZE( Db_Buf ) + DEALLOCATE(Db_Buf) + END IF + IF(ALLOCATED(Int_Buf)) THEN ! Y3Mesh + Int_BufSz = Int_BufSz + SIZE( Int_Buf ) + DEALLOCATE(Int_Buf) + END IF + Int_BufSz = Int_BufSz + 1 ! WriteOutput allocated yes/no + IF ( ALLOCATED(InData%WriteOutput) ) THEN + Int_BufSz = Int_BufSz + 2*1 ! WriteOutput upper/lower bounds for each dimension + Re_BufSz = Re_BufSz + SIZE(InData%WriteOutput) ! WriteOutput + END IF + IF ( Re_BufSz .GT. 0 ) THEN + ALLOCATE( ReKiBuf( Re_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating ReKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Db_BufSz .GT. 0 ) THEN + ALLOCATE( DbKiBuf( Db_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating DbKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF ( Int_BufSz .GT. 0 ) THEN + ALLOCATE( IntKiBuf( Int_BufSz ), STAT=ErrStat2 ) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating IntKiBuf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + END IF + IF(OnlySize) RETURN ! return early if only trying to allocate buffers (not pack them) + + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + + CALL MeshPack( InData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y1Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + CALL MeshPack( InData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y2Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + CALL MeshPack( InData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2, OnlySize ) ! Y3Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Re_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Re_Buf) > 0) ReKiBuf( Re_Xferred:Re_Xferred+SIZE(Re_Buf)-1 ) = Re_Buf + Re_Xferred = Re_Xferred + SIZE(Re_Buf) + DEALLOCATE(Re_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Db_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Db_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Db_Buf) > 0) DbKiBuf( Db_Xferred:Db_Xferred+SIZE(Db_Buf)-1 ) = Db_Buf + Db_Xferred = Db_Xferred + SIZE(Db_Buf) + DEALLOCATE(Db_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF(ALLOCATED(Int_Buf)) THEN + IntKiBuf( Int_Xferred ) = SIZE(Int_Buf); Int_Xferred = Int_Xferred + 1 + IF (SIZE(Int_Buf) > 0) IntKiBuf( Int_Xferred:Int_Xferred+SIZE(Int_Buf)-1 ) = Int_Buf + Int_Xferred = Int_Xferred + SIZE(Int_Buf) + DEALLOCATE(Int_Buf) + ELSE + IntKiBuf( Int_Xferred ) = 0; Int_Xferred = Int_Xferred + 1 + ENDIF + IF ( .NOT. ALLOCATED(InData%WriteOutput) ) THEN + IntKiBuf( Int_Xferred ) = 0 + Int_Xferred = Int_Xferred + 1 + ELSE + IntKiBuf( Int_Xferred ) = 1 + Int_Xferred = Int_Xferred + 1 + IntKiBuf( Int_Xferred ) = LBOUND(InData%WriteOutput,1) + IntKiBuf( Int_Xferred + 1) = UBOUND(InData%WriteOutput,1) + Int_Xferred = Int_Xferred + 2 + + DO i1 = LBOUND(InData%WriteOutput,1), UBOUND(InData%WriteOutput,1) + ReKiBuf(Re_Xferred) = InData%WriteOutput(i1) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_PackOutput + + SUBROUTINE SD_UnPackOutput( ReKiBuf, DbKiBuf, IntKiBuf, Outdata, ErrStat, ErrMsg ) + REAL(ReKi), ALLOCATABLE, INTENT(IN ) :: ReKiBuf(:) + REAL(DbKi), ALLOCATABLE, INTENT(IN ) :: DbKiBuf(:) + INTEGER(IntKi), ALLOCATABLE, INTENT(IN ) :: IntKiBuf(:) + TYPE(SD_OutputType), INTENT(INOUT) :: OutData + INTEGER(IntKi), INTENT( OUT) :: ErrStat + CHARACTER(*), INTENT( OUT) :: ErrMsg + ! Local variables + INTEGER(IntKi) :: Buf_size + INTEGER(IntKi) :: Re_Xferred + INTEGER(IntKi) :: Db_Xferred + INTEGER(IntKi) :: Int_Xferred + INTEGER(IntKi) :: i + INTEGER(IntKi) :: i1, i1_l, i1_u ! bounds (upper/lower) for an array dimension 1 + INTEGER(IntKi) :: ErrStat2 + CHARACTER(ErrMsgLen) :: ErrMsg2 + CHARACTER(*), PARAMETER :: RoutineName = 'SD_UnPackOutput' + ! buffers to store meshes, if any + REAL(ReKi), ALLOCATABLE :: Re_Buf(:) + REAL(DbKi), ALLOCATABLE :: Db_Buf(:) + INTEGER(IntKi), ALLOCATABLE :: Int_Buf(:) + ! + ErrStat = ErrID_None + ErrMsg = "" + Re_Xferred = 1 + Db_Xferred = 1 + Int_Xferred = 1 + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%Y1Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y1Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%Y2Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y2Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Re_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Re_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Re_Buf = ReKiBuf( Re_Xferred:Re_Xferred+Buf_size-1 ) + Re_Xferred = Re_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Db_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Db_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Db_Buf = DbKiBuf( Db_Xferred:Db_Xferred+Buf_size-1 ) + Db_Xferred = Db_Xferred + Buf_size + END IF + Buf_size=IntKiBuf( Int_Xferred ) + Int_Xferred = Int_Xferred + 1 + IF(Buf_size > 0) THEN + ALLOCATE(Int_Buf(Buf_size),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating Int_Buf.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + Int_Buf = IntKiBuf( Int_Xferred:Int_Xferred+Buf_size-1 ) + Int_Xferred = Int_Xferred + Buf_size + END IF + CALL MeshUnpack( OutData%Y3Mesh, Re_Buf, Db_Buf, Int_Buf, ErrStat2, ErrMsg2 ) ! Y3Mesh + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName) + IF (ErrStat >= AbortErrLev) RETURN + + IF(ALLOCATED(Re_Buf )) DEALLOCATE(Re_Buf ) + IF(ALLOCATED(Db_Buf )) DEALLOCATE(Db_Buf ) + IF(ALLOCATED(Int_Buf)) DEALLOCATE(Int_Buf) + IF ( IntKiBuf( Int_Xferred ) == 0 ) THEN ! WriteOutput not allocated + Int_Xferred = Int_Xferred + 1 + ELSE + Int_Xferred = Int_Xferred + 1 + i1_l = IntKiBuf( Int_Xferred ) + i1_u = IntKiBuf( Int_Xferred + 1) + Int_Xferred = Int_Xferred + 2 + IF (ALLOCATED(OutData%WriteOutput)) DEALLOCATE(OutData%WriteOutput) + ALLOCATE(OutData%WriteOutput(i1_l:i1_u),STAT=ErrStat2) + IF (ErrStat2 /= 0) THEN + CALL SetErrStat(ErrID_Fatal, 'Error allocating OutData%WriteOutput.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + DO i1 = LBOUND(OutData%WriteOutput,1), UBOUND(OutData%WriteOutput,1) + OutData%WriteOutput(i1) = ReKiBuf(Re_Xferred) + Re_Xferred = Re_Xferred + 1 + END DO + END IF + END SUBROUTINE SD_UnPackOutput + + + SUBROUTINE SD_Input_ExtrapInterp(u, t, u_out, t_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time +! values of u (which has values associated with times in t). Order of the interpolation is given by the size of u +! +! expressions below based on either +! +! f(t) = a +! f(t) = a + b * t, or +! f(t) = a + b * t + c * t**2 +! +! where a, b and c are determined as the solution to +! f(t1) = u1, f(t2) = u2, f(t3) = u3 (as appropriate) +! +!.................................................................................................................................. + + TYPE(SD_InputType), INTENT(INOUT) :: u(:) ! Input at t1 > t2 > t3 + REAL(DbKi), INTENT(IN ) :: t(:) ! Times associated with the Inputs + TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out + REAL(DbKi), INTENT(IN ) :: t_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + INTEGER(IntKi) :: order ! order of polynomial fit (max 2) + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp' + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + if ( size(t) .ne. size(u)) then + CALL SetErrStat(ErrID_Fatal,'size(t) must equal size(u)',ErrStat,ErrMsg,RoutineName) + RETURN + endif + order = SIZE(u) - 1 + IF ( order .eq. 0 ) THEN + CALL SD_CopyInput(u(1), u_out, MESH_UPDATECOPY, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE IF ( order .eq. 1 ) THEN + CALL SD_Input_ExtrapInterp1(u(1), u(2), t, u_out, t_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE IF ( order .eq. 2 ) THEN + CALL SD_Input_ExtrapInterp2(u(1), u(2), u(3), t, u_out, t_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE + CALL SetErrStat(ErrID_Fatal,'size(u) must be less than 4 (order must be less than 3).',ErrStat,ErrMsg,RoutineName) + RETURN + ENDIF + END SUBROUTINE SD_Input_ExtrapInterp + + + SUBROUTINE SD_Input_ExtrapInterp1(u1, u2, tin, u_out, tin_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time +! values of u (which has values associated with times in t). Order of the interpolation is 1. +! +! f(t) = a + b * t, or +! +! where a and b are determined as the solution to +! f(t1) = u1, f(t2) = u2 +! +!.................................................................................................................................. + + TYPE(SD_InputType), INTENT(INOUT) :: u1 ! Input at t1 > t2 + TYPE(SD_InputType), INTENT(INOUT) :: u2 ! Input at t2 + REAL(DbKi), INTENT(IN ) :: tin(2) ! Times associated with the Inputs + TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out + REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + REAL(DbKi) :: t(2) ! Times associated with the Inputs + REAL(DbKi) :: t_out ! Time to which to be extrap/interpd + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp1' + REAL(DbKi) :: b ! temporary for extrapolation/interpolation + REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts + INTEGER :: i1 ! dim1 counter variable for arrays + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + ! we'll subtract a constant from the times to resolve some + ! numerical issues when t gets large (and to simplify the equations) + t = tin - tin(1) + t_out = tin_out - tin(1) + + IF ( EqualRealNos( t(1), t(2) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + + ScaleFactor = t_out / t(2) + CALL MeshExtrapInterp1(u1%TPMesh, u2%TPMesh, tin, u_out%TPMesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp1(u1%LMesh, u2%LMesh, tin, u_out%LMesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) +IF (ALLOCATED(u_out%CableDeltaL) .AND. ALLOCATED(u1%CableDeltaL)) THEN + DO i1 = LBOUND(u_out%CableDeltaL,1),UBOUND(u_out%CableDeltaL,1) + b = -(u1%CableDeltaL(i1) - u2%CableDeltaL(i1)) + u_out%CableDeltaL(i1) = u1%CableDeltaL(i1) + b * ScaleFactor + END DO +END IF ! check if allocated + END SUBROUTINE SD_Input_ExtrapInterp1 + + + SUBROUTINE SD_Input_ExtrapInterp2(u1, u2, u3, tin, u_out, tin_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Input u_out at time t_out, from previous/future time +! values of u (which has values associated with times in t). Order of the interpolation is 2. +! +! expressions below based on either +! +! f(t) = a + b * t + c * t**2 +! +! where a, b and c are determined as the solution to +! f(t1) = u1, f(t2) = u2, f(t3) = u3 +! +!.................................................................................................................................. + + TYPE(SD_InputType), INTENT(INOUT) :: u1 ! Input at t1 > t2 > t3 + TYPE(SD_InputType), INTENT(INOUT) :: u2 ! Input at t2 > t3 + TYPE(SD_InputType), INTENT(INOUT) :: u3 ! Input at t3 + REAL(DbKi), INTENT(IN ) :: tin(3) ! Times associated with the Inputs + TYPE(SD_InputType), INTENT(INOUT) :: u_out ! Input at tin_out + REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + REAL(DbKi) :: t(3) ! Times associated with the Inputs + REAL(DbKi) :: t_out ! Time to which to be extrap/interpd + INTEGER(IntKi) :: order ! order of polynomial fit (max 2) + REAL(DbKi) :: b ! temporary for extrapolation/interpolation + REAL(DbKi) :: c ! temporary for extrapolation/interpolation + REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Input_ExtrapInterp2' + INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts + INTEGER :: i1 ! dim1 counter variable for arrays + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + ! we'll subtract a constant from the times to resolve some + ! numerical issues when t gets large (and to simplify the equations) + t = tin - tin(1) + t_out = tin_out - tin(1) + + IF ( EqualRealNos( t(1), t(2) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + ELSE IF ( EqualRealNos( t(2), t(3) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(2) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + ELSE IF ( EqualRealNos( t(1), t(3) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + + ScaleFactor = t_out / (t(2) * t(3) * (t(2) - t(3))) + CALL MeshExtrapInterp2(u1%TPMesh, u2%TPMesh, u3%TPMesh, tin, u_out%TPMesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp2(u1%LMesh, u2%LMesh, u3%LMesh, tin, u_out%LMesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) +IF (ALLOCATED(u_out%CableDeltaL) .AND. ALLOCATED(u1%CableDeltaL)) THEN + DO i1 = LBOUND(u_out%CableDeltaL,1),UBOUND(u_out%CableDeltaL,1) + b = (t(3)**2*(u1%CableDeltaL(i1) - u2%CableDeltaL(i1)) + t(2)**2*(-u1%CableDeltaL(i1) + u3%CableDeltaL(i1)))* scaleFactor + c = ( (t(2)-t(3))*u1%CableDeltaL(i1) + t(3)*u2%CableDeltaL(i1) - t(2)*u3%CableDeltaL(i1) ) * scaleFactor + u_out%CableDeltaL(i1) = u1%CableDeltaL(i1) + b + c * t_out + END DO +END IF ! check if allocated + END SUBROUTINE SD_Input_ExtrapInterp2 + + + SUBROUTINE SD_Output_ExtrapInterp(y, t, y_out, t_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time +! values of y (which has values associated with times in t). Order of the interpolation is given by the size of y +! +! expressions below based on either +! +! f(t) = a +! f(t) = a + b * t, or +! f(t) = a + b * t + c * t**2 +! +! where a, b and c are determined as the solution to +! f(t1) = y1, f(t2) = y2, f(t3) = y3 (as appropriate) +! +!.................................................................................................................................. + + TYPE(SD_OutputType), INTENT(INOUT) :: y(:) ! Output at t1 > t2 > t3 + REAL(DbKi), INTENT(IN ) :: t(:) ! Times associated with the Outputs + TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out + REAL(DbKi), INTENT(IN ) :: t_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + INTEGER(IntKi) :: order ! order of polynomial fit (max 2) + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp' + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + if ( size(t) .ne. size(y)) then + CALL SetErrStat(ErrID_Fatal,'size(t) must equal size(y)',ErrStat,ErrMsg,RoutineName) + RETURN + endif + order = SIZE(y) - 1 + IF ( order .eq. 0 ) THEN + CALL SD_CopyOutput(y(1), y_out, MESH_UPDATECOPY, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE IF ( order .eq. 1 ) THEN + CALL SD_Output_ExtrapInterp1(y(1), y(2), t, y_out, t_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE IF ( order .eq. 2 ) THEN + CALL SD_Output_ExtrapInterp2(y(1), y(2), y(3), t, y_out, t_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + ELSE + CALL SetErrStat(ErrID_Fatal,'size(y) must be less than 4 (order must be less than 3).',ErrStat,ErrMsg,RoutineName) + RETURN + ENDIF + END SUBROUTINE SD_Output_ExtrapInterp + + + SUBROUTINE SD_Output_ExtrapInterp1(y1, y2, tin, y_out, tin_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time +! values of y (which has values associated with times in t). Order of the interpolation is 1. +! +! f(t) = a + b * t, or +! +! where a and b are determined as the solution to +! f(t1) = y1, f(t2) = y2 +! +!.................................................................................................................................. + + TYPE(SD_OutputType), INTENT(INOUT) :: y1 ! Output at t1 > t2 + TYPE(SD_OutputType), INTENT(INOUT) :: y2 ! Output at t2 + REAL(DbKi), INTENT(IN ) :: tin(2) ! Times associated with the Outputs + TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out + REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + REAL(DbKi) :: t(2) ! Times associated with the Outputs + REAL(DbKi) :: t_out ! Time to which to be extrap/interpd + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp1' + REAL(DbKi) :: b ! temporary for extrapolation/interpolation + REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts + INTEGER :: i1 ! dim1 counter variable for arrays + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + ! we'll subtract a constant from the times to resolve some + ! numerical issues when t gets large (and to simplify the equations) + t = tin - tin(1) + t_out = tin_out - tin(1) + + IF ( EqualRealNos( t(1), t(2) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + + ScaleFactor = t_out / t(2) + CALL MeshExtrapInterp1(y1%Y1Mesh, y2%Y1Mesh, tin, y_out%Y1Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp1(y1%Y2Mesh, y2%Y2Mesh, tin, y_out%Y2Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp1(y1%Y3Mesh, y2%Y3Mesh, tin, y_out%Y3Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) +IF (ALLOCATED(y_out%WriteOutput) .AND. ALLOCATED(y1%WriteOutput)) THEN + DO i1 = LBOUND(y_out%WriteOutput,1),UBOUND(y_out%WriteOutput,1) + b = -(y1%WriteOutput(i1) - y2%WriteOutput(i1)) + y_out%WriteOutput(i1) = y1%WriteOutput(i1) + b * ScaleFactor + END DO +END IF ! check if allocated + END SUBROUTINE SD_Output_ExtrapInterp1 + + + SUBROUTINE SD_Output_ExtrapInterp2(y1, y2, y3, tin, y_out, tin_out, ErrStat, ErrMsg ) +! +! This subroutine calculates a extrapolated (or interpolated) Output y_out at time t_out, from previous/future time +! values of y (which has values associated with times in t). Order of the interpolation is 2. +! +! expressions below based on either +! +! f(t) = a + b * t + c * t**2 +! +! where a, b and c are determined as the solution to +! f(t1) = y1, f(t2) = y2, f(t3) = y3 +! +!.................................................................................................................................. + + TYPE(SD_OutputType), INTENT(INOUT) :: y1 ! Output at t1 > t2 > t3 + TYPE(SD_OutputType), INTENT(INOUT) :: y2 ! Output at t2 > t3 + TYPE(SD_OutputType), INTENT(INOUT) :: y3 ! Output at t3 + REAL(DbKi), INTENT(IN ) :: tin(3) ! Times associated with the Outputs + TYPE(SD_OutputType), INTENT(INOUT) :: y_out ! Output at tin_out + REAL(DbKi), INTENT(IN ) :: tin_out ! time to be extrap/interp'd to + INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation + CHARACTER(*), INTENT( OUT) :: ErrMsg ! Error message if ErrStat /= ErrID_None + ! local variables + REAL(DbKi) :: t(3) ! Times associated with the Outputs + REAL(DbKi) :: t_out ! Time to which to be extrap/interpd + INTEGER(IntKi) :: order ! order of polynomial fit (max 2) + REAL(DbKi) :: b ! temporary for extrapolation/interpolation + REAL(DbKi) :: c ! temporary for extrapolation/interpolation + REAL(DbKi) :: ScaleFactor ! temporary for extrapolation/interpolation + INTEGER(IntKi) :: ErrStat2 ! local errors + CHARACTER(ErrMsgLen) :: ErrMsg2 ! local errors + CHARACTER(*), PARAMETER :: RoutineName = 'SD_Output_ExtrapInterp2' + INTEGER :: i01 ! dim1 level 0 counter variable for arrays of ddts + INTEGER :: i1 ! dim1 counter variable for arrays + ! Initialize ErrStat + ErrStat = ErrID_None + ErrMsg = "" + ! we'll subtract a constant from the times to resolve some + ! numerical issues when t gets large (and to simplify the equations) + t = tin - tin(1) + t_out = tin_out - tin(1) + + IF ( EqualRealNos( t(1), t(2) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(2) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + ELSE IF ( EqualRealNos( t(2), t(3) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(2) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + ELSE IF ( EqualRealNos( t(1), t(3) ) ) THEN + CALL SetErrStat(ErrID_Fatal, 't(1) must not equal t(3) to avoid a division-by-zero error.', ErrStat, ErrMsg,RoutineName) + RETURN + END IF + + ScaleFactor = t_out / (t(2) * t(3) * (t(2) - t(3))) + CALL MeshExtrapInterp2(y1%Y1Mesh, y2%Y1Mesh, y3%Y1Mesh, tin, y_out%Y1Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp2(y1%Y2Mesh, y2%Y2Mesh, y3%Y2Mesh, tin, y_out%Y2Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) + CALL MeshExtrapInterp2(y1%Y3Mesh, y2%Y3Mesh, y3%Y3Mesh, tin, y_out%Y3Mesh, tin_out, ErrStat2, ErrMsg2 ) + CALL SetErrStat(ErrStat2, ErrMsg2, ErrStat, ErrMsg,RoutineName) +IF (ALLOCATED(y_out%WriteOutput) .AND. ALLOCATED(y1%WriteOutput)) THEN + DO i1 = LBOUND(y_out%WriteOutput,1),UBOUND(y_out%WriteOutput,1) + b = (t(3)**2*(y1%WriteOutput(i1) - y2%WriteOutput(i1)) + t(2)**2*(-y1%WriteOutput(i1) + y3%WriteOutput(i1)))* scaleFactor + c = ( (t(2)-t(3))*y1%WriteOutput(i1) + t(3)*y2%WriteOutput(i1) - t(2)*y3%WriteOutput(i1) ) * scaleFactor + y_out%WriteOutput(i1) = y1%WriteOutput(i1) + b + c * t_out + END DO +END IF ! check if allocated + END SUBROUTINE SD_Output_ExtrapInterp2 + +END MODULE SubDyn_Types +!ENDOFREGISTRYGENERATEDFILE From 104c521d81bf96ac5360625ba2337cc23db77e89 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Thu, 23 Nov 2023 01:32:22 +0100 Subject: [PATCH 10/23] Cleaning code from checks (print) --- modules/subdyn/src/FEM.f90 | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/modules/subdyn/src/FEM.f90 b/modules/subdyn/src/FEM.f90 index 07ffce5f49..2635815249 100644 --- a/modules/subdyn/src/FEM.f90 +++ b/modules/subdyn/src/FEM.f90 @@ -1308,13 +1308,6 @@ SUBROUTINE ElemK_Spring(k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k K(12, 5) = K(11,6) K(12, 11) = K(11,12) - ! Temporary check. Looking at the spring element matrix (local coordinate system). - print*,'Spring element stiffness (local coordinate system)' - print*, K - - ! Temporary check. Looking at direction cosine matrix. - print*,'Direction cosine',DirCos - DC = 0.0_FEKi DC( 1: 3, 1: 3) = DirCos DC( 4: 6, 4: 6) = DirCos @@ -1322,10 +1315,6 @@ SUBROUTINE ElemK_Spring(k11, k12, k13, k14, k15, k16, k22, k23, k24, k25, k26, k DC(10:12, 10:12) = DirCos K = MATMUL( MATMUL(DC, K), TRANSPOSE(DC) ) ! TODO: change me if DirCos convention is transposed - - ! Temporary check. Looking at the spring element matrix (global coordinate system). - print*,'Spring element stiffness (global coordinate system)' - print*, K END SUBROUTINE ElemK_Spring !------------------------------------------------------------------------------------------------------ From ed5d7e4198806343c6130646a531a6145174fd83 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 27 Nov 2023 12:00:30 -0700 Subject: [PATCH 11/23] Update api_change.rst --- docs/source/user/api_change.rst | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/docs/source/user/api_change.rst b/docs/source/user/api_change.rst index 267a5809fc..2af1f4224c 100644 --- a/docs/source/user/api_change.rst +++ b/docs/source/user/api_change.rst @@ -9,6 +9,22 @@ The changes are tabulated according to the module input file, line number, and f The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +OpenFAST v4.0.0 to OpenFAST v3.5.1 +---------------------------------- + +============================================= ==== =============== ======================================================================================================================================================================================================== +Modified in OpenFAST v4.0.0 +--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Module Line Flag Name Example Value +============================================= ==== =============== ======================================================================================================================================================================================================== +SubDyn 56\* ----------------------- SPRING ELEMENT PROPERTIES ------------------------------------- +SubDyn 57\* NSpringPropSets 0 - Number of spring properties +SubDyn 58\* PropSetID k11 k12 k13 k14 k15 k16 k22 k23 k24 k25 k26 k33 k34 k35 k36 k44 k45 k46 k55 k56 k66 +SubDyn 59\* (-) (N/m) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/rad) (N/rad) (N/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) +============================================= ==== =============== ======================================================================================================================================================================================================== + +\*Exact line number depends on number of entries in various preceeding tables. + OpenFAST v3.5.0 to OpenFAST v3.5.1 ---------------------------------- From 921341e5df63cf9cff4e62475b3b5f3fc0c655b7 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 27 Nov 2023 12:42:34 -0700 Subject: [PATCH 12/23] Update input_files.rst --- docs/source/user/subdyn/input_files.rst | 46 ++++++++++++++----------- 1 file changed, 26 insertions(+), 20 deletions(-) diff --git a/docs/source/user/subdyn/input_files.rst b/docs/source/user/subdyn/input_files.rst index 157ad04f33..6bdaae4c29 100644 --- a/docs/source/user/subdyn/input_files.rst +++ b/docs/source/user/subdyn/input_files.rst @@ -179,11 +179,10 @@ properties, the material properties are not allowed to change within a single member. Future releases will allow for members of different cross-sections, -i.e., noncircular members. For this reason, the input file has -(currently unused) sections dedicated to the identification of direction -cosines that in the future will allow the module to identify the correct -orientation of noncircular members. The current release only accepts -tubular (circular) members. +i.e., noncircular members. For this reason, the input file has sections +dedicated to the identification of direction cosines that in the future +will allow the module to identify the correct orientation of noncircular +members. The current release only accepts tubular (circular) members. The file is organized into several functional sections. Each section corresponds to an aspect of the SubDyn model and substructure. @@ -419,7 +418,7 @@ MEMBER X-SECTION PROPERTY table (discussed next) for starting cross-section properties and **MPropSetID2** specifies the identifier for ending cross-section properties, allowing for tapered members. The sixth column specify the member type **MType**. -A member is one of the three following types (see :numref:`SD_FEM`): +A member is one of the four following types (see :numref:`SD_FEM`): - Beams (*MType=1*), Euler-Bernoulli (*FEMMod=1*) or Timoshenko (*FEMMod=3*) @@ -427,9 +426,12 @@ A member is one of the three following types (see :numref:`SD_FEM`): - Rigid link (*MType=3*) +- Spring element (*MType=4*) + **COSMID** refers to the IDs of the members' cosine matrices for noncircular -members; the current release uses SubDyn's default direction cosine convention -if it's not present or when COSMID values are -1. +members and spring elements; the current release uses SubDyn's default direction cosine convention +if it's not present or when COSMID values are -1. Spring elements are defined between joints that +are coincident in the space and the direction cosine must be provided. An example of member table is given below @@ -525,22 +527,26 @@ An example of rigid link properties table is given below (-) (kg/m) 12 7850.0 3 7000.0 - - - - - - - - - - - - +Spring Properties +~~~~~~~~~~~~~~~~ +Members that are specified as spring elements (**MType=5**), +have their properties defined in the spring element properties table. +The table lists for each spring property: the property ID (**PropSetID**), the diagonal stiffness +coefficients (**K11**, **K22**, **K33**, **K44**, **K55**, **K66**), and the cross-coupling +stiffness coefficients (**K12**, **K13**, **K14**, **K15**, **K16**, **K23**, **K24**, **K25**, +**K26**, **K34**, **K35**, **K36**, **K45**, **K46**, **K56**). The stiffness matrix is considered symmetric. +The FEM representation of the spring element is given in :numref:`SD_SpringElement`. +An example of spring properties table is given below: +.. code:: + -------------------------- SPRING ELEMENT PROPERTIES ---------------------------- + 1 NSpringPropSets - Number of spring properties + PropSetID k11 k12 k13 k14 k15 k16 k22 k23 k24 k25 k26 k33 k34 k35 k36 k44 k45 k46 k55 k56 k66 + (-) (N/m) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/rad) (N/rad) (N/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) + 2 2E7 0 0 0 0 0 1E12 0 0 0 0 1E12 0 0 0 1E12 0 0 1E8 0 1e12 Member Cosine Matrices COSM (i,j) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ From d51aeee7d1fdbd65b33ca900ba477f9086b1013a Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 27 Nov 2023 13:36:57 -0700 Subject: [PATCH 13/23] Update theory.rst --- docs/source/user/subdyn/theory.rst | 51 +++++++++++++++++++++++++++--- 1 file changed, 47 insertions(+), 4 deletions(-) diff --git a/docs/source/user/subdyn/theory.rst b/docs/source/user/subdyn/theory.rst index ad56023b4a..edb6762327 100644 --- a/docs/source/user/subdyn/theory.rst +++ b/docs/source/user/subdyn/theory.rst @@ -279,7 +279,7 @@ The following joints are supported: - Ball joint (*JointType=4*) -A member is one of the three following types: +A member is one of the four following types: - Beams (*MType=1*), Euler-Bernoulli (*FEMMod=1*) or Timoshenko (*FEMMod=3*) @@ -287,11 +287,13 @@ A member is one of the three following types: - Rigid link (*MType=3*) +- Spring element (*MType=5*) + Beam members may be split into several elements to increase the accuracy of the model (using -the input parameter *NDiv*). Member of other types (rigid links and -pretension cables) are not split. In this document, the term *element* +the input parameter *NDiv*). Member of other types (rigid links, pretension cables and springs) +are not split. In this document, the term *element* refers to: a sub-division of a beam member or a member of another type -than beam (rigid-link or pretension cable). The term *joints* refers to +than beam (rigid-link, pretension cable or spring). The term *joints* refers to the points defining the extremities of the members. Some joints are defined in the input file, while others arise from the subdivision of beam members. The end points of an elements are called nodes and each @@ -1287,9 +1289,50 @@ The constraint are applied after the full system has been assembled. +.. _SD_SpringElement: + + +Spring Elements +~~~~~~~~~~~ + +Do not confuse the spring member with the springs defined as +a boundary condition in land-based systems. The spring element +relates two joints by means of a 6 by 6 stiffness matrix that +is assumed symmetric (k_ij = k_ji). + +.. math:: + +\begin{aligned} + K= + \begin{bmatrix} + k_{11} & k_{12} & k_{13} & k_{14} & k_{15} & k_{16} \\ + k_{21} & k_{22} & k_{23} & k_{24} & k_{25} & k_{26} \\ + k_{31} & k_{32} & k_{33} & k_{34} & k_{35} & k_{36} \\ + k_{41} & k_{42} & k_{43} & k_{44} & k_{45} & k_{46} \\ + k_{51} & k_{52} & k_{53} & k_{54} & k_{55} & k_{56} \\ + k_{61} & k_{62} & k_{63} & k_{64} & k_{65} & k_{66} \\ + \end{bmatrix} + +The spring element does not have a mass associated. However, if desired, a lumped mass can be +defined at the joints. + +Since each joint has 6 DOFs (3 translations and 3 rotations), mathematically, the +spring element has a 12 by 12 dimension. +.. math:: +\begin{aligned} + K_e= + \begin{bmatrix} + k_{6x6} & -k_{6x6} \\ + -k_{6x6} & k_{6x6} \\ + \end{bmatrix} +The spring element must be defined between two coincident joints and the orientation has to be +provided by means of the direction cosine. This allows the assembly of the spring element in the +global system stiffness matrix. +The spring element can be connected to beams, kinematic joints (e.g., revolute joint, universal joint, +and spherical joint), the interface joint and rigid links. However, it cannot be connected to a cable. .. _GenericCBReduction: From d1c6bab3c7b0dcabbb97cff05ac3c08cef9f6490 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 27 Nov 2023 13:38:59 -0700 Subject: [PATCH 14/23] Update OC4_Jacket_SD_Input.dat --- docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat b/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat index 43111b830f..45c9edafaa 100644 --- a/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat +++ b/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat @@ -247,6 +247,10 @@ PropSetID EA MatDens T0 CtrlChannel 0 NRigidPropSets - Number of rigid link properties PropSetID MatDens (-) (kg/m) +----------------------- SPRING ELEMENT PROPERTIES ------------------------------------- + 0 NSpringPropSets - Number of spring properties +PropSetID k11 k12 k13 k14 k15 k16 k22 k23 k24 k25 k26 k33 k34 k35 k36 k44 k45 k46 k55 k56 k66 + (-) (N/m) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/rad) (N/rad) (N/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) ---------------------- MEMBER COSINE MATRICES COSM(i,j) ------------------------------- 0 NCOSMs - Number of unique cosine matrices (i.e., of unique member alignments including principal axis rotations); ignored if NXPropSets=0 or 9999 in any element below COSMID COSM11 COSM12 COSM13 COSM21 COSM22 COSM23 COSM31 COSM32 COSM33 From daf2cf748d232af0f4dac435c2f68cb029f30a03 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Mon, 27 Nov 2023 13:40:07 -0700 Subject: [PATCH 15/23] Update OC4_Jacket_SD_Input.dat --- docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat b/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat index 45c9edafaa..2c7cf3dcfe 100644 --- a/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat +++ b/docs/source/user/subdyn/examples/OC4_Jacket_SD_Input.dat @@ -111,7 +111,7 @@ IJointID ItfTDXss ItfTDYss ItfTDZss ItfRDXss ItfRDYss ItfRDZss 56 1 1 1 1 1 1 ----------------------------------- MEMBERS ------------------------------------------- 112 NMembers - Number of members (-) -MemberID MJointID1 MJointID2 MPropSetID1 MPropSetID2 MType COSMID ![MType={1:beam circ., 2:cable, 3:rigid, 4:beam arb.}. COMSID={-1:none}] +MemberID MJointID1 MJointID2 MPropSetID1 MPropSetID2 MType COSMID ![MType={1:beam circ., 2:cable, 3:rigid, 4:beam arb., 5:spring}. COMSID={-1:none}] (-) (-) (-) (-) (-) (-) (-) 1 1 2 2 2 1 -1 2 2 3 2 2 1 -1 From fd37a8430b2deb909010d1801e32432abf26c08b Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Tue, 28 Nov 2023 12:30:39 -0700 Subject: [PATCH 16/23] Update input_files.rst --- docs/source/user/subdyn/input_files.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/user/subdyn/input_files.rst b/docs/source/user/subdyn/input_files.rst index 6bdaae4c29..d338ab8c06 100644 --- a/docs/source/user/subdyn/input_files.rst +++ b/docs/source/user/subdyn/input_files.rst @@ -426,7 +426,7 @@ A member is one of the four following types (see :numref:`SD_FEM`): - Rigid link (*MType=3*) -- Spring element (*MType=4*) +- Spring element (*MType=5*) **COSMID** refers to the IDs of the members' cosine matrices for noncircular members and spring elements; the current release uses SubDyn's default direction cosine convention From aa1582ecdb010a05aaf285b7d533101b5fea91b4 Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Tue, 28 Nov 2023 12:46:51 -0700 Subject: [PATCH 17/23] Update SD_FEM.f90 --- modules/subdyn/src/SD_FEM.f90 | 50 +++++++++++++++++------------------ 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index bc75a39cb4..b2e1fd7c16 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -690,7 +690,7 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) ! --- Cables, rigid link and spring properties (these cannot be subdivided, so direct copy of inputs) Init%NPropC = Init%NPropSetsC Init%NPropR = Init%NPropSetsR - Init%NPropS = Init%NPropSetsS + Init%NPropS = Init%NPropSetsS CALL AllocAry(Init%PropsC, Init%NPropC, PropSetsCCol, 'Init%PropsCable', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropsR, Init%NPropR, PropSetsRCol, 'Init%PropsRigid', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropsS, Init%NPropS, PropSetsSCol, 'Init%PropsSpring', ErrStat2, ErrMsg2); if(Failed()) return @@ -888,27 +888,27 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) p%ElemProps(i)%Area = -9.99e+36 p%ElemProps(i)%Rho = -9.99e+36 p%ElemProps(i)%T0 = -9.99e+36 - p%ElemProps(i)%k11 = -9.99e+36 - p%ElemProps(i)%k12 = -9.99e+36 - p%ElemProps(i)%k13 = -9.99e+36 - p%ElemProps(i)%k14 = -9.99e+36 - p%ElemProps(i)%k15 = -9.99e+36 - p%ElemProps(i)%k16 = -9.99e+36 - p%ElemProps(i)%k22 = -9.99e+36 - p%ElemProps(i)%k23 = -9.99e+36 - p%ElemProps(i)%k24 = -9.99e+36 - p%ElemProps(i)%k25 = -9.99e+36 - p%ElemProps(i)%k26 = -9.99e+36 - p%ElemProps(i)%k33 = -9.99e+36 - p%ElemProps(i)%k34 = -9.99e+36 - p%ElemProps(i)%k35 = -9.99e+36 - p%ElemProps(i)%k36 = -9.99e+36 - p%ElemProps(i)%k44 = -9.99e+36 - p%ElemProps(i)%k45 = -9.99e+36 - p%ElemProps(i)%k46 = -9.99e+36 - p%ElemProps(i)%k55 = -9.99e+36 - p%ElemProps(i)%k56 = -9.99e+36 - p%ElemProps(i)%k66 = -9.99e+36 + p%ElemProps(i)%k11 = -9.99e+36 + p%ElemProps(i)%k12 = -9.99e+36 + p%ElemProps(i)%k13 = -9.99e+36 + p%ElemProps(i)%k14 = -9.99e+36 + p%ElemProps(i)%k15 = -9.99e+36 + p%ElemProps(i)%k16 = -9.99e+36 + p%ElemProps(i)%k22 = -9.99e+36 + p%ElemProps(i)%k23 = -9.99e+36 + p%ElemProps(i)%k24 = -9.99e+36 + p%ElemProps(i)%k25 = -9.99e+36 + p%ElemProps(i)%k26 = -9.99e+36 + p%ElemProps(i)%k33 = -9.99e+36 + p%ElemProps(i)%k34 = -9.99e+36 + p%ElemProps(i)%k35 = -9.99e+36 + p%ElemProps(i)%k36 = -9.99e+36 + p%ElemProps(i)%k44 = -9.99e+36 + p%ElemProps(i)%k45 = -9.99e+36 + p%ElemProps(i)%k46 = -9.99e+36 + p%ElemProps(i)%k55 = -9.99e+36 + p%ElemProps(i)%k56 = -9.99e+36 + p%ElemProps(i)%k66 = -9.99e+36 ! --- Properties that are specific to some elements if (eType==idMemberBeamCirc) then @@ -1017,8 +1017,8 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) if (DEV_VERSION) then print*,'Member',I,'is a spring element' endif - p%ElemProps(i)%Area = 0 ! Spring elements have no area - p%ElemProps(i)%Rho = 0 ! Spring elements have no mass + p%ElemProps(i)%Area = 0 ! Spring elements have no area + p%ElemProps(i)%Rho = 0 ! Spring elements have no mass p%ElemProps(i)%k11 = Init%PropsS(P1, 2) p%ElemProps(i)%k12 = Init%PropsS(P1, 3) p%ElemProps(i)%k13 = Init%PropsS(P1, 4) @@ -2344,7 +2344,7 @@ SUBROUTINE ElemM(ep, Me) endif else if (ep%eType==idMemberSpring) then - Me=0.0_FEKi ! Spring element has no mass associated. Consider using a lumped mass at JointID, if desired. + Me=0.0_FEKi ! Spring element has no mass associated. Consider using a lumped mass at JointID, if desired. endif END SUBROUTINE ElemM From 23d90fe1a680a8fd61fcbfa81cdb71dfd350320b Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Tue, 28 Nov 2023 12:51:32 -0700 Subject: [PATCH 18/23] Update SubDyn_Tests.f90 --- modules/subdyn/src/SubDyn_Tests.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/subdyn/src/SubDyn_Tests.f90 b/modules/subdyn/src/SubDyn_Tests.f90 index dd822f52e5..6576a77c05 100644 --- a/modules/subdyn/src/SubDyn_Tests.f90 +++ b/modules/subdyn/src/SubDyn_Tests.f90 @@ -323,7 +323,7 @@ subroutine Test_Transformations(ErrStat,ErrMsg) character(ErrMsgLen), intent(out) :: ErrMsg real(ReKi), dimension(3) :: P1, P2, e1, e2, e3 - integer(IntKi) :: eType + integer(IntKi) :: eType real(FEKi), dimension(3,3) :: DirCos, Ref real(ReKi), dimension(6,6) :: T, Tref real(ReKi) :: L From 2caee67e8822337a1b47dfee427fb4b67a4e217e Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Tue, 28 Nov 2023 13:08:00 -0700 Subject: [PATCH 19/23] Update input_files.rst --- docs/source/user/subdyn/input_files.rst | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/docs/source/user/subdyn/input_files.rst b/docs/source/user/subdyn/input_files.rst index d338ab8c06..f37fd49f96 100644 --- a/docs/source/user/subdyn/input_files.rst +++ b/docs/source/user/subdyn/input_files.rst @@ -532,10 +532,11 @@ Spring Properties ~~~~~~~~~~~~~~~~ Members that are specified as spring elements (**MType=5**), have their properties defined in the spring element properties table. -The table lists for each spring property: the property ID (**PropSetID**), the diagonal stiffness -coefficients (**K11**, **K22**, **K33**, **K44**, **K55**, **K66**), and the cross-coupling -stiffness coefficients (**K12**, **K13**, **K14**, **K15**, **K16**, **K23**, **K24**, **K25**, -**K26**, **K34**, **K35**, **K36**, **K45**, **K46**, **K56**). The stiffness matrix is considered symmetric. +The table lists for each spring property: the property ID (**PropSetID**) and the +stiffness coefficients (**K11**, **K12**, **K13**, **K14**, **K15**, **K16**, **K22**, +**K23**, **K24**, **K25**, **K26**, **K33**, **K34**, **K35**, **K36**, **K44**, **K45**, +**K46**, **K55**, **K56**, **K66**). The stiffness matrix is considered symmetric and +includes diagonal (kii) and cross-coupling (kij) coefficients. The FEM representation of the spring element is given in :numref:`SD_SpringElement`. An example of spring properties table is given below: From 9ad3f4a81f556fa101933a95fde313a947e53757 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 28 Nov 2023 14:57:34 -0700 Subject: [PATCH 20/23] SD: remove tab characters --- modules/subdyn/src/FEM.f90 | 2 +- modules/subdyn/src/SD_FEM.f90 | 14 +++++++------- modules/subdyn/src/SubDyn.f90 | 28 ++++++++++++++-------------- 3 files changed, 22 insertions(+), 22 deletions(-) diff --git a/modules/subdyn/src/FEM.f90 b/modules/subdyn/src/FEM.f90 index 2635815249..f9ef9422eb 100644 --- a/modules/subdyn/src/FEM.f90 +++ b/modules/subdyn/src/FEM.f90 @@ -953,7 +953,7 @@ END SUBROUTINE GetRigidTransformation !! in the FAST framework. SUBROUTINE GetDirCos(P1, P2, eType, DirCos, L_out, ErrStat, ErrMsg) REAL(ReKi) , INTENT(IN ) :: P1(3), P2(3) ! (x,y,z) global positions of two nodes making up an element - INTEGER(IntKi), INTENT(IN ) :: eType ! element type (1:beam circ., 2:cable, 3:rigid, 4:beam arb., 5:spring) + INTEGER(IntKi), INTENT(IN ) :: eType ! element type (1:beam circ., 2:cable, 3:rigid, 4:beam arb., 5:spring) REAL(FEKi) , INTENT( OUT) :: DirCos(3, 3) ! calculated direction cosine matrix REAL(ReKi) , INTENT( OUT) :: L_out ! length of element INTEGER(IntKi), INTENT( OUT) :: ErrStat ! Error status of the operation diff --git a/modules/subdyn/src/SD_FEM.f90 b/modules/subdyn/src/SD_FEM.f90 index 82e48d2aa0..2e7390b032 100644 --- a/modules/subdyn/src/SD_FEM.f90 +++ b/modules/subdyn/src/SD_FEM.f90 @@ -398,7 +398,7 @@ SUBROUTINE SD_ReIndex_CreateNodesAndElems(Init,p, ErrStat, ErrMsg) p%Elems(iMem,n) = FINDLOCI(Init%PropSetsX(:,1), Init%Members(iMem, n) ) else if (mType==idMemberSpring) then sType='Spring property' - p%Elems(iMem,n) = FINDLOCI(Init%PropSetsS(:,1), Init%Members(iMem, n) ) + p%Elems(iMem,n) = FINDLOCI(Init%PropSetsS(:,1), Init%Members(iMem, n) ) else ! Should not happen print*,'Element type unknown',mType @@ -694,10 +694,10 @@ SUBROUTINE SD_Discrt(Init,p, ErrStat, ErrMsg) CALL AllocAry(Init%PropsC, Init%NPropC, PropSetsCCol, 'Init%PropsCable', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropsR, Init%NPropR, PropSetsRCol, 'Init%PropsRigid', ErrStat2, ErrMsg2); if(Failed()) return CALL AllocAry(Init%PropsS, Init%NPropS, PropSetsSCol, 'Init%PropsSpring', ErrStat2, ErrMsg2); if(Failed()) return - Init%PropsC(1:Init%NPropC, 1:PropSetsCCol) = Init%PropSetsC(1:Init%NPropC, 1:PropSetsCCol) + Init%PropsC(1:Init%NPropC, 1:PropSetsCCol) = Init%PropSetsC(1:Init%NPropC, 1:PropSetsCCol) Init%PropsR(1:Init%NPropR, 1:PropSetsRCol) = Init%PropSetsR(1:Init%NPropR, 1:PropSetsRCol) - Init%PropsS(1:Init%NPropS, 1:PropSetsSCol) = Init%PropSetsS(1:Init%NPropS, 1:PropSetsSCol) - + Init%PropsS(1:Init%NPropS, 1:PropSetsSCol) = Init%PropSetsS(1:Init%NPropS, 1:PropSetsSCol) + CALL CleanUp_Discrt() CONTAINS @@ -909,7 +909,7 @@ SUBROUTINE SetElementProperties(Init, p, ErrStat, ErrMsg) p%ElemProps(i)%k55 = -9.99e+36 p%ElemProps(i)%k56 = -9.99e+36 p%ElemProps(i)%k66 = -9.99e+36 - + ! --- Properties that are specific to some elements if (eType==idMemberBeamCirc) then E = Init%PropsB(P1, 2) ! TODO E2 @@ -2364,7 +2364,7 @@ SUBROUTINE ElemK(ep, Ke) else if (ep%eType==idMemberSpring) then CALL ElemK_Spring(eP%k11, eP%k12, eP%k13, eP%k14, eP%k15, eP%k16, eP%k22, eP%k23, eP%k24, eP%k25, eP%k26, eP%k33, eP%k34, eP%k35, eP%k36, eP%k44, eP%k45, eP%k46, eP%k55, eP%k56, eP%k66, eP%DirCos, Ke) - + endif END SUBROUTINE ElemK @@ -2380,7 +2380,7 @@ SUBROUTINE ElemF(ep, gravity, Fg, Fo) else if (ep%eType==idMemberRigid) then Fo(1:12)=0.0_FEKi else if (ep%eType==idMemberSpring) then - Fo(1:12)=0.0_FEKi + Fo(1:12)=0.0_FEKi endif CALL ElemG( eP%Area, eP%Length, eP%rho, eP%DirCos, Fg, gravity ) END SUBROUTINE ElemF diff --git a/modules/subdyn/src/SubDyn.f90 b/modules/subdyn/src/SubDyn.f90 index 33a920e792..0f24e5a000 100644 --- a/modules/subdyn/src/SubDyn.f90 +++ b/modules/subdyn/src/SubDyn.f90 @@ -1259,7 +1259,7 @@ SUBROUTINE SD_Input(SDInputFile, Init, p, ErrStat,ErrMsg) CALL AllocAry(Init%PropSetsS, Init%NPropSetsS, PropSetsSCol, 'PropSetsS', ErrStat2, ErrMsg2); if(Failed()) return DO I = 1, Init%NPropSetsS READ(UnIn, FMT='(A)', IOSTAT=ErrStat2) Line; ErrMsg2='Error reading spring property line'; if (Failed()) return - call ReadFAryFromStr(Line, Init%PropSetsS(I,:), PropSetsSCol, nColValid, nColNumeric); + call ReadFAryFromStr(Line, Init%PropSetsS(I,:), PropSetsSCol, nColValid, nColNumeric); if ((nColValid/=nColNumeric).or.((nColNumeric/=22).and.(nColNumeric/=PropSetsSCol)) ) then CALL Fatal(' Error in file "'//TRIM(SDInputFile)//'": Spring property line must consist of 22 numerical values. Problematic line: "'//trim(Line)//'"') return @@ -3783,13 +3783,13 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E WRITE(UnSum, '(A,I6)') '#Number of nodes per member:', Init%Ndiv+1 WRITE(UnSum, '(A9,A10,A10,A10,A10,A15,A15,A16)') '#Member ID', 'Joint1_ID', 'Joint2_ID','Prop_I','Prop_J', 'Mass','Length', 'Node IDs...' DO i=1,p%NMembers - !Calculate member mass here; this should really be done somewhere else, yet it is not used anywhere else - !IT WILL HAVE TO BE MODIFIED FOR OTHER THAN CIRCULAR PIPE ELEMENTS - propIDs=Init%Members(i,iMProp:iMProp+1) - if (Init%Members(I, iMType)/=idMemberSpring) then ! This check only applies for members different than springs (springs have no mass and no length) - mLength=MemberLength(Init%Members(i,1),Init,ErrStat,ErrMsg) ! TODO double check mass and length - endif - IF (ErrStat .EQ. ErrID_None) THEN + !Calculate member mass here; this should really be done somewhere else, yet it is not used anywhere else + !IT WILL HAVE TO BE MODIFIED FOR OTHER THAN CIRCULAR PIPE ELEMENTS + propIDs=Init%Members(i,iMProp:iMProp+1) + if (Init%Members(I, iMType)/=idMemberSpring) then ! This check only applies for members different than springs (springs have no mass and no length) + mLength=MemberLength(Init%Members(i,1),Init,ErrStat,ErrMsg) ! TODO double check mass and length + endif + IF (ErrStat .EQ. ErrID_None) THEN mType = Init%Members(I, iMType) ! if (mType==idMemberBeamCirc) then iProp(1) = FINDLOCI(Init%PropSetsB(:,1), propIDs(1)) @@ -3812,7 +3812,7 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E else if (mType==idMemberSpring) then iProp(1) = FINDLOCI(Init%PropSetsS(:,1), propIDs(1)) mMass= 0.0 ! Spring element has no mass - mLength = 0.0 ! Spring element has no length. Both JointIDs must be coincident. + mLength = 0.0 ! Spring element has no length. Both JointIDs must be coincident. WRITE(UnSum, '("#",I9,I10,I10,I10,I10,ES15.6E2,ES15.6E2, A3,2(I6),A)') Init%Members(i,1:3),propIDs(1),propIDs(2),& mMass,mLength,' ',(Init%MemberNodes(i, j), j = 1, 2), ' # Spring element' else if (mType==idMemberBeamArb) then @@ -3824,9 +3824,9 @@ SUBROUTINE OutSummary(Init, p, m, InitInput, CBparams, Modes, Omega, Omega_Gy, E else WRITE(UnSum, '(A)') '#TODO, member unknown' endif - ELSE - RETURN - ENDIF + ELSE + RETURN + ENDIF ENDDO !------------------------------------------------------------------------------------------------------------- ! write Cosine matrix for all members to a txt file @@ -4086,7 +4086,7 @@ END SUBROUTINE StateMatrices FUNCTION MemberLength(MemberID,Init,ErrStat,ErrMsg) TYPE(SD_InitType), INTENT(IN) :: Init !< Input data for initialization routine, this structure contains many variables needed for summary file INTEGER(IntKi), INTENT(IN) :: MemberID !< Member ID # - REAL(ReKi) :: MemberLength !< Member Length + REAL(ReKi) :: MemberLength !< Member Length INTEGER(IntKi), INTENT( OUT) :: ErrStat !< Error status of the operation CHARACTER(*), INTENT( OUT) :: ErrMsg !< Error message if ErrStat /= ErrID_None !Locals @@ -4110,7 +4110,7 @@ FUNCTION MemberLength(MemberID,Init,ErrStat,ErrMsg) xyz1= Init%Joints(Joint1,2:4) xyz2= Init%Joints(Joint2,2:4) MemberLength=SQRT( SUM((xyz2-xyz1)**2.) ) - if ( EqualRealNos(MemberLength, 0.0_ReKi) ) then + if ( EqualRealNos(MemberLength, 0.0_ReKi) ) then call SetErrStat(ErrID_Fatal,' Member with ID '//trim(Num2LStr(MemberID))//' has zero length!', ErrStat,ErrMsg,RoutineName); return endif From 81b9317265d5ae1e1a9e198a76e8479252da4b13 Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Tue, 28 Nov 2023 22:38:43 -0700 Subject: [PATCH 21/23] SD: update regression test list for spring elements --- reg_tests/CTestList.cmake | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/reg_tests/CTestList.cmake b/reg_tests/CTestList.cmake index 786e4192fd..9d9006ebbe 100644 --- a/reg_tests/CTestList.cmake +++ b/reg_tests/CTestList.cmake @@ -407,6 +407,12 @@ sd_regression("SD_SparHanging" "subdyn;offshore") sd_regression("SD_AnsysComp1_PinBeam" "subdyn;offshore") # TODO Issue #855 sd_regression("SD_AnsysComp2_Cable" "subdyn;offshore") sd_regression("SD_AnsysComp3_PinBeamCable" "subdyn;offshore") # TODO Issue #855 +sd_regression("SD_Spring_Case1" "subdyn;offshore") +sd_regression("SD_Spring_Case2" "subdyn;offshore") +sd_regression("SD_Spring_Case3" "subdyn;offshore") +sd_regression("SD_Revolute_Joint" "subdyn;offshore") +sd_regression("SD_2Beam_Spring" "subdyn;offshore") +sd_regression("SD_2Beam_Cantilever" "subdyn;offshore") # TODO test below are bugs, should be added when fixed # sd_regression("SD_Force" "subdyn;offshore") # sd_regression("SD_AnsysComp4_UniversalCableRigid" "subdyn;offshore") From 8870ebfa923a4d30bd68235bb1e58565f4079e0c Mon Sep 17 00:00:00 2001 From: Roger Bergua Date: Wed, 29 Nov 2023 07:42:30 -0700 Subject: [PATCH 22/23] Update input_files.rst --- docs/source/user/subdyn/input_files.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/user/subdyn/input_files.rst b/docs/source/user/subdyn/input_files.rst index f37fd49f96..745767713d 100644 --- a/docs/source/user/subdyn/input_files.rst +++ b/docs/source/user/subdyn/input_files.rst @@ -547,7 +547,7 @@ An example of spring properties table is given below: 1 NSpringPropSets - Number of spring properties PropSetID k11 k12 k13 k14 k15 k16 k22 k23 k24 k25 k26 k33 k34 k35 k36 k44 k45 k46 k55 k56 k66 (-) (N/m) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/m) (N/rad) (N/rad) (N/rad) (N/m) (N/rad) (N/rad) (N/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) (Nm/rad) - 2 2E7 0 0 0 0 0 1E12 0 0 0 0 1E12 0 0 0 1E12 0 0 1E8 0 1e12 + 2 2E7 0 0 0 0 0 1E12 0 0 0 0 1E12 0 0 0 1E12 0 0 1E8 0 1E12 Member Cosine Matrices COSM (i,j) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ From 3b5cfabde9060e89ecd642a65900672bd337c5ce Mon Sep 17 00:00:00 2001 From: andrew-platt Date: Wed, 29 Nov 2023 09:47:26 -0700 Subject: [PATCH 23/23] SD springs: update r-test pointer --- reg_tests/r-test | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reg_tests/r-test b/reg_tests/r-test index 1cbf6a1ae9..9a42b24203 160000 --- a/reg_tests/r-test +++ b/reg_tests/r-test @@ -1 +1 @@ -Subproject commit 1cbf6a1ae96655e2a7fa2a6865ccc99fc39bf6c8 +Subproject commit 9a42b2420312ab5dfd49065e7ddab6fb69dc7d3f