Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bug: BeamDyn Initial Strain and Linearization #2085

Merged
merged 6 commits into from
Mar 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
230 changes: 124 additions & 106 deletions modules/beamdyn/src/BeamDyn.f90
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ MODULE BeamDyn
! follow the moving BladeRootMotion mesh. This requires changing the states after an UpdateStates call to be relative to
! the new BladeRootMotion mesh orientation and position.
! Upadate the reference frame after each State update (or use the old method)?
LOGICAL, PARAMETER :: ChangeRefFrame = .true.
LOGICAL, PARAMETER :: ChangeRefFrame = .false.

CONTAINS

Expand Down Expand Up @@ -94,7 +94,6 @@ SUBROUTINE BD_Init( InitInp, u, p, x, xd, z, OtherState, y, MiscVar, Interval, I
REAL(BDKi) :: temp_CRV(3)
REAL(BDKi),ALLOCATABLE :: GLL_nodes(:)
REAL(BDKi) :: TmpDCM(3,3)
REAL(BDKi) :: denom
LOGICAL :: QuasiStaticInitialized !< True if quasi-static solution was found


Expand Down Expand Up @@ -153,7 +152,7 @@ SUBROUTINE BD_Init( InitInp, u, p, x, xd, z, OtherState, y, MiscVar, Interval, I
! set mass and stiffness matrices: p%Stif0_QP and p%Mass0_QP
call InitializeMassStiffnessMatrices(InputFileData, p, ErrStat2,ErrMsg2); if (Failed()) return

! Set the initial displacements: p%uu0, p%E10
! Set the initial displacements: p%uu0, p%rrN0, p%E10
CALL BD_QuadraturePointDataAt0(p)


Expand All @@ -163,8 +162,6 @@ SUBROUTINE BD_Init( InitInp, u, p, x, xd, z, OtherState, y, MiscVar, Interval, I
CALL BD_ComputeBladeMassNew( p, ErrStat2, ErrMsg2 ); if (Failed()) return !computes p%blade_mass,p%blade_CG,p%blade_IN


! Actuator

if (p%UsePitchAct) then

! Calculate the pitch angle
Expand Down Expand Up @@ -594,12 +591,8 @@ subroutine InitializeNodalLocations(member_total,kp_member,kp_coordinate,p,GLL_n

tangent = tangent / TwoNorm(tangent)

! Calculate the node initial rotation
CALL BD_ComputeIniNodalCrv(tangent, twist, temp_CRV, ErrStat, ErrMsg)

! Store rotation in node initial position vector and save node twist
p%uuN0(4:6,i,elem) = temp_CRV
p%twN0(i,elem) = twist

enddo

Expand Down Expand Up @@ -736,11 +729,11 @@ SUBROUTINE BD_InitShpDerJaco( GLL_Nodes, p )

CALL BD_diffmtc(p%nodes_per_elem,GLL_nodes,p%QPtN,p%nqp,p%Shp,p%ShpDer)

! Calculate the Jacobian relating element axial length to real coordinates
DO nelem = 1,p%elem_total
DO idx_qp = 1, p%nqp
DO i=1,3
Gup0(i) = dot_product(p%ShpDer(:,idx_qp), p%uuN0(i,:,nelem))
Gup0(:) = 0.0_BDKi
DO i=1,p%nodes_per_elem
Gup0(:) = Gup0(:) + p%ShpDer(i,idx_qp)*p%uuN0(1:3,i,nelem)
ENDDO
p%Jacobian(idx_qp,nelem) = TwoNorm(Gup0)
ENDDO
Expand Down Expand Up @@ -898,11 +891,10 @@ subroutine SetParameters(InitInp, InputFileData, p, OtherState, ErrStat, ErrMsg)
INTEGER(IntKi) :: i, j ! generic counter index
INTEGER(IntKi) :: indx ! counter into index array (p%NdIndx)
INTEGER(IntKi) :: nUniqueQP ! number of unique quadrature points (not double-counting nodes at element boundaries)

REAL(BDKi) :: denom
integer(intKi) :: ErrStat2 ! temporary Error status
character(ErrMsgLen) :: ErrMsg2 ! temporary Error message
character(*), parameter :: RoutineName = 'SetParameters'
real(DbKi) :: denom



Expand Down Expand Up @@ -973,25 +965,7 @@ subroutine SetParameters(InitInp, InputFileData, p, OtherState, ErrStat, ErrMsg)
p%dof_elem = p%dof_node * p%nodes_per_elem
p%rot_elem = (p%dof_node/2) * p%nodes_per_elem

! Actuator
p%UsePitchAct = InputFileData%UsePitchAct
if (p%UsePitchAct) then
p%pitchK = InputFileData%pitchK
p%pitchC = InputFileData%pitchC
p%pitchJ = InputFileData%pitchJ

! calculate (I-hA)^-1
p%torqM(1,1) = p%pitchJ + p%pitchC*p%dt
p%torqM(2,1) = -p%pitchK * p%dt
p%torqM(1,2) = p%pitchJ * p%dt
p%torqM(2,2) = p%pitchJ
denom = p%pitchJ + p%pitchC*p%dt + p%pitchK*p%dt**2
if (EqualRealNos(denom,0.0_BDKi)) then
call SetErrStat(ErrID_Fatal,"Cannot invert matrix for pitch actuator: J+c*dt+k*dt^2 is zero.",ErrStat,ErrMsg,RoutineName)
else
p%torqM(:,:) = p%torqM / denom
end if
end if

!................................
! allocate some parameter arrays
Expand All @@ -1013,7 +987,7 @@ subroutine SetParameters(InitInp, InputFileData, p, OtherState, ErrStat, ErrMsg)


CALL AllocAry(p%uuN0, p%dof_node,p%nodes_per_elem, p%elem_total,'uuN0 (initial position) array',ErrStat2,ErrMsg2); CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName )
CALL AllocAry(p%twN0, p%nodes_per_elem, p%elem_total,'twN0 (initial twist) array',ErrStat2,ErrMsg2); CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName )
CALL AllocAry(p%rrN0, (p%dof_node/2),p%nodes_per_elem, p%elem_total,'p%rrN0',ErrStat2,ErrMsg2); CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName )
CALL AllocAry(p%uu0, p%dof_node, p%nqp, p%elem_total,'p%uu0', ErrStat2,ErrMsg2); CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName )
CALL AllocAry(p%E10, (p%dof_node/2),p%nqp, p%elem_total,'p%E10', ErrStat2,ErrMsg2); CALL SetErrStat( ErrStat2, ErrMsg2, ErrStat, ErrMsg, RoutineName )

