Skip to content

Commit

Permalink
Merge pull request WEC-Sim#1058 from akeeste/added_mass_updates
Browse files Browse the repository at this point in the history
Added mass updates
  • Loading branch information
salhus authored Jul 26, 2023
2 parents 636eed5 + 104a419 commit cba3cca
Show file tree
Hide file tree
Showing 6 changed files with 156 additions and 84 deletions.
132 changes: 88 additions & 44 deletions docs/_include/added_mass.rst
Original file line number Diff line number Diff line change
@@ -1,89 +1,133 @@
.. _dev-added-mass:

Theoretical Implementation
^^^^^^^^^^^^^^^^^^^^^^^^^^^

Added mass is a special multi-directional fluid dynamic phenomenon that most
physics software cannot account for well. WEC-Sim uses a special added mass
treatment to get around the current limitations of Simscape Multibody. For the
most robust simulation, the added mass matrix should be combined with the mass
and inertia, shown in the manipulation of the governing equation below:
physics software cannot account for well.
Modeling difficulties arise because the added mass force is proportional to acceleration.
However most time-domain simulations are attempting to use the calculated forces to determine
a body's acceleration, which then determines the velocity and position at the next time step.
Solving for acceleration when forces are dependent on acceleration creates an algebraic loop.

The most robust solution is to combine the added mass matrix with the rigid body's mass and inertia,
shown in the manipulation of the governing equation below:

.. math::

m\ddot{X_i} &= \Sigma F(t,\omega) - A\ddot{X_i} \\
(m+A)\ddot{X_i} &= \Sigma F(t,\omega) \\
M\ddot{X_i} &= \Sigma F(t,\omega) - A\ddot{X_i} \\
(M+A)\ddot{X_i} &= \Sigma F(t,\omega) \\
M_{adjusted}\ddot{X_i} &= \Sigma F(t,\omega)

where :math:`m` is the mass, :math:`I` is the moment of inertia, :math:`A` is the added mass, and subscript :math:`i` represents the timestep being solved for.
In this case, the mass of a body is set to the sum of the translational mass, rotational inertia and the added mass matrix:
where capital :math:`M` is the mass matrix, :math:`A` is the added mass, and subscript :math:`i` represents the timestep being solved for.
In this case, the adjusted body mass matrix is defined as the sum of the translational mass (:math:`m`), inertia tensor (:math:`I`), and the added mass matrix:

.. math::

M_{adjusted} = \begin{bmatrix}
m + A_{1,1} & A_{1,2} & A_{1,3} & A_{1,4} & A_{1,5} & A_{1,6} \\
A_{2,1} & m + A_{2,2} & A_{2,3} & A_{2,4} & A_{2,5} & A_{2,6} \\
A_{3,1} & A_{3,2} & m + A_{3,3} & A_{3,4} & A_{3,5} & A_{3,6} \\
A_{4,1} & A_{4,2} & A_{4,3} & I_{4,4} + A_{4,4} & A_{4,5} & A_{4,6} \\
A_{5,1} & A_{5,2} & A_{5,3} & A_{5,4} & I_{5,5} + A_{5,5} & A_{5,6} \\
A_{6,1} & A_{6,2} & A_{6,3} & A_{6,4} & A_{6,5} & I_{6,6} + A_{6,6} \\
A_{4,1} & A_{4,2} & A_{4,3} & I_{1,1} + A_{4,4} & -I_{2,1} + A_{4,5} & -I_{3,1} + A_{4,6} \\
A_{5,1} & A_{5,2} & A_{5,3} & I_{2,1} + A_{5,4} & I_{2,2} + A_{5,5} & -I_{3,2} + A_{5,6} \\
A_{6,1} & A_{6,2} & A_{6,3} & I_{3,1} + A_{6,4} & I_{3,2} + A_{6,5} & I_{3,3} + A_{6,6} \\
\end{bmatrix}

This formulation is ideal because it removes the acceleration dependence from the right hand side of the equation.
Without this treatment, the acceleration creates an unsolvable algebraic loop.
There are ways to get around this issue, but simulation robustness and stability become more difficult.
This formulation is desirable because it removes the acceleration dependence from the right hand side of the governing equation.
Without this treatment, the acceleration causes an unsolvable algebraic loop.
There are alternative approximations to solve the algebraic loop, but simulation robustness and stability become increasingly difficult.

