FloatingArrayDesign / MoorDyn

a lumped-mass mooring line model intended for coupling with floating structure codes
BSD 3-Clause "New" or "Revised" License
64 stars 37 forks source link

MoorDyn2 and Matlab #200

Closed MikeFengK closed 3 months ago

MikeFengK commented 3 months ago

Hello!

I established the model of OC4-5MW semi-submersible wind turbine in Matlab, and the wind turbine platform was connected with three mooring lines. It is hoped that the tension of the three mooring lines on the three connection points of the platform can be obtained through MoorDynV2. Or obtain the resultant force of the three lines at the center of gravity of the platform and the resultant moment at the center of gravity of the platform, please note that it is not the moment at the intersection point of the horizontal plane and the tower (the origin of the reference frame).

However, I have encountered a problem that cannot be solved. I will explain my research process and hope to get your help. Thank you.

1 Download and install: Open “ moordyn-2.2.2-win64.exe” , get “moordyn-2.2” , find “moordyn.dll” in “moordyn-2.2 \bin”, and find ”MoorDyn2.h“ in “moordyn-2.2 \include\moordyn”.

2Code: I will first try the stationary state of the platform. The resultant force generated by the three mooring lines should be [0;0;1839000] in the xyz direction, and the resultant torque should be [0;0;0].

I used the following code in matlab.


mooring_load_ptr = zeros(1,6);
mooring_load_ptr = libpointer('doublePtr',mooring_load_ptr);

[notfound,warnings] = loadlibrary('moordyn.dll','MoorDyn2.h'); system = calllib('moordyn','MoorDyn_Create','lines.txt');

x = zeros(6,1); dx= zeros(6,1);

calllib('moordyn','MoorDyn_Init',system, x, dx);

t = 0.0; dt = 0.001; calllib('moordyn', 'MoorDyn_Step', system, x, dx, mooring_load_ptr, t, dt); mooring_load = mooring_load_ptr.value;


lines.txt contains the following --------------------- MoorDyn Input File ------------------------------------ Mooring system for OC4-DeepCwind Semi ----------------------- 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 ---------------------- 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 Vessel 20.434 35.393 -14.0 0 0 0 0 5 Vessel -40.868 0.0 -14.0 0 0 0 0 6 Vessel 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 - ---------------------- SOLVER OPTIONS --------------------------------------- 0 writeLog - 0.001 dtM - time step to use in mooring integration (s) RK2 tScheme
9.81 g - The gravity acceleration (m/s^2) 1025 rho - The water density (kg/m^3) 200 WtrDpth - The water depth (m) 1.0 dtIC - time interval for analyzing convergence during IC gen (s) 120.0 TmaxIC - max time for ic gen (s) 5.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) 0.001 threshIC - threshold for IC convergence (-) 0 WaveKin - 0.25 dtWave - The time step to evaluate the waves, only for wave grid (WaveKin = 3) (s) 0 Currents - The currents model to use ------------------------- need this line --------------------------------------

When I run it once mooring_load=[1.13e+07,1.96e+07,-5.86e+06,-2.26e+07,0,-5.86e+06], What went wrong, please

RyanDavies19 commented 3 months ago

Hi @MikeFengK, the reason you are seeing issues is because you have three points listed as vessel, which is equivalent to having three coupled points. This means that you would need to provide MoorDyn a state vector and derivative of size 9 (3 coupled points x 3 dof per point). Additionally your input file defines the points at non-zero positions, but the state vector you provide tells MoorDyn the points are at 0,0,0. If you change to a size 9 vector with positions of the line attachments you should get the results you are looking for in terms of the forces at each fairlead. Your x vector in that case would look something like: [p4x, p4y, p4z, p5x, p5y, p5z, p6x, p6y, p6z] with dx in the same order.

If you wanted to get a 6 DOF response on your model, you should use a coupled body object and attach your fairleads to the body: Bodies. In this case, MoorDyn will take the 6 dof location of the coupled body as input and return the forces and moments at the bodies location.