Expand Down Expand Up @@ -1143,6 +1117,26 @@ subroutine SetParameters(InitInp, InputFileData, p, OtherState, ErrStat, ErrMsg)
! set parameters for pitch actuator:
!...............................................

! Actuator
p%UsePitchAct = InputFileData%UsePitchAct
if (p%UsePitchAct) then
p%pitchK = InputFileData%pitchK
p%pitchC = InputFileData%pitchC
p%pitchJ = InputFileData%pitchJ

! calculate (I-hA)^-1
p%torqM(1,1) = p%pitchJ + p%pitchC*p%dt
p%torqM(2,1) = -p%pitchK * p%dt
p%torqM(1,2) = p%pitchJ * p%dt
p%torqM(2,2) = p%pitchJ
denom = p%pitchJ + p%pitchC*p%dt + p%pitchK*p%dt**2
if (EqualRealNos(denom,0.0_BDKi)) then
call SetErrStat(ErrID_Fatal, "Cannot invert matrix for pitch actuator: J+c*dt+k*dt^2 is zero.", ErrStat, ErrMsg, RoutineName)
return
else
p%torqM(:,:) = p%torqM / denom
end if
end if

!...............................................
! set parameters for File I/O data:
Expand Down Expand Up @@ -2252,58 +2246,73 @@ SUBROUTINE BD_QuadraturePointDataAt0( p )

TYPE(BD_ParameterType), INTENT(INOUT) :: p !< Parameters

CHARACTER(*), PARAMETER :: RoutineName = 'BD_QuadraturePointDataAt0'
INTEGER(IntKi) :: ErrStat2 ! The error status code
CHARACTER(ErrMsgLen) :: ErrMsg2 ! The error message, if an error occurred
REAL(BDKi) :: rot0_temp(3)
REAL(BDKi) :: rotu_temp(3)
REAL(BDKi) :: rot_temp(3)
REAL(BDKi) :: R0_temp(3,3)

