Computing Multiple State Updates w/ MoorDyn

Hi,

I am currently running MoorDyn v1 as a simple library called from Matlab. My goal is to implement a particle filter algorithm on my model which requires that I compute mooring loads for a number of state updates. For example, given the state vector of displacements & velocities at time t1, I would like to compute mooring loads for a set of state vectors at t2. My understanding of MoorDyn is that it is storing internally its state vector and updating that when LinesCalc is called, implying that calling LinesCalc multiple times is not a viable option. I tested this with the following Matlab script:

% Check if MoorDyn can be called multiple times per update for SRCKF
clear all; close all; clc;

%% ----- Unload MoorDyn if Still Loaded ----- %%
if libisloaded('MoorDyn_Win64')
    calllib('MoorDyn_Win64','LinesClose');
    unloadlibrary('MoorDyn_Win64')
end

%% ----- Init Constants & Sim Parameters ----- %%
% MoorDyn parameters
dll_path = 'MoorDyn_Win64.dll';
header_path = 'MoorDyn.h';

% Simulation parameters
dt = 0.0125;
time = [0:dt:20];

% Displacements
X = [linspace(0,25,length(time));
     repmat(zeros(1,length(time)),[5,1])];

% Velocities
XD = zeros(size(X));

%% ----- Baseline Simulation ----- %%
% Load in MoorDyn
[notfound,warnings] = loadlibrary(dll_path,header_path);

% Prepare pointer
Fmooring_pointer = zeros(1,6);     
Fmooring_pointer = libpointer('doublePtr',Fmooring_pointer);

% Init MoorDyn
load_status = calllib('MoorDyn_Win64','LinesInit',zeros(6,1),zeros(6,1));

% Simulate surge displacement
Last_time = 0;
for i = 1:length(time)

    % Compute mooring loads
    calllib('MoorDyn_Win64','LinesCalc',X(:,i),XD(:,i),Fmooring_pointer,Last_time,dt);

    % Extract mooring forces
    Baseline_Force(:,i) = Fmooring_pointer.Value;

    % Store last time
    Last_time = time(i);

end

% Unload MoorDyn & clear pointer
if libisloaded('MoorDyn_Win64')
    calllib('MoorDyn_Win64','LinesClose');
    unloadlibrary('MoorDyn_Win64')
end

clear Fmooring_pointer

%% ----- Vary Surge Simulation ----- %%
% Load in MoorDyn
[notfound,warnings] = loadlibrary(dll_path,header_path);

% Prepare pointer
Fmooring_pointer = zeros(1,6);     
Fmooring_pointer = libpointer('doublePtr',Fmooring_pointer);

% Init MoorDyn
load_status = calllib('MoorDyn_Win64','LinesInit',zeros(6,1),zeros(6,1));

% Simulate surge displacement w/ 3 points per step
Last_time = 0;
for i = 1:length(time)

    % Compute mooring loads
    calllib('MoorDyn_Win64','LinesCalc',X(:,i) + 0.5*X(:,i),XD(:,i),Fmooring_pointer,Last_time,dt);
    calllib('MoorDyn_Win64','LinesCalc',X(:,i) - 0.5*X(:,i),XD(:,i),Fmooring_pointer,Last_time,dt);
    calllib('MoorDyn_Win64','LinesCalc',X(:,i),XD(:,i),Fmooring_pointer,Last_time,dt);

    % Extract mooring forces
    Middle_Force(:,i) = Fmooring_pointer.Value;

    % Store last time
    Last_time = time(i);

end

% Unload MoorDyn & clear pointer
if libisloaded('MoorDyn_Win64')
    calllib('MoorDyn_Win64','LinesClose');
    unloadlibrary('MoorDyn_Win64')
end

clear Fmooring_pointer

%% ----- Confirm MoorDyn Unloaded ----- %%
if libisloaded('MoorDyn_Win64')
    calllib('MoorDyn_Win64','LinesClose');
    unloadlibrary('MoorDyn_Win64')
end

%% ----- Plot Results Comparison ----- %%
% DOF titles
DOFs = {'Surge','Sway','Heave','Roll','Pitch','Yaw'};