The core issue with this combined mass formulation is that Simscape Multibody, and most other physics software, do not allow a generic body to have a degree-of-freedom specific mass.
For example, a rigid body can't have one mass for surge motion and another mass for heave motion.
Simscape rigid bodies only have one translational mass, a 1x3 moment of inertia matrix, and 1x3 product of inertia matrix.

The core issue with this combined mass formulation is that Simscape does not allow a generic body to have a degree-of-freedom specific mass.
A Simscape body is only allowed to have one translational mass and three values of inertia about each translational axis.
WEC-Sim's Implemenation
^^^^^^^^^^^^^^^^^^^^^^^^

Due to this limitation, WEC-Sim cannot combine the mass and added mass on the left-hand side of the equation of motion (as shown above).
Instead, WEC-Sim moves some components of added mass, while the majority of the components remain on the right-hand side.
There is a 1-1 mapping between rotational inertia and the roll-roll (4,4), pitch-pitch (5,5), yaw-yaw (6,6) added mass components.
Additionally, some combination of the surge-surge (1,1), sway-sway (2,2), heave-heave (3,3) components correspond to the translational mass of the body. Therefore, WEC-Sim treats the added mass in the following way:
Due to this limitation, WEC-Sim cannot combine the body mass and added mass on the left-hand side of the equation of motion (as shown above).
The algebaric loop can be solved by predicting the acceleration at the current time step, and using that to calculate the added mass force.
But this method can cause numerical instabilities.
Instead, WEC-Sim decreases the added mass force magnitude by moving *some* components of added mass into the body mass, while a modified added mass force is calculated with the remainder of the added mass coefficients.

There is a 1-1 mapping between the body's inertia tensor and rotational added mass coefficients.
These added mass coefficients are entirely lumped with the body's inertia.
Additionally, the surge-surge (1,1), sway-sway (2,2), heave-heave (3,3) added mass coefficients correspond to the translational mass of the body, but must be treated identically.

WEC-Sim implements this added mass treatment using both a modified added mass matrix and a modified body mass matrix:

.. math::

M_{adjusted} &= m + \alpha Y \\
M\ddot{X_i} &= \Sigma F(t,\omega) - A\ddot{X_i} \\
(M+dMass)\ddot{X_i} &= \Sigma F(t,\omega) - (A-dMass)\ddot{X_i} \\
M_{adjusted}\ddot{X_i} &= \Sigma F(t,\omega) - A_{adjusted}\ddot{X_i} \\

where
where :math:`dMass` is the change in added mass and defined as:

.. math::

dMass &= \begin{bmatrix}
\alpha Y & 0 & 0 & 0 & 0 & 0 \\
0 & \alpha Y & 0 & 0 & 0 & 0 \\
0 & 0 & \alpha Y & 0 & 0 & 0 \\
0 & 0 & 0 & A{4,4} & -A{5,4} & -A{6,4} \\
0 & 0 & 0 & A{5,4} & A{5,5} & -A{6,5} \\
0 & 0 & 0 & A{6,4} & A{6,5} & A{6,6} \\
\end{bmatrix} \\
Y &= (A_{1,1} + A_{2,2} + A_{3,3}) \\
\alpha &= body(iBod).adjMassFactor

and
The resultant definition of the body mass matrix and added mass matrix are then:

.. math::