I'll also note that MoorDyn has a Matlab wrapper if you compile the code from the source. Your method will work fine as well, but if you want you can read more about it here: https://moordyn.readthedocs.io/en/latest/drivers.html#matlab

MikeFengK commented 3 months ago

Thank you very much for your help! All three methods you provided were very helpful to me. I still have some questions, I hope you can explain it again, thank you!

According to the first paragraph of your reply, I changed the code.


mooring_load_ptr = zeros(9,1);
mooring_load_ptr = libpointer('doublePtr',mooring_load_ptr);

[notfound,warnings] = loadlibrary('moordyn.dll','MoorDyn2.h'); system = calllib('moordyn','MoorDyn_Create','lines.txt');

x = [20.434;35.393;-14.0;-40.868;0;-14.0;20.434;-35.393;-14.0]; dx= zeros(9,1);

calllib('moordyn','MoorDyn_Init',system, x, dx);

t = 0.0; dt = 0.001; calllib('moordyn', 'MoorDyn_Step', system, x, dx, mooring_load_ptr, t, dt); mooring_load = mooring_load_ptr.value;


matlab will have a warning, can you help me to see what is wrong.


Running MoorDyn (v2.0.0, 2023-09-18) MoorDyn v2 has significant ongoing input file changes from v1. Copyright: (C) 2023 National Renewable Energy Laboratory, (C) 2014-2019 Matt Hall This program is released under the BSD 3-Clause license. The filename is lines.txt Generated entities: nLineTypes = 1 nRodTypes = 0 nPoints = 6 nBodies = 0 nRods = 0 nLines = 3 nFails = 0 nFreeBodies = 0 nFreeRods = 0 nFreePoints = 0 nCpldBodies = 0 nCpldRods = 0 nCpldPoints = 3 Time integrator = 2nd order Runge-Kutta No Waves or Currents, or set externally Creating mooring system... Initializing coupled Point 4 at 20.434, 35.393, -14... Initializing coupled Point 5 at -40.868, 0, -14... Initializing coupled Point 6 at 20.434, -35.393, -14...


I need to add: When I first ran the program, line 77 in the Waves.h file MoorDynSeafloor = 0 was an error. I don't know how to modify it, just change MoorDynSeafloor = 0 to MoorDynSeafloor. Does that have anything to do with it

RyanDavies19 commented 3 months ago

Thank you very much for your help! All three methods you provided were very helpful to me. I still have some questions, I hope you can explain it again, thank you!

1 According to the first paragraph of your reply, I changed the code.

mooring_load_ptr = zeros(9,1); mooring_load_ptr = libpointer('doublePtr',mooring_load_ptr);

[notfound,warnings] = loadlibrary('moordyn.dll','MoorDyn2.h'); system = calllib('moordyn','MoorDyn_Create','lines.txt');

x = [20.434;35.393;-14.0;-40.868;0;-14.0;20.434;-35.393;-14.0]; dx= zeros(9,1);

calllib('moordyn','MoorDyn_Init',system, x, dx);

t = 0.0; dt = 0.001; calllib('moordyn', 'MoorDyn_Step', system, x, dx, mooring_load_ptr, t, dt); mooring_load = mooring_load_ptr.value;

Here mooring_load becomes an array of [9,1]. Is it the force at each fairlead [[F4x, F4y, F4z, F5x, F5y, F5z, F6x, F6y, F6z]]? If not, which function in MoorDyn2.h can get these forces.

matlab will have a warning, can you help me to see what is wrong. I dont know why rho : 24596.5 , it should be 1025 .