% Generate plots
for i = [1,3,5]
    figure
    gca; hold on; box on;
    plot(time,Baseline_Force(i,:),'DisplayName','Baseline')
    plot(time,Middle_Force(i,:),'DisplayName','Multiple')
    xlabel('Time [s]')
    ylabel('Mooring Load [N]')
    title(sprintf('%s Mooring Force',DOFs{i}))
    legend
end

Which produced the following plots in Surge, Heave, and Pitch:



My current thought on how to get around this is to run MoorDyn for all displacement combinations within a reasonable range, and fit polynomials to each element of the 6x6 mooring stiffness array for quick computing of mooring forces from displacement. While this would neglect dynamic effects, at high sample rates I’m thinking this might be OK. My question is therefore twofold: firstly, is there potentially a way around this approach to use the MoorDyn library directly? Closing and re-initializing the lines for each would not be feasible. And secondly, if not, thoughts on my alternate approach?

Best,
Ian

Hi @Ian.Ammerman,

If I am understanding right you are using MoorDyn-C for this (GitHub - FloatingArrayDesign/MoorDyn: a lumped-mass mooring line model intended for coupling with floating structure codes) as that is the only place MoorDyn v1 is available. You are correct that moordyn stores the state vector internally between calls to LineCalc. You are not supposed to call Lines calc multiple times at the same timestep, this will cause the time outputs to not agree between your two versions.

A coupled thoughts on your questions:
Do you have any specific reason to use MD v1? If not use version 2. Version 2 has significant improvements over version 1 and is more accurate. Most helpful to your work, version 2 allows for multiple instances of MoorDyn to be called in parallel. Additionally, using version 2 you are able to compile and build a matlab wrapper for MoorDyn: MoorDyn Wrappers and Drivers — MoorDyn 2.2.2 documentation. From there it is possible to run multiple instances of MoorDyn in parallel from a single input file using something along the lines of this puesdo code:

system1 = MoorDynM_Create('<filename>')
system2 = MoorDynM_Create('<filename>')
...
systemN = MoorDynM_Create('<filename>')

% set up state variable stuff here
<state stuff>

% initialize systems
MoorDynM_Init(system1, x1, xd1)
MoorDynM_Init(system2, x2, xd2)
...
MoorDynM_Init(systemN, xN, xdN)

% do time stepping
dt = <coupling timestep>
for i = 1:length(time)

   [t1, f1] = MoorDynM_Step(system1, x1, xd1, t, dt) % t1 is the time and f1 is the force array same length as the state x1
   [t2, f2] = MoorDynM_Step(system2, x2, xd2, t, dt)
   ...
   [tN, fN] = MoorDynM_Step(systemN, xN, xdN, t, dt)
   t = t + dt

% close things up
MoorDynM_Close(system1)
MoorDynM_Close(system2)
...
MoorDynM_Close(systemN)

As long as you don’t need to change the number of MoorDyn instances (number of state vectors) during your simulation then this option will work fine based on what it seems you need to do.

An alternative to this is to not use MoorDyn at all and instead use a different tool like MoorPy, which follows a similar structure to MoorDyn but solves for mooring loads using a quasi-static approach (much faster than MoorDyn): MoorPy — MoorPy 0.9.1 documentation

Hi @Ryan.Davies ,

Thank you for the response. You are correct that I have been using the MoorDyn-C to this point.

There isn’t any technical reason that I can’t use MoorDyn v2. Up to this point v1 was what I was familiar with and was sufficient. To your point about running multiple instances in parallel, I suspect I would still need to initialize the other instances at each time step. The general flow of the particle filter (square-root cubature Kalman filter specifically) I have implemented is as follows:

  1. Generate 2n sigma points (state vectors) around the current (mean) state.
  2. Propogate sigma points forward using dynamics model.
  3. Recombine sigma points into updated mean state
  4. Generate 2n sigma points based on new state vector.
  5. Compute model outputs.
  6. Recombine output sigma points into updated mean output.
  7. Compute Kalman gain and perform correction on mean state.