I_{adjusted} &= \begin{bmatrix}
I_{4,4} + A_{4,4} \\
I_{5,5} + A_{5,5} \\
I_{6,6} + A_{6,6} \\
\end{bmatrix} \\
M &= \begin{bmatrix}
m + \alpha Y & 0 & 0 & 0 & 0 & 0 \\
0 & m + \alpha Y & 0 & 0 & 0 & 0 \\
0 & 0 & m + \alpha Y & 0 & 0 & 0 \\
0 & 0 & 0 & I_{4,4} + A_{4,4} & -(I_{5,4} + A_{5,4}) & -(I_{6,4} + A_{6,4}) \\
0 & 0 & 0 & I_{5,4} + A_{5,4} & I_{5,5} + A_{5,5} & -(I_{6,5} + A_{6,5}) \\
0 & 0 & 0 & I_{6,4} + A_{6,4} & I_{6,5} + A_{6,5} & I_{6,6} + A_{6,6} \\
\end{bmatrix} \\
A_{adjusted} &= \begin{bmatrix}
A_{1,1} - \alpha Y & A_{1,2} & A_{1,3} & A_{1,4} & A_{1,5} & A_{1,6} \\
A_{2,1} & A_{2,2} - \alpha Y & A_{2,3} & A_{2,4} & A_{2,5} & A_{2,6} \\
A_{3,1} & A_{3,2} & A_{3,3} - \alpha Y & A_{3,4} & A_{3,5} & A_{3,6} \\
A_{4,1} & A_{4,2} & A_{4,3} & 0 & A_{4,5} & A_{4,6} \\
A_{5,1} & A_{5,2} & A_{5,3} & A_{5,4} & 0 & A_{5,6} \\
A_{6,1} & A_{6,2} & A_{6,3} & A_{6,4} & A_{6,5} & 0\\
\end{bmatrix}
A_{4,1} & A_{4,2} & A_{4,3} & 0 & A_{4,5} + A_{5,4} & A_{4,6} + A_{6,4} \\
A_{5,1} & A_{5,2} & A_{5,3} & 0 & 0 & A_{5,6} + A_{6,5} \\
A_{6,1} & A_{6,2} & A_{6,3} & 0 & 0 & 0 \\
\end{bmatrix}

.. Note::
We should see that :math:`A_{4,5} + A_{5,4} = A_{4,6} + A_{6,4} = A_{5,6} + A_{6,5} = 0`, but there may be numerical differences in the added mass coefficients which are preserved.

The factor :math:`\alpha` represents ``simu.adjMassFactor =2``, the default value.
Though the components of added mass and body mass are manipulated in WEC-Sim, the total system is unchanged.
This manipulation does not affect the governing equations of motion, only the implementation.

The summation of the adjusted mass, inertia and added mass is identical to the original summation above.
The governing equation of motion does not change, only its implementation.
A simulation class weight factor controls the degree to which the added mass is adjusted to create the most robust simulation possible.
To see its effects, set ``simu.adjMassFactor = 0`` and WEC-Sim will likely become unstable.
The fraction of translational added mass that is moved into the body mass is determined by ``body(iBod).adjMassFactor``, whose default value is :math:`2.0`.
Advanced users may change this weighting factor in the ``wecSimInuptFile`` to create the most robust simulation possible.
To see its effects, set ``body(iB).adjMassFactor = 0`` and see if simulations become unstable.

However WEC-Sim again contains an unsolvable algebraic loop due to the acceleration dependence.
WEC-Sim removes this algebraic problem using a `Simulink Transport Delay <https://www.mathworks.com/help/simulink/slref/transportdelay.html>`_ with a very small time delay (``1e-8``).
This typically results in using the acceleration at a previous time step to calculate the added mass force.
However, since the time delay is smaller than the simulation time step Simulink will extrapolate the previous step to within 1e-8 of the current time step.
This manipulation does not move all added mass components.
WEC-Sim still contains an algebraic loop due to the acceleration dependence of the remaining added mass force from :math:`A_{adjusted}`, and components of the Morison Element force.
WEC-Sim solves the algebraic loop using a `Simulink Transport Delay <https://www.mathworks.com/help/simulink/slref/transportdelay.html>`_ with a very small time delay (``1e-8``).
This blocks extrapolates the previous acceleration by ``1e-8`` seconds, which results in a known acceleration for the added mass force.
The small extraplation solves the algebraic loop but prevents large errors that arise when extrapolating the acceleration over an entire time step.
This will convert the algebraic loop equation of motion to a solvable one:

.. math::

M_{adjusted}\ddot{X_i} &= \Sigma F(t,\omega) - A_{adjusted}\ddot{X}_{i - (10^{-8}/dt)} \\
M_{adjusted}\ddot{X_i} &= \Sigma F(t,\omega) - A_{adjusted}\ddot{X}_{i - (1 + 10^{-8}/dt)} \\