INTEGER(IntKi) :: nelem ! number of current element
INTEGER(IntKi) :: idx_qp ! index of current quadrature point
INTEGER(IntKi) :: i
REAL(BDKi) :: twist, tan_vect(3), R0(3), u0(3)
INTEGER(IntKi) :: idx_node ! index of current GLL node

! Loop through elements
DO nelem = 1,p%elem_total
CHARACTER(*), PARAMETER :: RoutineName = 'BD_QuadraturePointDataAt0'

! Loop through quadrature points
do idx_qp = 1, p%nqp

! Loop through displacement DOFs
do i = 1,3
! Initialize to zero for the summation
p%uu0(:,:,:) = 0.0_BDKi
p%rrN0(:,:,:) = 0.0_BDKi
p%E10(:,:,:) = 0.0_BDKi

! Calculate the quadrature point initial positions by using the
! shape functions to interpolate from the node initial positions
! Initial displacement field \n
! \f$ \underline{u_0}\left( \xi \right) =
! \sum_{k=1}^{p+1} h^k\left( \xi \right) \underline{\hat{u}_0}^k
! \f$
u0(i) = dot_product(p%Shp(:,idx_qp), p%uuN0(i,:,nelem))

! Calculate \f$ x_0^\prime \f$, the derivative with respect to \f$ \hat{x} \f$-direction
! (tangent to curve through this GLL point)
! This uses the shape function derivative to calculate the tangent at the quadrature points
! with respect to the element axis from the node positions.
! Note: this is a unit vector after scaling by the Jacobian
tan_vect(i) = dot_product(p%ShpDer(:,idx_qp), p%uuN0(i,:,nelem)) / p%Jacobian(idx_qp,nelem)
! calculate rrN0 (Initial relative rotation array)
DO nelem = 1,p%elem_total
p%rrN0(1:3,1,nelem) = (/ 0.0_BDKi, 0.0_BDKi, 0.0_BDKi /) ! first node has no rotation relative to itself.
DO idx_node=2,p%nodes_per_elem
! Find resulting rotation parameters R(Nr) = Ri^T(Nu(1)) R(Nu(:))
! where R(Nu(1))^T is the transpose rotation parameters for the root node
CALL BD_CrvCompose(p%rrN0(1:3,idx_node,nelem),p%uuN0(4:6,1,nelem),p%uuN0(4:6,idx_node,nelem),FLAG_R1TR2) ! rrN0 = node composed with root
ENDDO
ENDDO

end do

! Interpolate the twist to QP from the shape function and node values
twist = dot_product(p%Shp(:,idx_qp), p%twN0(:,nelem))
DO nelem = 1,p%elem_total
DO idx_qp = 1,p%nqp
!> ### Calculate the the initial displacement fields in an element
!! Initial displacement field \n
!! \f$ \underline{u_0}\left( \xi \right) =
!! \sum_{k=1}^{p+1} h^k\left( \xi \right) \underline{\hat{u}_0}^k
!! \f$ \n
!! and curvature \n
!! \f$ \underline{c_0}\left( \xi \right) =
!! \sum_{k=1}^{p+1} h^k\left( \xi \right) \underline{\hat{c}_0}^k
!! \f$

! Calculate quadrature point initial rotation, R0
! The nodal rotation function is used to avoid errors that occur when
! when interpolating the QP rotations from the node rotations.
call BD_ComputeIniNodalCrv(tan_vect, twist, R0, ErrStat2, ErrMsg2)
! Note that p%uu0 was set to zero prior to this routine call, so the following is the summation.

! Save initial position and rotation
p%uu0(1:3,idx_qp,nelem) = u0
p%uu0(4:6,idx_qp,nelem) = R0
DO idx_node=1,p%nodes_per_elem
p%uu0(1:3,idx_qp,nelem) = p%uu0(1:3,idx_qp,nelem) + p%Shp(idx_node,idx_qp)*p%uuN0(1:3,idx_node,nelem)
p%uu0(4:6,idx_qp,nelem) = p%uu0(4:6,idx_qp,nelem) + p%Shp(idx_node,idx_qp)*p%rrN0(1:3,idx_node,nelem)
ENDDO

! Save initial tangent vector for calculating strain
p%E10(1:3,idx_qp,nelem) = tan_vect