This is a simplified overview of course, excluding uncertainty and covariance calculations.

Currently, I compute the mooring loads prior to step 1 using the current mean state and treat those forces as constant for each sigma point. If I were to implement MoorDyn v2, it seems like I would create 2n+1 systems, with the first being the “baseline” system state. This system would only be updated after step 7 when the updated “true” state is confirmed to maintain the internal states. That leaves the issue of the remaining 2n systems, which would need to have the same internal state as the baseline. I wonder, can system objects be “copied”? I.e. something like this:

%%% FOR EACH TIMESTEP ...

% Update baseline mooring system
calllib('MoorDyn','LinesCalc',baseline,X,XD, ...)

% Create 2n mooring systems
system1 = baseline;
system2 = baseline;
...
system2n = baseline;

% Propogate system
for i = 1:2n
     % Compute mooring load for sigma point
     calllib('MoorDyn','LinesCalc',systemi,Xi,XDi,...)

     % Do system dynamics calcs...
end

 % Do state correction
 X = X + Ky;

By copying the system objects, the internal state starting points are consistent - otherwise each system would need to be initialized independently, which would be computationally intractable I think.

Alternatively, as you mention MoorPy and the quasi-static approach, this looks like it could be a viable alternative at first glance. I will play around with this some more to better understand it.

Currently all of my code is in Matlab, though it could easily be converted to Python I think to implement this way. Am I correct in thinking that with the quasi-static method, the results are independent of the starting state? I.e., a floater starting at any initial condition would yield the same outputs for the same r6 input? While this would neglect dynamic effects, it seems this would be better suited to what I am trying to compute.

Best,
Ian

@Ian.Ammerman unfortunately you can’t copy systems like this, as the system variable is a pointer to an initialized system, so in your example code any calls to the variables system1-2n will just be repeated calls to the baseline system. If you were to just call the step function with the mean state for all the systems, MoorDyn would have non-physical forces because it would see the fairleads jumping to different places.

Just to be clear, are you expecting the output from the mooring model to be forces based on a displacement input? If thats the case then MoorPy is a better approach. You are correct the quasi-static approach is independent of state. In the quasi-static approach you give the model the displacement and it tells you the resulting force at that position, there’s no time dependence and no dynamics at play. MoorPy is quite a bit faster than MoorDyn and is used for a lot of optimization work. It’s also helpful that they share the same input file format.

Here are some publications that use MoorPy, there’s a theory paper in the works for the code that hasn’t been published yet.

Hi @Ryan.Davies ,

Thank you for the information. I’ve spent some time moving my project into a python version to apply MoorPy, but I’m having some trouble running the MoorPy example from the GitHub, and also have a related question on application. I am currently using Ubuntu via WSL. What I did was:

  1. Cloned MoorPy repository
  2. Executed “pip install moorpy” (“pip install .” in the cloned directory gave an error)
  3. Navigated to examples and executed the imported system example.

The error I recieved looked like this:

ian_ammerman@Dell-Laptop:~/MoorPy/examples$ python3 imported_system.py
attempting to read sample.txt
Traceback (most recent call last):
  File "/home/ian_ammerman/MoorPy/examples/imported_system.py", line 13, in <module>
    ms = mp.System(file='sample.txt')
  File "/home/ian_ammerman/.local/lib/python3.10/site-packages/moorpy/system.py", line 85, in __init__
    self.load(file)
  File "/home/ian_ammerman/.local/lib/python3.10/site-packages/moorpy/system.py", line 429, in load
    for line in f:          # loop through each line in the file
  File "/usr/lib/python3.10/codecs.py", line 322, in decode
    (result, consumed) = self._buffer_decode(data, self.errors, final)
UnicodeDecodeError: 'utf-8' codec can't decode byte 0x88 in position 1458: invalid start byte

I am using python 3.10.12. I assume it’s likely something I am doing wrong - have you seen this sort of error before?