Working with the Added Mass Implementation
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

WEC-Sim's added mass implementation should not affect a user's modeling workflow.
WEC-Sim handles the manipulation and restoration of the mass and forces in the bodyClass functions ``adjustMassMatrix()`` called by ``initializeWecSim`` and ``restoreMassMatrix``, ``storeForceAddedMass`` called by ``postProcessWecSim``.
However viewing ``body.mass, body.inertia, body,inertiaProducts, body.hydroForce.fAddedMass`` between calls to ``initializeWecSim`` and ``postProcessWecSim`` will not show the input file definitions.
Users can get the manipulated mass matrix, added mass coefficients, added mass force and total force from ``body.hydroForce.storage`` after the simulation.
However, in the rare case that a user wants to manipulate the added mass force *during* a simulation, the change in mass, :math:`dMass` above, must be taken into account. Refer to how ``body.calculateForceAddedMass()`` calculates the entire added mass force in WEC-Sim post-processing.

The acceleration used for the added mass represents the previous time step (:math:`i-1`) interpolated to ``1e-8`` seconds before the current time step being solved.
This can be thought of as a ``i-0.001%`` time step; a close approximation of the current time step.
.. Note:: If applying the method in ``body.calculateForceAddedMass()`` *during* the simulation, the negative of ``dMass`` must be taken: :math:`dMass = -dMass`. This must be accounted for because the definitions of mass, inertia, etc and their stored values are flipped between simulation and post-processing.

.. Note::
Depending on the wave formulation used, :math:`A` can either be a function of wave frequency :math:`A(\omega)`, or equal to the added mass at infinite wave frequency :math:`A_{\infty}`
16 changes: 8 additions & 8 deletions docs/_include/morison_element.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
As a reminder from the WEC-Sim Theory Manual, the Morison force equation assumes that the fluid forces in an oscillating flow on a structure of slender cylinders or other similar geometries arise partly from pressure effects from potential flow and partly from viscous effects. A slender cylinder implies that the diameter, :math:`D`, is small relative to the wave length, :math:`\lambda`, which is generally satisfied when :math:`D/\lambda<0.1-0.2`. If this condition is not met, wave diffraction effects must be taken into account. Assuming that the geometries are slender, the resulting force can be approximated by a modified Morison formulation for each element on the body.

Fixed Body
##########
^^^^^^^^^^

For a fixed body in an oscillating flow the force imposed by the fluid is given by:

Expand Down Expand Up @@ -63,7 +63,7 @@ The acceleration of the fluid particles will then be obtained by taking the time
Orbital velocity magnitude vectors for a wave period of 10 s and water depth of 50 m with a wave heading of 0 rads.

Moving Body
###########
^^^^^^^^^^^

If the body is allowed to move in an oscillating flow then Eqn. :eq:`fixed` must be adjusted as follows:

Expand All @@ -75,7 +75,7 @@ where :math:`U` is the body velocity. In the calculations performed by WEC-Sim,