end do
!> Add the blade root rotation parameters. That is,
!! compose the rotation parameters calculated with the shape functions with the rotation parameters
!! for the blade root.
rot0_temp(:) = p%uuN0(4:6,1,nelem) ! Rotation at root
rotu_temp(:) = p%uu0( 4:6,idx_qp,nelem) ! Rotation at current GLL point without root rotation

CALL BD_CrvCompose(rot_temp,rot0_temp,rotu_temp,FLAG_R1R2) ! rot_temp = rot0_temp composed with rotu_temp
p%uu0(4:6,idx_qp,nelem) = rot_temp(:) ! Rotation parameters at current GLL point with the root orientation


!> Set the initial value of \f$ x_0^\prime \f$, the derivative with respect to \f$ \hat{x} \f$-direction
!! (tangent to curve through this GLL point). This is simply the
CALL BD_CrvMatrixR(p%uu0(4:6,idx_qp,nelem),R0_temp) ! returns R0_temp (the transpose of the DCM orientation matrix)
p%E10(:,idx_qp,nelem) = R0_temp(:,3) ! unit vector tangent to curve through this GLL point (derivative with respect to z in IEC coords).
ENDDO
ENDDO


END SUBROUTINE BD_QuadraturePointDataAt0


Expand Down Expand Up @@ -2351,43 +2360,48 @@ SUBROUTINE BD_DisplacementQP( nelem, p, x, m )
TYPE(BD_ContinuousStateType), INTENT(IN ) :: x !< Continuous states at t
TYPE(BD_MiscVarType), INTENT(INOUT) :: m !< misc/optimization variables

INTEGER(IntKi) :: node_start !< Node point of first node in current element
INTEGER(IntKi) :: node_end !< Node point of last node in current element
INTEGER(IntKi) :: i, idx_qp
INTEGER(IntKi) :: idx_qp !< index to the current quadrature point
INTEGER(IntKi) :: elem_start !< Node point of first node in current element
INTEGER(IntKi) :: idx_node
CHARACTER(*), PARAMETER :: RoutineName = 'BD_DisplacementQP'

! Node at start and end of element
node_start = p%node_elem_idx(nelem,1)
node_end = node_start + p%nodes_per_elem - 1

!> ### Calculate the the displacement fields in an element
!! Using equations (27) and (28) \n
!! \f$ \underline{u}\left( \xi \right) =
!! \sum_{i=1}^{p+1} h^i\left( \xi \right) \underline{\hat{u}}^i
!! \f$ \n
!! and \n
!! \f$ \underline{u}^\prime \left( \xi \right) =
!! \sum_{k=1}^{p+1} h^{k\prime} \left( \xi \right) \underline{\hat{u}}^i
!! \f$
!!
!! | Variable | Value |
!! | :---------: | :------------------------------------------------------------------------- |
!! | \f$ \xi \f$ | Element natural coordinate \f$ \in [-1,1] \f$ |
!! | \f$ k \f$ | Node number of a \f$ p^\text{th} \f$ order Langrangian-interpolant |
!! | \f$ h^i \left( \xi \right ) \f$ | Component of the shape function matrix, \f$ \underline{\underline{N}} \f$ |
!! | \f$ h^{k\prime} \left( \xi \right ) \f$ | \f$ \frac{\mathrm{d}}{\mathrm{d}x_1} h^i \left( \xi \right) \f$ |
!! | \f$ \underline{\hat{u}}^i \f$ | \f$ k^\text{th} \f$ nodal value

! Loop through all quadrature points and displacement DOFs
! dot_product appears to be more exact that matmul
forall (idx_qp = 1:p%nqp, i = 1:3)
m%qp%uuu(i,idx_qp,nelem) = dot_product(p%Shp(:,idx_qp), x%q(i,node_start:node_end))
m%qp%uup(i,idx_qp,nelem) = dot_product(p%ShpDer(:,idx_qp), x%q(i,node_start:node_end)) / p%Jacobian(idx_qp,nelem)
end forall

!> Calculate \f$ \underline{E}_1 = x_0^\prime + u^\prime \f$ (equation 23). Note E_1 is along the z direction.
m%qp%E1(1:3,:,nelem) = p%E10(1:3,:,nelem) + m%qp%uup(1:3,:,nelem)

DO idx_qp=1,p%nqp
! Node point before start of this element
elem_start = p%node_elem_idx( nelem,1 )