My other question is in regards to the input file and usage. The wiki indicates that MoorPy is expected to use the MoorDyn v2 input file setup. I note from the example there is an extra field “internal damping” in the Lines section not present in the current MoorDyn v2 input file. Should this be added? Additionally, in regards to use, in order to prescribe non-zero position for equilibrium calculation, based on the provided example I need to add a body to the input file so that I can modify the r6 parameter. I don’t want the hydrodynamics of the body taken into account, so the parameters would mostly be zero, but I’m not sure how to add that into the input file. Is it as simple as adding a body line and then changing the “vessel” tags under “POINTS” to “body1”?

Best,
Ian

@Ian.Ammerman I can answer the MoorDyn v2 input file formatting things. Both MoorPy and MoorDyn have the same lines section formatting, the docs just show two different headers for the values. In the MoorPy docs the keyword is cIntDamp, and in the MoorDyn docs it is BA/-zeta (hyperlinks to relevant docs section). Both codes only actually read the values below the headers and units so the two are equivalent values. With regards to the bodies, yep it is that simple! The one caveat is that points attached to a body have their positions described in the body’s reference frame rather than the global frame. i.e. a 10m vertical line from a body at (10, 0, 0) would have the anchor point at (10, 0, -10) and the body attachment point at (0, 0, 0).

With regards to the python error, I am not super sure. Maybe an input file formatting issue? I’ve asked the MoorPy devs if they have any ideas.

Hi Ian,

This MoorPy error has come up more recently for some reason. It seems to be a non-Windows error. We’re not yet sure of the exact source/cause of the error yet.

In the short-term, the error is coming from one of the carets (^) in the sample.txt MoorDyn input file. One caret is not like the others. If you manually update that character, things should run smoothly. For the long-term, we are still looking into why this is happening, but it seems to happen for anyone running non-Windows. (Most of the MoorPy developers use Windows).

Hope this helps.

Stein

@Stein.Housner

Thank you for the info. I changed the character (also tried removing all carets from the sample.txt file) which seemed to fix the issue. I can run the example in the MoorPy repository clone as well as in my development environement.

Best,
Ian

1 Like

@Ryan.Davies

Using a MoorDyn v2 input file for the OC4 semi-sub platform:

--------------------- MoorDyn Input File ------------------------------------
Mooring system for OC4-DeepCwind Semi
FALSE Echo - echo the input file data (flag)
----------------------- LINE TYPES ------------------------------------------
Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx
(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-)
main 0.0766 113.35 7.536E8 -1.0 0 2.0 0.8 0.4 0.25
----------------------- BODIES ------------------------------------------------------
ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca*
(#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-)
1 coupled 0.00 0.00 0 0.00 0.00 0.00 0 0.00 0.00 0 0.00 0.00
---------------------- POINTS --------------------------------
ID Attachment X Y Z M V CdA CA
(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-)
1 Fixed 418.8 725.383 -200.0 0 0 0 0
2 Fixed -837.6 0.0 -200.0 0 0 0 0
3 Fixed 418.8 -725.383 -200.0 0 0 0 0
4 body1 20.434 35.393 -14.0 0 0 0 0
5 body1 -40.868 0.0 -14.0 0 0 0 0
6 body1 20.434 -35.393 -14.0 0 0 0 0
---------------------- LINES --------------------------------------
ID LineType AttachA AttachB UnstrLen NumSegs Outputs
(-) (-) (-) (-) (m) (-) (-)
1 main 1 4 835.35 20 -
2 main 2 5 835.35 20 -
3 main 3 6 835.35 20 -
---------------------- OPTIONS ---------------------------------------
0.001 dtM - time step to use in mooring integration (s)
3.0e6 kbot - bottom stiffness (Pa/m)
3.0e5 cbot - bottom damping (Pa-s/m)
2.0 dtIC - time interval for analyzing convergence during IC gen (s)
60.0 TmaxIC - max time for ic gen (s)
4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-)
0.01 threshIC - threshold for IC convergence (-)
200.0 depth
------------------------ OUTPUTS --------------------------------------------
END
------------------------- need this line --------------------------------------

I initialize the system, then apply a displacement in surge like this:

# Displace body and re-compute
ms.bodyList[0].r6 = np.array([10,0,0,0,0,0])