Review of Rigid Body Dynamics
*****************************
"""""""""""""""""""""""""""""
A rigid body is an idealization of a solid body in which deformation is neglected. In other words, the distance between any two given points of a rigid body remains constant in time regardless of external forces exerted on it. The position of the whole body is represented by its linear position together with its angular position with a global fixed reference frame. WEC-Sim calculates the position, velocity, and acceleration of the rigid body about its center of gravity; however, the placement of each morrison element will have a different local velocity that affects the fluid force. The relative velocity between point A and point B on a rigid body is given by:
Expand All @@ -90,12 +90,12 @@ where :math:`\omega` is the angular velocity of the body and :math:`\times` deno
:label: relA
WEC-Sim Implementations
#######################
^^^^^^^^^^^^^^^^^^^^^^^
As discussed in the WEC-Sim user manual, there are two options to model a Morison element(s) and will be described here in greater detail so potential developers can modify the code to suit their modeling needs.
Option 1
********
""""""""
In the first Morison element implementation option, the acceleration and velocity of the fluid flow are estimated at the Morison point of application, which can include both wave and current contributions, and then subtracts the body acceleration and velocity for the individual translational degrees of freedom (x-, y-, and z-components). The fluid flow properties are then used to calculate the Morison element force, indepenently for each degree of freedom, as shown by the following expressions:
Expand All @@ -109,7 +109,7 @@ In the first Morison element implementation option, the acceleration and velocit
where :math:`r_{g}` is the lever arm from the center of gravity of the body to the Morison element point of application. Option 1 provides the most flexibility in setting independent Morison element properties for the x-, y-, and z-directions; however, a limitation arises that the fluid flow magnitude does not consider the other fluid flow components. Depending on the simulation enviroment this approach can provide the same theoretical results as taking the magnitude of the x-, y-, and z-components of the fluid flow, but is case dependent. A comparison between the outputs of Option 1 and Option 2 can be found later in the Developer Manual Morison Element documentation.
Option 2
********
""""""""
The WEC-Sim Option 1 implementation solves for the of the Morison element force from the individual x-, y-, and z-components of the relative flow velocity and acceleration; however, this results in incorrect outputs at certain orientations of the flow and Morison Element. As opposed to solving for the x-, y-, and z-components of the Morison element force, the force can be calculated relative to the magnitude of the flow and distributed among its unit vector direction. Therefore the approach used in Option 2 is to decompose the fluid and body velocity and acceleration into tangential and normal components of the Morison element, as depicted in Figure :ref:`fig-option-2`
Expand Down Expand Up @@ -150,7 +150,7 @@ The Morison element force equation for a moving body relative to the fluid flow
:label: mefOption2
Comparison of Performance Between Option 1 and Option 2
********************************************************
"""""""""""""""""""""""""""""""""""""""""""""""""""""""

A simple test case, which defines a Morison element as vertical and stationary relative to horizontal fluid flow, was built to compare the Morison element force calculation between Option 1 and Option 2 within WEC-Sim. Theoretically, the magnitude of the Morison element force should remain constant as the orientation of the flow direction is rotated in the X-Y plane. The MF was calculated as the orientation of the flow was rotated about the z-axis from 1 to 360 degrees where the central axis of the ME is parallel wtih the z-axis. The remaining WEC-Sim input values for the simulation can be found in the following table.

Expand All @@ -172,4 +172,4 @@ Displaced Volume :math:`\forall` 0.10 :math:`m^{3}`

Graphical representation of the comparison between ME Option 1 and Option 2 within WEC-Sim.

:math:`F_{ME,1}` and :math:`F_{ME,2}` is the Morison element force output from Option 1 and Option 2 within WEC-Sim, respectively. Shown in the above figure, in Option 1 there is an oscillation in Morison element magnitude with flow direction while Option 2 demonstrates a constant force magnitude at any flow direction. The reason behind this performance is that Option 1 solves for the MF individually using the individual the x-, y-, and z- components of the flow while Option 2 calculates the force relative to the flow magnitude and distributed among the normal and tangential unit vectors of the flow.
:math:`F_{ME,1}` and :math:`F_{ME,2}` is the Morison element force output from Option 1 and Option 2 within WEC-Sim, respectively. Shown in the above figure, in Option 1 there is an oscillation in Morison element magnitude with flow direction while Option 2 demonstrates a constant force magnitude at any flow direction. The reason behind this performance is that Option 1 solves for the MF individually using the individual the x-, y-, and z- components of the flow while Option 2 calculates the force relative to the flow magnitude and distributed among the normal and tangential unit vectors of the flow.
2 changes: 1 addition & 1 deletion source/functions/initializeWecSim.m
Original file line number Diff line number Diff line change
Expand Up @@ -454,7 +454,7 @@
fprintf('\nSimulating the WEC device defined in the SimMechanics model %s... \n',simu.simMechanicsFile)
% Modify some stuff for simulation
for iBod = 1:simu.numHydroBodies
body(iBod).adjustMassMatrix(simu.adjMassFactor,simu.b2b);
body(iBod).adjustMassMatrix(simu.b2b);
end; clear iBod
warning('off','Simulink:blocks:TDelayTimeTooSmall');
warning('off','Simulink:blocks:BusSelDupBusCreatorSigNames');
Expand Down
Loading

0 comments on commit cba3cca

Please sign in to comment.