!> ### Calculate the the displacement fields in an element
!! Using equations (27) and (28) \n
!! \f$ \underline{u}\left( \xi \right) =
!! \sum_{i=1}^{p+1} h^i\left( \xi \right) \underline{\hat{u}}^i
!! \f$ \n
!! and \n
!! \f$ \underline{u}^\prime \left( \xi \right) =
!! \sum_{k=1}^{p+1} h^{k\prime} \left( \xi \right) \underline{\hat{u}}^i
!! \f$
!!
!! | Variable | Value |
!! | :---------: | :------------------------------------------------------------------------- |
!! | \f$ \xi \f$ | Element natural coordinate \f$ \in [-1,1] \f$ |
!! | \f$ k \f$ | Node number of a \f$ p^\text{th} \f$ order Langrangian-interpolant |
!! | \f$ h^i \left( \xi \right ) \f$ | Component of the shape function matrix, \f$ \underline{\underline{N}} \f$ |
!! | \f$ h^{k\prime} \left( \xi \right ) \f$ | \f$ \frac{\mathrm{d}}{\mathrm{d}x_1} h^i \left( \xi \right) \f$ |
!! | \f$ \underline{\hat{u}}^i \f$ | \f$ k^\text{th} \f$ nodal value |

! Initialize values for summation
m%qp%uuu(:,idx_qp,nelem) = 0.0_BDKi ! displacement field \f$ \underline{u} \left( \xi \right) \f$
m%qp%uup(:,idx_qp,nelem) = 0.0_BDKi ! displacement field \f$ \underline{u}^\prime \left( \xi \right) \f$

DO idx_node=1,p%nodes_per_elem
m%qp%uuu(1:3,idx_qp,nelem) = m%qp%uuu(1:3,idx_qp,nelem) + p%Shp(idx_node,idx_qp) *x%q(1:3,elem_start - 1 + idx_node)
m%qp%uup(1:3,idx_qp,nelem) = m%qp%uup(1:3,idx_qp,nelem) + p%ShpDer(idx_node,idx_qp)/p%Jacobian(idx_qp,nelem)*x%q(1:3,elem_start - 1 + idx_node)
ENDDO

!> Calculate \f$ \underline{E}_1 = x_0^\prime + u^\prime \f$ (equation 23). Note E_1 is along the z direction.
m%qp%E1(1:3,idx_qp,nelem) = p%E10(1:3,idx_qp,nelem) + m%qp%uup(1:3,idx_qp,nelem)

ENDDO
END SUBROUTINE BD_DisplacementQP


Expand Down Expand Up @@ -2738,6 +2752,8 @@ subroutine Calc_Fc_Fd()
REAL(BDKi) :: e1s
REAL(BDKi) :: eee(6) !< intermediate array for calculation Strain and curvature terms of Fc
REAL(BDKi) :: fff(6) !< intermediate array for calculation of the elastic force, Fc
REAL(BDKi) :: R(3,3) !< rotation matrix at quatrature point
REAL(BDKi) :: Rx0p(3) !< \f$ \underline{R} \underline{x}^\prime_0 \f$
!REAL(BDKi) :: Wrk(3)


Expand All @@ -2751,8 +2767,10 @@ subroutine Calc_Fc_Fd()
!!
!! Note: \f$ \underline{\underline{R}}\underline{\underline{R}}_0 \f$ is used to go from the material basis into the inertial basis
!! and the transpose for the other direction.
eee(1:3) = m%qp%E1(1:3,idx_qp,nelem) - m%qp%RR0(1:3,3,idx_qp,nelem) ! Using RR0 z direction in IEC coords

! eee(1:3) = m%qp%E1(1:3,idx_qp,nelem) - m%qp%RR0(1:3,3,idx_qp,nelem) ! Using RR0 z direction in IEC coords
call BD_CrvMatrixR(m%qp%uuu(4:6,idx_qp,nelem), R) ! Get rotation at QP as a matrix
Rx0p = matmul(R,p%E10(:,idx_qp,nelem)) ! Calculate rotated initial tangent
eee(1:3) = m%qp%E1(1:3,idx_qp,nelem) - Rx0p ! Use rotated initial tangent in place of RR0*i1 to eliminate likely mismatch between R0*i1 and x0'

!> ### Set the 1D sectional curvature, \f$ \underline{\kappa} \f$, equation (5)
!! \f$ \underline{\kappa} = \underline{k} + \underline{\underline{R}}\underline{k}_i \f$
Expand Down
Loading