The resulting plot shows like this:

Why is the displaced position at z = -200? I assume r6 is in the global frame?

@Ian.Ammerman I suspect that when you installed MoorPy via pip you did not build the version you cloned instead you installed the version from PyPi: MoorPy · PyPI (which has not been updated in almost a year).

If pip install ./ gives an error, you can also try running python setup.py install in the MoorPy directory, though pip is the preferred method. I am surprised this gave you an error though, I just tried pip and it worked fine for me (on a Mac)

@Ryan.Davies

That may be true. I edited my response as I was able to successfully install the cloned MoorPy and was able to get it running without error.

In the above edited response, I got around this by using the ms.initialize() command instead of ms.solveEquilibrium() after modifying r6 to avoid including other body forces (since bouyancy, mass, etc are all zero). This seems to work well, yielding the following plot for a simple surge displacement:

Hi Ian,

I’ll post some general MoorPy guidance here:
import moorpy as mp
ms = mp.System(‘your_MD_file.txt’) # load your MoorDyn file into MoorPy
ms.initialize() # “turn on” the mooring system and have all forces for all lines be computed
ms.solveEquilibrium() # solve for the positions of all “free” DOFs so that the net force on the system is nearly zero

In your case, I would run things in the following order:
ms = mp.System(‘your_MD_file.txt’)
ms.initialize()
ms.bodyList[0].setPosition(np.array([10,0,0,0,0,0]))
ms.solveEquilibrium()

Note that I used the “body.setPosition” function to move the body’s position, rather than setting it equal to the array.

If you are still seeing problems, I would check to see if the type of your MoorPy Body is equal to -1 (ms.bodyList[0].type == -1), meaning that it is a “coupled” type, as set in your MoorDyn file, which shouldn’t move when you call solveEquilibrium(), unless you manually set the body’s position each time.

Stein

@Ian.Ammerman if you want to read more about MoorPy theory, the recently published paper can be found here: Energies | Free Full-Text | Generalized Quasi-Static Mooring System Modeling with Analytic Jacobians

@Ryan.Davies

Thank you for the notes - I was able to get it running the way you suggested. I am having an interesting issue with the getForces function though.

Within my main code, I am calling MoorPy within a runge-kutta 4th order routine like this:

# Update mooring system
    self.Platform.ms.bodyList[0].setPosition(np.array([q_sg[0], q_sw[0], q_hv[0], q_r[0], q_p[0], 0]))
    self.Platform.ms.solveEquilibrium()

    # Compute mooring loads
    mooring_load = self.Platform.ms.bodyList[0].getForces()
    print("Position: ", self.Platform.ms.bodyList[0].r6, "Mooring Load: ", mooring_load)

What I’m seeing is that the mooring_load output is returning as zero until the platform has displaced significantly. Below are the returns from the print statement showing position (r6) and corresponding load from getForces:

Position:  [ 8.56763412e-01 -5.04642998e-02  0.00000000e+00  1.06296735e-04  1.00123025e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 2.21827300e+00 -2.02177641e-01  0.00000000e+00  1.08787577e-04  1.26123204e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 2.43145893e+00 -2.03782568e-01  0.00000000e+00  1.09011389e-04  1.22166359e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 4.64140243e+00 -4.32402340e-01  0.00000000e+00  1.11243873e-04  1.49824100e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.46294733e+00 -2.00154852e-01  0.00000000e+00  1.09744956e-04  1.37032994e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.72410898e+00 -2.09982669e-01  0.00000000e+00  1.11067732e-04  1.13288507e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.25634246e+00 -2.05472722e-01  0.00000000e+00  1.11305893e-04  1.29237972e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-1.62554666e+00  1.70900691e-02  0.00000000e+00  1.11985476e-04  9.83955760e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-2.38720414e+00  1.52941526e-01  0.00000000e+00  1.12352917e-04  9.41281329e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-5.00396720e+00  4.93570709e-01  0.00000000e+00  1.15828661e-04  5.18279039e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-5.58558792e+00  4.99961912e-01  0.00000000e+00  1.15258743e-04  5.64209470e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-9.25394267e+00  9.76220352e-01  0.00000000e+00  1.19565245e-04  1.27100193e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-1.45811819e+00  4.08603189e-01  0.00000000e+00  1.23044868e-04  4.32051112e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-3.66634564e+00  3.72121974e-01  0.00000000e+00  1.28908799e-04  1.23547099e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-4.42175705e-01  3.53438370e-01  0.00000000e+00  1.28518112e-04  7.82145582e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 5.16764778e+00 -2.46957758e-01  0.00000000e+00  1.35851831e-04  1.67922726e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 4.58637171e+00 -4.43075628e-01  0.00000000e+00  1.34438825e-04  1.64270699e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.08876681e+01 -1.18113961e+00  0.00000000e+00  1.35222161e-04  2.40339260e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 9.99647585e+00 -1.20385488e+00  0.00000000e+00  1.36634698e-04  2.46369766e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.52650610e+01 -2.14195953e+00  0.00000000e+00  1.35449604e-04  3.21241507e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-2.76132146e+00 -7.63182621e-01  0.00000000e+00  1.28089320e-04  2.60901875e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 2.37023539e+01 -5.58805075e-01  0.00000000e+00  1.25492009e-04  6.13682189e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-3.76210729e+00 -4.73438512e-01  0.00000000e+00  1.25871872e-04  2.14296604e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 1.94071559e+01  1.07233101e+00  0.00000000e+00  1.20433700e-04  2.76967526e-04  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [-3.91273613e+01  1.14859187e+00  0.00000000e+00  1.25506713e-04  1.13865546e-03  0.00000000e+00] Mooring Load:  [0. 0. 0. 0. 0. 0.]
Position:  [ 2.92182672e+02  2.72018475e+00  0.00000000e+00  1.34815056e-04 -6.97897348e-03  0.00000000e+00] Mooring Load:  [-2.28841424e+08 -5.72006631e+05  0.00000000e+00 -8.17104225e+06  3.268970

Taking these position values and using them as the example vector from the simple script used earlier yields non-zero values correctly. For example, using the second print statement line yields the following forces:

# Displace body and re-compute
ms.bodyList[0].setPosition(np.array([2.218,-0.2,0,0,0,0]))
print(ms.bodyList[0].r6)

ms.solveEquilibrium()  # equilibrate (specify 'both' to enable both free and coupled DOFs)
load = ms.bodyList[0].getForces()
print(f"Body offset position is {ms.bodyList[0].r6}")
print(f"Mooring Loads: {load}")

Body offset position is [ 2.218 -0.2    0.     0.     0.     0.   ]
Mooring Loads: [-1.63170979e+05  1.32403960e+04 -1.89647182e+06  1.66510091e+04 2.71485216e+05 -1.69608750e+02]

My initial though is how I am storing and accessing the system. I read in the input file and initilize the system first:

# Build mooring system
ms = mp.System(file=mooring_file)
ms.initialize()  # make sure everything's connected
ms.solveEquilibrium() # equilibrate

I then ascribe it to the platform object:

def buildPlatform(ElastoDyn_file, HST_file, Wam1_file, radiation_ss_file, Platform, mooring_system):

     # Do some other stuff here ...

     # Assign mooring system
     Platform.ms = mooring_system

by passing ms into the buildPlatform function. This is why I am calling it as self.Platform.ms (Platform is in turn an attribute of a “Turbine” class. Is it possible that the way I’m storing and accessing the mooring system is causing this sort of error? In terms of why it suddenly starts giving out values, there’s no change or significant event I can think of at that iteration that might cause it to start computing values. Do you have any thoughts?

Best,
Ian

Hi Ian,

If you haven’t solved this issue yet, I’m hoping that it’s only a matter of the inputs to the getForces() function.

Try running “getForces(DOFtype=‘both’, lines_only=True)”

These inputs make sure all mooring line objects are being accounted for in the force calculation and that we’re only considering the force of the mooring lines on the platform (as opposed to adding any mass/buoyancy forces from the platform)

Stein