Running MoorDyn (v2.0.0, 2023-09-18) MoorDyn v2 has significant ongoing input file changes from v1. Copyright: (C) 2023 National Renewable Energy Laboratory, (C) 2014-2019 Matt Hall This program is released under the BSD 3-Clause license. The filename is lines.txt Generated entities: nLineTypes = 1 nRodTypes = 0 nPoints = 6 nBodies = 0 nRods = 0 nLines = 3 nFails = 0 nFreeBodies = 0 nFreeRods = 0 nFreePoints = 0 nCpldBodies = 0 nCpldRods = 0 nCpldPoints = 3 Time integrator = 2nd order Runge-Kutta No Waves or Currents, or set externally Creating mooring system... Initializing coupled Point 4 at 20.434, 35.393, -14... Initializing coupled Point 5 at -40.868, 0, -14... Initializing coupled Point 6 at 20.434, -35.393, -14...

  • Line1: ID: 1 UnstrLen: 835.35 N : 20 d : 0.0766 rho : 24596.5 E : 1.63529e+11 EI : 0 BAin: -1 Can : 0.8 Cat : 0.25 Cdn : 2 Cdt : 0.4 ww_l: 1065.63 Line 1 damping set to 2.64894e+09 Ns = 1.22073e+07 Pa-s, based on input of -1 WRN D:\a\MoorDyn\MoorDyn\source\Line.cpp:504 moordyn::Line::initialize(): Catenary initial profile failed for Line 1, initalizing as linear Initialized Line 1
  • Line2: ID: 2 UnstrLen: 835.35 N : 20 d : 0.0766 rho : 24596.5 E : 1.63529e+11 EI : 0 BAin: -1 Can : 0.8 Cat : 0.25 Cdn : 2 Cdt : 0.4 ww_l: 1065.63 Line 2 damping set to 2.64894e+09 Ns = 1.22073e+07 Pa-s, based on input of -1 WRN D:\a\MoorDyn\MoorDyn\source\Line.cpp:504 moordyn::Line::initialize(): Catenary initial profile failed for Line 2, initalizing as linear Initialized Line 2
  • Line3: ID: 3 UnstrLen: 835.35 N : 20 d : 0.0766 rho : 24596.5 E : 1.63529e+11 EI : 0 BAin: -1 Can : 0.8 Cat : 0.25 Cdn : 2 Cdt : 0.4 ww_l: 1065.63 Line 3 damping set to 2.64894e+09 Ns = 1.22073e+07 Pa-s, based on input of -1 WRN D:\a\MoorDyn\MoorDyn\source\Line.cpp:504 moordyn::Line::initialize(): Catenary initial profile failed for Line 3, initalizing as linear Initialized Line 3 Finalizing ICs using dynamic relaxation (5X normal drag) Fairlead tensions converged Remaining error after 68 s = 0.0933394% on line 1 No Waves or Currents, or set externally

calllib('moordyn', 'MoorDyn_Step', system, x, dx, mooring_load_ptr, t, dt); Does setting t to a constant 0 here affect the result?

Hi @MikeFengK, the forces returned by MoorDyn are the fairlead forces in X,Y,Z. I think of it generally as the force that the system exerts on the coupled point in the corresponding direction (in the case of 6 DOF couplings, it returns forces and moments). The rho value you are seeing for the lines is the density of the lines, the linear density divided by the cross sectional area. And the error you are seeing should not effect your simulation. It is saying that the initial line shape is a straight line. However during the dynamic relaxation period (120 sec max in your case) MoorDyn will find the natural line shape. All that warning effects is how long dynamic relaxation takes. Lastly setting t = 0 I think would work, expect that all output files would not be handled well. Just to be safe I would suggest providing t each time you call the step function (t = t + dt in a loop).

RyanDavies19 commented 3 months ago

2 Your first paragraph refers to the fact that MoorDynV2 can calculate the tension of three mooring lines at the fairlead? Your second paragraph refers to the fact that MoorDynV2 can also calculate forces on the platform model which is built in MoorDynV2 ? However, I have built the platform model in Matlab, which can generate the change of position and speed in real time. I only need the tension generated by the three mooring lines at the fairlead. In this case, is it OK to use the method described in the first paragraph?

Yep your method is totally fine, it just means that you are relying on your scripts and codes to translate those fairlead forces into moments on your structure.

MikeFengK commented 3 months ago

Thank you very much for your help in answering my questions!Looking forward to your MoorDyn2.3.0。