From 1b45ade0439f3e663cbc31d8cfbbb2b07c622e3a Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 27 Feb 2026 07:57:00 +0100 Subject: [PATCH 01/16] Started version 2.6.2 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7364d410..a252cd83 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10) set(MOORDYN_MAJOR_VERSION 2) set(MOORDYN_MINOR_VERSION 6) -set(MOORDYN_PATCH_VERSION 1) +set(MOORDYN_PATCH_VERSION 2) set(MOORDYN_VERSION ${MOORDYN_MAJOR_VERSION}.${MOORDYN_MINOR_VERSION}) project(Moordyn VERSION ${MOORDYN_VERSION}) From 15ff998106b87ea6e708a92df6958b3f769f4dc8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 2 Mar 2026 03:53:32 +0000 Subject: [PATCH 02/16] build(deps): bump actions/upload-artifact from 6 to 7 Bumps [actions/upload-artifact](https://github.com/actions/upload-artifact) from 6 to 7. - [Release notes](https://github.com/actions/upload-artifact/releases) - [Commits](https://github.com/actions/upload-artifact/compare/v6...v7) --- updated-dependencies: - dependency-name: actions/upload-artifact dependency-version: '7' dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-emulated.yml | 2 +- .github/workflows/python-wheels.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/python-wheels-emulated.yml b/.github/workflows/python-wheels-emulated.yml index 348d710c..7f76c64f 100644 --- a/.github/workflows/python-wheels-emulated.yml +++ b/.github/workflows/python-wheels-emulated.yml @@ -79,7 +79,7 @@ jobs: with: output-dir: dist - - uses: actions/upload-artifact@v6 + - uses: actions/upload-artifact@v7 id: build_wheels with: name: python-wheels-${{runner.os}}_${{inputs.arch}} diff --git a/.github/workflows/python-wheels.yml b/.github/workflows/python-wheels.yml index 28aa98c3..7a945ad1 100644 --- a/.github/workflows/python-wheels.yml +++ b/.github/workflows/python-wheels.yml @@ -36,7 +36,7 @@ jobs: python -m pip install -U pip setuptools python setup.py sdist - - uses: actions/upload-artifact@v6 + - uses: actions/upload-artifact@v7 id: build_wheels with: name: python-wheels-sdist From 7fdcedbfd9653fe66eee94c7108501ae3ca1dc62 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 2 Mar 2026 03:53:36 +0000 Subject: [PATCH 03/16] build(deps): bump actions/download-artifact from 7 to 8 Bumps [actions/download-artifact](https://github.com/actions/download-artifact) from 7 to 8. - [Release notes](https://github.com/actions/download-artifact/releases) - [Commits](https://github.com/actions/download-artifact/compare/v7...v8) --- updated-dependencies: - dependency-name: actions/download-artifact dependency-version: '8' dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-test.yml | 2 +- .github/workflows/python-wheels.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/python-wheels-test.yml b/.github/workflows/python-wheels-test.yml index bc00ff82..f693dc6d 100644 --- a/.github/workflows/python-wheels-test.yml +++ b/.github/workflows/python-wheels-test.yml @@ -31,7 +31,7 @@ jobs: python-version: '3.12' - name: Download the wheels - uses: actions/download-artifact@v7 + uses: actions/download-artifact@v8 with: path: dist/ pattern: python-wheels-${{runner.os}}_${{inputs.arch}}* diff --git a/.github/workflows/python-wheels.yml b/.github/workflows/python-wheels.yml index 28aa98c3..3112fb7c 100644 --- a/.github/workflows/python-wheels.yml +++ b/.github/workflows/python-wheels.yml @@ -136,7 +136,7 @@ jobs: - uses: actions/checkout@v6 - name: Download artifacts - uses: actions/download-artifact@v7 + uses: actions/download-artifact@v8 with: path: dist/ pattern: python-wheels-* From 2cc05f17bfecda3cdc2078a406f693e66e41d077 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 9 Mar 2026 03:53:40 +0000 Subject: [PATCH 04/16] build(deps): bump docker/setup-qemu-action from 3 to 4 Bumps [docker/setup-qemu-action](https://github.com/docker/setup-qemu-action) from 3 to 4. - [Release notes](https://github.com/docker/setup-qemu-action/releases) - [Commits](https://github.com/docker/setup-qemu-action/compare/v3...v4) --- updated-dependencies: - dependency-name: docker/setup-qemu-action dependency-version: '4' dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-emulated.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-wheels-emulated.yml b/.github/workflows/python-wheels-emulated.yml index 348d710c..e92f4424 100644 --- a/.github/workflows/python-wheels-emulated.yml +++ b/.github/workflows/python-wheels-emulated.yml @@ -69,7 +69,7 @@ jobs: mkdir -p ${{github.workspace}}/install - name: Set up QEMU - uses: docker/setup-qemu-action@v3 + uses: docker/setup-qemu-action@v4 with: platforms: all if: runner.os == 'Linux' From 41bebbed3e9c1595557e6c8c180fa0115ed6f83f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 9 Mar 2026 03:53:44 +0000 Subject: [PATCH 05/16] build(deps): bump pypa/cibuildwheel from 3.3.1 to 3.4.0 Bumps [pypa/cibuildwheel](https://github.com/pypa/cibuildwheel) from 3.3.1 to 3.4.0. - [Release notes](https://github.com/pypa/cibuildwheel/releases) - [Changelog](https://github.com/pypa/cibuildwheel/blob/main/docs/changelog.md) - [Commits](https://github.com/pypa/cibuildwheel/compare/v3.3.1...v3.4.0) --- updated-dependencies: - dependency-name: pypa/cibuildwheel dependency-version: 3.4.0 dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-emulated.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-wheels-emulated.yml b/.github/workflows/python-wheels-emulated.yml index 348d710c..95a6628e 100644 --- a/.github/workflows/python-wheels-emulated.yml +++ b/.github/workflows/python-wheels-emulated.yml @@ -75,7 +75,7 @@ jobs: if: runner.os == 'Linux' - name: Build wheels - uses: pypa/cibuildwheel@v3.3.1 + uses: pypa/cibuildwheel@v3.4.0 with: output-dir: dist From d1f449615e447be4986c83ec15ec4f3ede86a684 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 24 Mar 2026 09:03:13 +0100 Subject: [PATCH 06/16] fix(core): Memory leak on lean-vtk --- source/leanvtk/leanvtk.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/source/leanvtk/leanvtk.hpp b/source/leanvtk/leanvtk.hpp index 8a17d5e0..012b044f 100644 --- a/source/leanvtk/leanvtk.hpp +++ b/source/leanvtk/leanvtk.hpp @@ -141,6 +141,8 @@ class VTKDataNodeBase { , binary_(false) {} + virtual ~VTKDataNodeBase() = default; + virtual void write(std::ostream &os) const { }; From 26bad3b33d5eb6b7161d8151562c40def989b1ba Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 24 Mar 2026 17:07:41 +0100 Subject: [PATCH 07/16] fix(core): Segmentation Fault when trying to print Td output --- source/Line.cpp | 60 ++++++++++++++++++++++++++----------------------- 1 file changed, 32 insertions(+), 28 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index f14b743c..228a37c4 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1567,33 +1567,37 @@ Line::Output(real time) // Flags changed to just be one character (case sensitive) per output flag. // To match FASTv8 version. -// Helper to format and write a single value -auto write_val = [&](real val) { - *outfile << std::setw(WIDTH) - << std::right - << std::scientific - << std::setprecision(PRECISION) - << val; - }; - if (outfile) // if not a null pointer (indicating no output) { if (!outfile->is_open()) { LOGWRN << "Unable to write to output file " << endl; return; } - // Loops through the nodes - auto write_vec_array = [&](const std::vector& arr) { - for (unsigned int i = 0; i <= N; i++) - for (unsigned int J = 0; J < 3; J++){ - write_val(arr[i][J]);} - - }; - // Loops through the nodes for scalars - auto write_scalar_array = [&](const std::vector& arr) { - for (unsigned int i = 0; i <= N; i++) - write_val(arr[i]); - }; + + // Helper to format and write values + auto write_val = [&](real val) { + *outfile << std::setw(WIDTH) + << std::right + << std::scientific + << std::setprecision(PRECISION) + << val; + }; + auto write_vec_array = [&](const std::vector& arr, + const unsigned int n) + { + for (unsigned int i = 0; i < n; i++) { + for (unsigned int J = 0; J < 3; J++) { + write_val(arr[i][J]); + } + } + }; + auto write_scalar_array = [&](const std::vector& arr, + const unsigned int n) + { + for (unsigned int i = 0; i < n; i++) { + write_val(arr[i]); + } + }; // output time *outfile << setw(10) << right << fixed << setprecision(4) << time; @@ -1602,21 +1606,21 @@ auto write_val = [&](real val) { // if (find(channels.begin(), channels.end(), "position") != // channels.end()) if (channels.find("p") != string::npos) { - write_vec_array(r); // position + write_vec_array(r, N + 1); } // output curvatures? if (channels.find("K") != string::npos) { - write_scalar_array(Kurv); + write_scalar_array(Kurv, N + 1); } // output velocities? if (channels.find("v") != string::npos) { - write_vec_array(rd); + write_vec_array(rd, N + 1); } // output wave velocities? if (channels.find("U") != string::npos) { auto [_z, U, _ud, _pdyn] = waves->getWaveKinLine(lineId); - write_vec_array(U); + write_vec_array(U, N + 1); } // output hydro drag force? if (channels.find("D") != string::npos) { @@ -1628,7 +1632,7 @@ auto write_val = [&](real val) { // output VIV force (only CF for now) if (channels.find("V") != string::npos) { - write_vec_array(Lf); + write_vec_array(Lf, N + 1); } // output segment tensions? if (channels.find("t") != string::npos) { @@ -1647,7 +1651,7 @@ auto write_val = [&](real val) { } // output internal damping force? if (channels.find("c") != string::npos) { - write_vec_array(Td); // internal damping force + write_vec_array(Td, N); // internal damping force } // output segment strains? if (channels.find("s") != string::npos) { @@ -1663,7 +1667,7 @@ auto write_val = [&](real val) { } // output seabed contact forces? if (channels.find("b") != string::npos) { - write_vec_array(B); + write_vec_array(B, N + 1); } *outfile << "\n"; From f9e4f31acb323b84bf60880fbc9c3f8146cf1076 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 6 Apr 2026 03:53:36 +0000 Subject: [PATCH 08/16] build(deps): bump pypa/cibuildwheel from 3.4.0 to 3.4.1 Bumps [pypa/cibuildwheel](https://github.com/pypa/cibuildwheel) from 3.4.0 to 3.4.1. - [Release notes](https://github.com/pypa/cibuildwheel/releases) - [Changelog](https://github.com/pypa/cibuildwheel/blob/main/docs/changelog.md) - [Commits](https://github.com/pypa/cibuildwheel/compare/v3.4.0...v3.4.1) --- updated-dependencies: - dependency-name: pypa/cibuildwheel dependency-version: 3.4.1 dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-emulated.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-wheels-emulated.yml b/.github/workflows/python-wheels-emulated.yml index ba5866d5..3b168859 100644 --- a/.github/workflows/python-wheels-emulated.yml +++ b/.github/workflows/python-wheels-emulated.yml @@ -75,7 +75,7 @@ jobs: if: runner.os == 'Linux' - name: Build wheels - uses: pypa/cibuildwheel@v3.4.0 + uses: pypa/cibuildwheel@v3.4.1 with: output-dir: dist From 9c9d9fc4e74b435db79af0a1ada37bbe56a7d207 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 6 Apr 2026 03:53:41 +0000 Subject: [PATCH 09/16] build(deps): bump matlab-actions/run-command from 2 to 3 Bumps [matlab-actions/run-command](https://github.com/matlab-actions/run-command) from 2 to 3. - [Release notes](https://github.com/matlab-actions/run-command/releases) - [Commits](https://github.com/matlab-actions/run-command/compare/v2...v3) --- updated-dependencies: - dependency-name: matlab-actions/run-command dependency-version: '3' dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/matlab.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/matlab.yml b/.github/workflows/matlab.yml index 4691ea6d..e680edd4 100644 --- a/.github/workflows/matlab.yml +++ b/.github/workflows/matlab.yml @@ -45,7 +45,7 @@ jobs: uses: matlab-actions/setup-matlab@v2 - name: Compile and run - uses: matlab-actions/run-command@v2 + uses: matlab-actions/run-command@v3 with: command: | mex('-setup', '-v', 'C'); From 3521d7fe680cad877639f28c9461e44831379b58 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 6 Apr 2026 03:53:44 +0000 Subject: [PATCH 10/16] build(deps): bump matlab-actions/setup-matlab from 2 to 3 Bumps [matlab-actions/setup-matlab](https://github.com/matlab-actions/setup-matlab) from 2 to 3. - [Release notes](https://github.com/matlab-actions/setup-matlab/releases) - [Commits](https://github.com/matlab-actions/setup-matlab/compare/v2...v3) --- updated-dependencies: - dependency-name: matlab-actions/setup-matlab dependency-version: '3' dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/matlab.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/matlab.yml b/.github/workflows/matlab.yml index e680edd4..4c9447a6 100644 --- a/.github/workflows/matlab.yml +++ b/.github/workflows/matlab.yml @@ -42,7 +42,7 @@ jobs: run: cmake --install ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} - name: Set up MATLAB - uses: matlab-actions/setup-matlab@v2 + uses: matlab-actions/setup-matlab@v3 - name: Compile and run uses: matlab-actions/run-command@v3 From 094ecffc1f60b2458f6a4bf87d5044ed44ab1bba Mon Sep 17 00:00:00 2001 From: Zhilong Wei <110678381+zhilongwei@users.noreply.github.com> Date: Sun, 26 Apr 2026 08:43:22 +0200 Subject: [PATCH 11/16] feat(core): Implementation of the Syrope model for polyester ropes * Syrope model implementation * Optimization of the exponential working curve formula * Fixed wrong initial mean tension and wrong working when Tmean < Tmax * Documentation for Syrope extension * Test for Syrope model with slow loading * Three working curve formulas in one test * Formatting * Renamed the input file for the Syrope test * Syrope test passed * Added a reference for the Syrope model * Removed bold texts in Syrope input description * Keep the Syrope reference in Chicago style as the others * Use (std::max) and (std::min) instead of std::max and std::min for Windows sake * #define _USE_MATH_DEFINES before including cmath * Disabled quadratic and exponential wc formulas, increased time step size and reduced IC duration * formatted test syrope.cpp * Put the references in chronological order * Moved the nonlinear stiffness inputs to the Additional MoorDyn Files * Read syrope working curve settings from a separate file * Read initial Tmax and Tmean for Syrope lines in the LINES section * Updated the test input files * Updated the docs for Syrope model * read Tmax and Tmean from a separate section instead from LINES section * Throw a warning if a SYROPE IC is present but Syrope is not used * Read Tmax and Tmean for Syrope lines from a separate section instead from LINES section * Updated the input files for test syrope * Updated documentation for Syrope IC inputs * Excluded the syrope test from memcheck * Removed Tmax0 and Tmean0 from LINES section --- .github/workflows/memcheck.yml | 2 +- docs/inputs.rst | 100 ++- docs/references.rst | 14 +- source/Line.cpp | 130 +++- source/Line.hpp | 60 ++ source/Misc.hpp | 4 + source/MoorDyn2.cpp | 281 +++++++- source/MoorDyn2.hpp | 44 ++ tests/CMakeLists.txt | 1 + tests/Mooring/syrope/exp_wc/line.txt | 31 + tests/Mooring/syrope/exp_wc/syrope.dat | 4 + tests/Mooring/syrope/linear_wc/line.txt | 31 + tests/Mooring/syrope/linear_wc/syrope.dat | 4 + tests/Mooring/syrope/owc.dat | 32 + tests/Mooring/syrope/quadratic_wc/line.txt | 31 + tests/Mooring/syrope/quadratic_wc/syrope.dat | 4 + tests/syrope.cpp | 639 +++++++++++++++++++ 17 files changed, 1366 insertions(+), 46 deletions(-) create mode 100644 tests/Mooring/syrope/exp_wc/line.txt create mode 100644 tests/Mooring/syrope/exp_wc/syrope.dat create mode 100644 tests/Mooring/syrope/linear_wc/line.txt create mode 100644 tests/Mooring/syrope/linear_wc/syrope.dat create mode 100644 tests/Mooring/syrope/owc.dat create mode 100644 tests/Mooring/syrope/quadratic_wc/line.txt create mode 100644 tests/Mooring/syrope/quadratic_wc/syrope.dat create mode 100644 tests/syrope.cpp diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 92456bfb..99999289 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -36,4 +36,4 @@ jobs: - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux - run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} -E "(seafloor|time_schemes|wavekin|wilson|lowe_and_langley_2006)" + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} -E "(seafloor|time_schemes|wavekin|wilson|lowe_and_langley_2006|syrope)" diff --git a/docs/inputs.rst b/docs/inputs.rst index 4ac84b86..6d27bc8a 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -266,6 +266,7 @@ There is not a limit on the number of lines you can write here. --------------------- MoorDyn Input File ------------------------------------ MoorDyn v2 sample input file +.. _line-types-v2: Line Types ^^^^^^^^^^ @@ -285,7 +286,7 @@ The columns in order are as follows: - Diam – the volume-equivalent diameter of the line – the diameter of a cylinder having the same displacement per unit length (m) - MassDen – the mass per unit length of the line (kg/m) - - EA – the line stiffness, product of elasticity modulus and cross-sectional area (N) + - EA – the line stiffness, product of elasticity modulus and cross-sectional area (N), or nonlinear parameters (see descriptions below) - BA/-zeta – the line internal damping (measured in N-s) or, if a negative value is entered, the desired damping ratio (in fraction of critical) for the line type (and MoorDyn will set the BA of each line accordingly) @@ -306,24 +307,13 @@ The columns in order are as follows: - cF - OPTIONAL - the center of the range of non-dimensional frequencies for the CF VIV synchronization model. If it is not provided and VIV is enabled (Cl > 0) then it is default to 0.18 to align with the the theory found :ref:`here ` -Note: Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file -must be located in the same folder as the main MoorDyn input file for MoorDyn-C or for MoorDyn-F -in the same folder as the executable calling MoorDyn-F, unless a path is specified. Such file is a -tabulated file with 3 header lines and then a strain column and a tension column separated by a blank space: - -.. code-block:: none - - ----Polyester---- - Strain Tension - (-) (N) - 0.0 0.0 - ... ... - Note: MoorDyn has the ability to model the viscoelastic properties of synthetic lines in two ways. The first method, from work linked in the :ref:`theory section `, allows a user to specify a bar-separated constant dynamic and static stiffness. The second method allows the user to provide a constant static stiffness and two terms to determine the dynamic stiffness as a linear function of mean load. The equation is: -`EA_d = EA_Dc + EA_D_Lm * mean_load` where `EA_D_Lm` is the slope of the load-stiffness curve. Both of these methods allow users to provide static -and dynamic damping coefficients as values separated by |. While the static damping can be described as a fraction of critical, the dynamic damping +`EA_d = EA_Dc + EA_D_Lm * mean_load` where `EA_D_Lm` is the slope of the load-stiffness curve. This method can be used standalone, +and is also part of the Syrope model described in :ref:`Syrope Model for Polyester Lines `. +Both of these methods allow users to provide static and dynamic damping coefficients as values separated by |. +While the static damping can be described as a fraction of critical, the dynamic damping needs to be input as a value. Example inputs are below: .. code-block:: none @@ -497,9 +487,9 @@ The columns are as follows: - UnstrLen - the unstretched length of the line - NumSegs - how many segments the line is discretized into (it will have NumSegs+1 nodes total, including its two end nodes) - - LineOutputs - any data to be output in a dedicated output file for that line. + - LineOutputs - any data to be output in a dedicated output file for that line. -This last entry expects a string of one or more characters without spaces, each character +This `LineOutputs` entry expects a string of one or more characters without spaces, each character activating a given output property. A placeholder character such as “-” should be used if no outputs are wanted. Ten output properties are currently possible: @@ -1008,6 +998,80 @@ data. 5000 0.15 0.0 --------------------- need this line ------------------ +Nonlinear Stiffness (EA) Inputs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file +must be located in the same folder as the main MoorDyn input file for MoorDyn-C or for MoorDyn-F +in the same folder as the executable calling MoorDyn-F, unless a path is specified. Such file is a +tabulated file with 3 header lines and then a strain column and a tension column separated by a blank space: + +.. code-block:: none + + ----Polyester---- + Strain Tension + (-) (N) + 0.0 0.0 + ... ... + +.. _syrope-model-polyester-lines: +Syrope Model for Polyester Lines +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +MoorDyn supports the Syrope material model for polyester ropes. In this formulation, the +tension–strain response is nonlinear and load-path dependent, meaning the unloading and +reloading curves differ. See additional details in the :ref:`theory section ` +and the references therein. + +To enable the Syrope model for a given line type, specify the EA field using three +bar-separated entries, analogous to the load-dependent dynamic stiffness method described in :ref:`Line Types `. +To indicate Syrope, the first entry must start with ``SYROPE:``, followed by the name (or path) +of a Syrope config file defining the working curves. The second and third entries are +``EA_Dc`` and ``EA_D_Lm`` (as in the load-dependent dynamic stiffness method in :ref:`Line Types `). Static and dynamic +damping may be provided in BA as ``BA_s|BA_d`` (same convention as above). + +Example: + +.. code-block:: none + + TypeName Diam Mass/m EA BA + (name) (m) (kg/m) (N) (N-s) + poly ... ... SYROPE:syrope.dat|EA_Dc|EA_D_Lm BA_s|BA_d + +The file ``syrope.dat`` defines + +- OWC: a tabulated nonlinear original working curve +- WCType: the working-curve type (options: ``LINEAR``, ``QUADRATIC``, ``EXP``) +- k1: the first coefficient for the working curve formula (sets the strain offset where mean tension is zero) +- k2: the second coefficient for the working curve formula (sets the curve shape) + +One example of such file is shown below. + +.. code-block:: none + + ../owc.dat OWC Original working curve lookup table path, relative to the MoorDyn input file + LINEAR WCType Working curve formula: LINEAR, QUADRATIC, or EXP + 0.25 k1 First parameter defining the working curve shape + 1.00 k2 Second parameter defining the working curve shape + +The ``owc.dat`` file follows the same format as the tabulated non-linear stiffness files described +above (three header lines, then columns for strain and tension). + +Initial conditions are specified for the Syrope lines in a separate ``SYROPE IC`` section placed after the ``LINES`` section. + +- Line(s) - the Syrope line number(s). This may be a single line number or a comma-separated list of line numbers. If non-Syrope lines are included, they are ignored and a warning is raised. +- Tmax0 – the initial highest mean tension experienced by the line prior to the current time (N) +- Tmean0 – the initial mean tension (N) + +One example of the ``SYROPE IC`` section is shown below. + +.. code-block:: none + + ---------------------- SYROPE IC -------------------------------------- + Line(s) Tmax0 Tmean0 + (-) (N) (N) + 7,8,9 3.53e6 1.18e6 + +In general, ``Tmax0 >= Tmean0``. + MoorDyn-F with FAST.Farm - Inputs ------------------------------- diff --git a/docs/references.rst b/docs/references.rst index a6e24059..c4f59200 100644 --- a/docs/references.rst +++ b/docs/references.rst @@ -82,16 +82,16 @@ Overview of MoorDyn v2 (bodies, rods, and line failures): `Hall, Matthew, “MoorDyn V2: New Capabilities in Mooring System Components and Load Cases.” In Proceedings of the ASME 2020 39th International Conference on Ocean, Offshore and Arctic Engineering. virtual conference, 2020. `_ -Seabed friction and bathymetry approach used in v2: - - `Housner, Stein, Ericka Lozon, Bruce Martin, Dorian Brefort, and Matthew Hall, “Seabed Bathymetry and Friction Modeling in MoorDyn.” Journal of - Physics: Conference Series 2362, no. 1, Nov 2022: 012018. `_ - Implementation of bending stiffness modeling for power cables: `Hall, Matthew, Senu Sirnivas, and Yi-Hsiang Yu, “Implementation and Verification of Cable Bending Stiffness in MoorDyn.” In ASME 2021 3rd International Offshore Wind Technical Conference, V001T01A011. Virtual, Online: American Society of Mechanical Engineers, 2021. `_ +Seabed friction and bathymetry approach used in v2: + + `Housner, Stein, Ericka Lozon, Bruce Martin, Dorian Brefort, and Matthew Hall, “Seabed Bathymetry and Friction Modeling in MoorDyn.” Journal of + Physics: Conference Series 2362, no. 1, Nov 2022: 012018. `_ + Non-linear line stiffness: `Lozon, Ericka, Matthew Hall, Paul McEvoy, Seojin Kim, and Bradley Ling, “Design and Analysis of a Floating-Wind Shallow-Water Mooring System @@ -122,6 +122,10 @@ Modeling of Bi-stable Nonlinear Energy Sinks in MoorDyn (most recent description `Anargyros Michaloliakos, Wei-Ying Wong, Ryan Davies, Malakonda Reddy Lekkala, Matthew Hall, Lei Zuo, Alexander F. Vakakis, "Stabilizing dynamic subsea power cables using Bi-stable nonlinear energy sinks", Ocean Engineering, vol. 334, August 2025. `_ +Syrope model for polyester ropes: + + `Wei, Zhilong, Harry B. Bingham, and Yanlin Shao. 2026. “ESOMOOR D5.1: Extended Moordyn Solver and Validation Report”. Technical University of Denmark. `_ + The Fortran version of MoorDyn is available as a module inside of OpenFAST: https://openfast.readthedocs.io/en/main/ diff --git a/source/Line.cpp b/source/Line.cpp index 228a37c4..1741a5a4 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -118,6 +118,50 @@ Line::getNonlinearBA(real ld_stretched, real l_unstretched) const return Yi / Xi; } +void +Line::setWorkingCurve(real Tmax) +{ + // Check if Tmax is within the valid range + if (Tmax < stiffYs.front() || Tmax > stiffYs.back()) { + LOGERR << "Line " << lineId << ": Tmax value " << Tmax + << " is outside the working curve range [" << stiffYs.front() + << ", " << stiffYs.back() << "]." << endl; + throw moordyn::invalid_value_error("Invalid Tmax for working curve"); + } + // maximum and minimum strains for the working curve + real eps_max = interp(stiffYs, stiffXs, Tmax); + real eps_min = stiffXs.front() + k1 * (eps_max - stiffXs.front()); + + // For linear working curve, if k1 >= 1.0 (usually much larger than unity), + // it is taken as the slope (or dimensional stiffness) + if (syropeWCForm == SYROPE_LINEAR_WC && k1 >= 1.0) + eps_min = eps_max - Tmax / k1; + + for (unsigned int I = 0; I < nEApointsWC; I++) { + // Normalize the strain points between eps_min and eps_max + stiffxs_[I] = eps_min + (eps_max - eps_min) * I / + (nEApointsWC - 1); // total strain + real xi = (stiffxs_[I] - eps_min) / (eps_max - eps_min); + + if (syropeWCForm == SYROPE_LINEAR_WC) + stiffys_[I] = Tmax * xi; + else if (syropeWCForm == SYROPE_QUADRATIC_WC) + stiffys_[I] = Tmax * xi * (k2 * xi + (1.0 - k2)); + else if (syropeWCForm == SYROPE_EXP_WC) + stiffys_[I] = Tmax * (1.0 - exp(k2 * xi)) / (1.0 - exp(k2)); + else { + LOGERR << "Line " << lineId + << ": Invalid Syrope working curve formula " << syropeWCForm + << "." << endl; + throw moordyn::invalid_value_error( + "Invalid Syrope working curve formula"); + } + + stiffzs_[I] = stiffxs_[I] - + 1.0 / vbeta * log(1.0 + vbeta / alphaMBL * stiffys_[I]); + } +} + void Line::setup(int number_in, LineProps* props, @@ -158,16 +202,50 @@ Line::setup(int number_in, Cl = props->Cl; dF = props->dF; cF = props->cF; + syropeWCForm = (syrope_wc_formula)props->SyropeWCForm; + k1 = props->k1; + k2 = props->k2; // copy in nonlinear stress-strain data if applicable stiffXs.clear(); stiffYs.clear(); + stiffZs.clear(); nEApoints = props->nEApoints; for (unsigned int I = 0; I < nEApoints; I++) { stiffXs.push_back(props->stiffXs[I]); stiffYs.push_back(props->stiffYs[I]); } + // Compute the slow strain + if (ElasticMod == ELASTIC_SYROPE) { + for (unsigned int I = 0; I < nEApoints; I++) { + stiffZs.push_back( + props->stiffXs[I] - + 1.0 / vbeta * log(1.0 + vbeta / alphaMBL * props->stiffYs[I])); + } + + // Check if stiffZs is strictly increasing + for (unsigned int I = 1; I < nEApoints; I++) { + if (stiffZs[I] <= stiffZs[I - 1]) { + LOGERR << "Line " << number + << ": The slow strain values for the Syrope model are " + "not strictly increasing. Please check the " + "stress-strain data provided." + << endl; + throw moordyn::invalid_value_error( + "Invalid slow strain data for Syrope model"); + } + } + + // Initialize working curve arrays + stiffxs_.clear(); + stiffys_.clear(); + stiffzs_.clear(); + stiffxs_.assign(nEApointsWC, 0.0); + stiffys_.assign(nEApointsWC, 0.0); + stiffzs_.assign(nEApointsWC, 0.0); + } + // Use the last entry on the lookup table. see Line::initialize() const real EA = nEApoints ? stiffYs.back() / stiffXs.back() : props->EA; NatFreqCFL::length(UnstrLen / N); @@ -606,13 +684,24 @@ Line::initialize() // the segment. This is required here to initalize the state as non-zero, // which avoids an initial transient where the segment goes from unstretched // to stretched in one time step. - if (ElasticMod != ELASTIC_CONSTANT) { + if (ElasticMod != ELASTIC_CONSTANT && ElasticMod != ELASTIC_SYROPE) { for (unsigned int i = 0; i < N; i++) { lstr[i] = unitvector(qs[i], r[i], r[i + 1]); dl_1[i] = lstr[i] - l[i]; // delta l of the segment } } + // If using the Syrope model, initalize the deltaL_1 to slow stretch based + // on the mean tension and the active working curve + if (ElasticMod == ELASTIC_SYROPE) { + for (unsigned int i = 0; i < N; i++) { + lstr[i] = unitvector(qs[i], r[i], r[i + 1]); + setWorkingCurve(Tmax[i]); + dl_1[i] = interp(stiffys_, stiffzs_, Tmean[i]) * + l[i]; // stretch instead of strain + } + } + // If using the VIV model, initalize as a distribution between 0 and 2pi for // inital phase of lift force to avoid initial transient if (Cl > 0) @@ -1019,7 +1108,8 @@ Line::getStateDeriv(InstanceStateVarView drdt) BA = getNonlinearBA(ldstr[i], l[i]); Td[i] = BA * ldstr[i] / l[i] * qs[i]; - } else { + } else if (ElasticMod == ELASTIC_VISCO_CTE || + ElasticMod == ELASTIC_VISCO_MEAN) { // viscoelastic model from // https://asmedigitalcollection.asme.org/OMAE/proceedings/IOWTC2023/87578/V001T01A029/1195018 // note that dl_1[i] is the same as Line%dl_1 in MD-F. This is the @@ -1094,6 +1184,42 @@ Line::getStateDeriv(InstanceStateVarView drdt) // update state derivative for static stiffness stretch. The visco // state is always the last element in the row. drdt.row(i).tail<1>()[0] = ld_1[i]; + } else if (ElasticMod == ELASTIC_SYROPE) { + const real dl = lstr[i] - l[i]; + + if (moordyn::EqualRealNos(Tmean[i], Tmax[i])) { + // on the original working curve + Tmean[i] = interp(stiffZs, stiffYs, dl_1[i] / l[i]); + if (dl >= 0.0) + T[i] = Tmean[i] * qs[i]; + else + T[i] = vec::Zero(); + + ld_1[i] = ((dl - interp(stiffYs, stiffXs, Tmean[i]) * l[i]) * + (alphaMBL + vbeta * Tmean[i]) + + BA_D * ldstr[i]) / + (BA + BA_D); + drdt.row(i).tail<1>()[0] = ld_1[i]; + Td[i] = ld_1[i] / l[i] * BA * qs[i]; + } else { // on the working curve + Tmean[i] = interp(stiffzs_, stiffys_, dl_1[i] / l[i]); + if (dl >= 0.0) + T[i] = Tmean[i] * qs[i]; + else + T[i] = vec::Zero(); + + ld_1[i] = ((dl - interp(stiffys_, stiffxs_, Tmean[i]) * l[i]) * + (alphaMBL + vbeta * Tmean[i]) + + BA_D * ldstr[i]) / + (BA + BA_D); + drdt.row(i).tail<1>()[0] = ld_1[i]; + Td[i] = ld_1[i] / l[i] * BA * qs[i]; + } + + if (Tmean[i] > Tmax[i]) { + Tmax[i] = Tmean[i]; + setWorkingCurve(Tmax[i]); + } } } diff --git a/source/Line.hpp b/source/Line.hpp index 9ee1b5f5..4691374c 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -90,8 +90,20 @@ class DECLDIR Line final ELASTIC_VISCO_CTE = 2, /// mean load dependent dynamic stiffness ELASTIC_VISCO_MEAN = 3, + /// Syrope model + ELASTIC_SYROPE = 4, } elastic_model; + /// @brief Syrope working curve formulas + typedef enum + { + /// linear working curve + SYROPE_LINEAR_WC = 1, + /// quadratic working curve + SYROPE_QUADRATIC_WC = 2, + /// exponential working curve + SYROPE_EXP_WC = 3, + } syrope_wc_formula; /** @brief Get the non-linear stiffness. This is interpolated from a * curve provided in the input file. @@ -130,6 +142,12 @@ class DECLDIR Line final { return seafloor ? seafloor->getAverageDepth() : -env->WtrDpth; } + + /** @brief Set up the active working curve with given Tmax + * @param Tmax preceding highest mean tension + */ + inline void setWorkingCurve(real Tmax); + // ENVIRONMENTAL STUFF /// Global struct that holds environmental settings EnvCondRef env; @@ -218,6 +236,9 @@ class DECLDIR Line final std::vector stiffXs; /// y array for stress-strain lookup table std::vector stiffYs; + /// z array for stress-strain original working curves (used only in Syrope + /// model) + std::vector stiffZs; /// number of values in bent stiffness lookup table (0 for constant EI) unsigned int nEIpoints; /// x array for bent stiffness lookup table @@ -231,6 +252,13 @@ class DECLDIR Line final /// y array for stress-strainrate lookup table std::vector dampYs; + /// auxiliary x array for Syrope working curve + std::vector stiffxs_; + /// auxiliary y array for Syrope working curve + std::vector stiffys_; + /// auxiliary z array for Syrope working curve + std::vector stiffzs_; + // Externally provided data /** true if pressure bending forces shall be considered, false otherwise * @see @@ -265,6 +293,20 @@ class DECLDIR Line final // line segment volumes std::vector V; + // Syrope variables + /// Working curve formula. See ::syrope_wc_formula + syrope_wc_formula syropeWCForm; + /// first coefficient for the Syrope working curve formula + moordyn::real k1; + /// second coefficient for the Syrope working curve formula + moordyn::real k2; + /// preceding highest mean tensions + std::vector Tmax; + /// mean tensions + std::vector Tmean; + /// number of interpolation points for Syrope working curve + const unsigned int nEApointsWC = 30; + // forces /// segment tensions std::vector T; @@ -487,6 +529,24 @@ class DECLDIR Line final * @} */ + /** @brief Set the initial Tmax values + * @param Tmax0 Initial Tmax value + */ + inline void setInitialTmax(moordyn::real Tmax0) { Tmax.assign(N, Tmax0); } + + /** @brief Set the initial mean tension values + * @param Tmean0 Initial Tmean value + */ + inline void setInitialTmean(moordyn::real Tmean0) + { + Tmean.assign(N, Tmean0); + } + + /** @brief Get the elastic model used by the line + * @return The elastic model. See ::elastic_model + */ + inline elastic_model getElasticModel() const { return ElasticMod; } + /** @brief Number of segments * * The number of nodes can be computed as moordyn::Line::getN() + 1 diff --git a/source/Misc.hpp b/source/Misc.hpp index 45c75e7f..d93013fd 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -1178,6 +1178,10 @@ typedef struct _LineProps // (matching Line Dictionary inputs) double bstiffXs[nCoef]; // x array for stress-strain lookup table (up to nCoef) double bstiffYs[nCoef]; // y array for stress-strain lookup table + int SyropeWCForm; // Syrope working curve formula (1=linear, 2=quadratic, + // 3=exponential) + double k1; // first coefficient for the Syrope working curve formula + double k2; // second coefficient for the Syrope working curve formula } LineProps; typedef struct _RodProps // (matching Rod Dictionary inputs) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 5bd39417..29e80b76 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1332,6 +1332,68 @@ moordyn::MoorDyn::ReadInFile() } } + if ((i = findStartOfSection(in_txt, { "SYROPE IC" })) != -1) { + bool hasSyrope = false; + for (auto lineProp : LinePropList) { + if (lineProp->ElasticMod == 4) { + hasSyrope = true; + break; + } + } + if (!hasSyrope) { + LOGWRN << "Warning in " << _filepath << " at line " << i + 1 + << ":" << endl + << "No line type with Syrope model is defined, but SYROPE IC section is present" << endl; + return MOORDYN_INVALID_INPUT; + } + + LOGDBG << " Reading Syrope line initial conditions:" << endl; + + // parse until the next header or the end of the file + while ((in_txt[i].find("---") == string::npos) && + (i < (int)in_txt.size())) { + vector entries = moordyn::str::split(in_txt[i], ' '); + if (entries.size() < 3) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "3 fields are required, but just " << entries.size() + << " are provided" << endl; + return MOORDYN_INVALID_INPUT; + } + + int line_id = atoi(entries[0].c_str()); + vector lineNums = moordyn::str::split(entries[0], ','); + real Tmax0 = atof(entries[1].c_str()); + real Tmean0 = atof(entries[2].c_str()); + + for (unsigned int il = 0; il < lineNums.size(); il++) { + const unsigned int line_id = atoi(lineNums[il].c_str()); + if (!line_id || line_id > LineList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "There are not " << line_id << " lines" << endl; + return MOORDYN_INVALID_INPUT; + } + + auto* line = LineList[line_id - 1]; + if (line->getElasticModel() == 4) { + line->setInitialTmax(Tmax0); + line->setInitialTmean(Tmean0); + } + else + { + LOGWRN << "Warning in " << _filepath << " at line " << i + 1 + << ":" << endl + << "Line " << line_id << " does not have Syrope model, but is included in SYROPE IC section" << endl; + } + } + + i++; + } + } + if ((i = findStartOfSection(in_txt, { "FAILURE" })) != -1) { LOGDBG << " Reading failure conditions:" << endl; // parse until the next header or the end of the file @@ -1922,29 +1984,82 @@ moordyn::MoorDyn::readLineProps(string inputText, int lineNum) moordyn::error_id err; vector EA_stuff = moordyn::str::split(entries[3], '|'); const int EA_N = EA_stuff.size(); - if (EA_N == 1) { - obj->ElasticMod = 1; // normal case - } else if (EA_N == 2) { - obj->ElasticMod = 2; // viscoelastic model, constant dynamic stiffness - obj->EA_D = atof(EA_stuff[1].c_str()); - } else if (EA_N == 3) { - obj->ElasticMod = - 3; // viscoelastic model load dependent dynamic stiffness + + // Check if Syrope model is being used + const std::string& ea0 = EA_stuff.empty() ? std::string() : EA_stuff[0]; + const bool is_syrope = (!ea0.empty() && ea0.rfind("SYROPE:", 0) == 0); + + if (is_syrope) { + obj->ElasticMod = 4; // Syrope model + LOGDBG + << "Line type '" << obj->type + << "' is using the Syrope model for axial tension-strain behavior." + << endl; + + if (EA_N != 3) { + LOGERR << "A line type EA entry with Syrope model must have 3 " + "(bar-separated) values." + << endl; + return nullptr; + } + + const std::string syrope_config = ea0.substr(7); obj->alphaMBL = atof(EA_stuff[1].c_str()); obj->vbeta = atof(EA_stuff[2].c_str()); - } else { - LOGERR - << "A line type EA entry can have at most 3 (bar-separated) values." - << endl; - return nullptr; + + // Read Syrope settings + std::string owc_path; + std::string wc_formula; + err = read_syrope_working_curves( + syrope_config.c_str(), owc_path, wc_formula, obj->k1, obj->k2); + if (err) + return nullptr; + + if (wc_formula == "linear") + obj->SyropeWCForm = 1; + else if (wc_formula == "quadratic") + obj->SyropeWCForm = 2; + else if (wc_formula == "exp") + obj->SyropeWCForm = 3; + else { + LOGERR << "Unrecognized Syrope working curve formula: " + << wc_formula << endl; + return nullptr; + } + + err = read_curve(owc_path.c_str(), + &(obj->EA), + &(obj->nEApoints), + obj->stiffXs, + obj->stiffYs); + if (err) + return nullptr; + } else { // Not Syrope, other models + if (EA_N == 1) { + obj->ElasticMod = 1; // normal case + } else if (EA_N == 2) { + obj->ElasticMod = + 2; // viscoelastic model, constant dynamic stiffness + obj->EA_D = atof(EA_stuff[1].c_str()); + } else if (EA_N == 3) { + obj->ElasticMod = + 3; // viscoelastic model load dependent dynamic stiffness + obj->alphaMBL = atof(EA_stuff[1].c_str()); + obj->vbeta = atof(EA_stuff[2].c_str()); + } else { + LOGERR << "A line type EA entry can have at most 3 (bar-separated) " + "values." + << endl; + return nullptr; + } + err = read_curve(EA_stuff[0].c_str(), + &(obj->EA), + &(obj->nEApoints), + obj->stiffXs, + obj->stiffYs); + if (err) + return nullptr; } - err = read_curve(EA_stuff[0].c_str(), - &(obj->EA), - &(obj->nEApoints), - obj->stiffXs, - obj->stiffYs); - if (err) - return nullptr; vector BA_stuff = moordyn::str::split(entries[4], '|'); unsigned int BA_N = BA_stuff.size(); @@ -2538,6 +2653,132 @@ moordyn::MoorDyn::detachLines(FailProps* failure) obj->setState(pos, vel); } +moordyn::error_id +moordyn::MoorDyn::read_syrope_working_curves(const char* entry, + string& owc_path, + string& wc_formula, + double& k1, + double& k2) +{ + string fpath = _basepath + entry; + LOGMSG << "Loading SYROPE working curves from '" << fpath << "'..." + << std::endl; + ifstream f(fpath); + if (!f.is_open()) { + LOGERR << "Cannot read the file '" << fpath << "'" << std::endl; + return MOORDYN_INVALID_INPUT_FILE; + } + + vector flines; + int i = 0; + while (f.good()) { + string fline; + getline(f, fline); + moordyn::str::rtrim(fline); + flines.push_back(fline); + i++; + } + f.close(); + + if (i < 4) { + LOGERR << "Error: Not enough data in SYROPE working curves file" + << endl; + return MOORDYN_INVALID_INPUT; + } + + bool has_owc = false; + bool has_wc_formula = false; + bool has_k1 = false; + bool has_k2 = false; + for (auto fline : flines) { + vector entries = moordyn::str::split(fline, ' '); + if (entries.size() < 2) { + LOGWRN << "Ignoring option line " << i + << " due to unspecified value or option type when reading " + "SYROPE working curves file" + << endl; + continue; + } + + LOGDBG << "\t" << entries[1] << ": " << entries[0] << std::endl; + const string value = entries[0]; + const string name = str::lower(entries[1]); + + if (name == "owc") { + owc_path = value; + has_owc = true; + } else if (name == "wctype") { + const string value_lower = str::lower(value); + if (value_lower != "linear" && value_lower != "quadratic" && + value_lower != "exp") { + LOGERR << "Unrecognized wc_formula value '" << value + << "'. Should be 'linear' or 'quadratic' or 'exp'" + << endl; + return MOORDYN_INVALID_INPUT; + } + wc_formula = value_lower; + has_wc_formula = true; + } else if (name == "k1") { + try { + k1 = std::stod(value); + } catch (const std::invalid_argument&) { + LOGERR << "Invalid k1 value '" << value << "'" << endl; + return MOORDYN_INVALID_INPUT; + } catch (const std::out_of_range&) { + LOGERR << "Out-of-range k1 value '" << value << "'" << endl; + return MOORDYN_INVALID_INPUT; + } + has_k1 = true; + } else if (name == "k2") { + try { + k2 = std::stod(value); + } catch (const std::invalid_argument&) { + LOGERR << "Invalid k2 value '" << value << "'" << endl; + return MOORDYN_INVALID_INPUT; + } catch (const std::out_of_range&) { + LOGERR << "Out-of-range k2 value '" << value << "'" << endl; + return MOORDYN_INVALID_INPUT; + } + has_k2 = true; + } else + LOGWRN << "Warning: Unrecognized option '" << name << "'" << endl; + } + + if (!has_owc || !has_wc_formula || !has_k1 || !has_k2) { + LOGERR << "Error: Missing required parameter(s) in SYROPE working " + "curves settings" + << endl; + return MOORDYN_INVALID_INPUT; + } + + // Check k1 and k2 are physically reasonable + if (wc_formula == "linear") { + if (k1 < 0.0) { + LOGERR << "Error: LINEAR working curve requires k1 >= 0" << endl; + return MOORDYN_INVALID_INPUT; + } + } else if (wc_formula == "quadratic") { + if ((k1 < 0.0) || (k1 >= 1.0) || (k2 <= 0.0) || (k2 > 1.0)) { + LOGERR << "Error: QUADRATIC working curve requires 0 <= k1 < 1 and " + "0 < k2 <= 1" + << endl; + return MOORDYN_INVALID_INPUT; + } + } else if (wc_formula == "exp") { + if ((k1 < 0.0) || (k1 >= 1.0) || (k2 <= 0.0)) { + LOGERR << "Error: EXP working curve requires 0 <= k1 < 1 and k2 > 0" + << endl; + return MOORDYN_INVALID_INPUT; + } + } else { + LOGERR << "Error: Invalid working curve formula '" << wc_formula + << "'. Expected 'linear', 'quadratic', or 'exp'" << endl; + return MOORDYN_INVALID_INPUT; + } + + return MOORDYN_SUCCESS; +}; + moordyn::error_id moordyn::MoorDyn::WriteOutputs(double t, double dt) { diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index d1cc22cc..fc449721 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -786,6 +786,50 @@ class MoorDyn final : public io::IO return MOORDYN_SUCCESS; } + /** + * @brief Read SYROPE working-curve settings from a text file + * + * This helper reads the path to the original working-curve lookup table, + * the working curve formula, and the `k1` and `k2` coefficients that + * define the working curve + * + * @param entry Path to the SYROPE working-curve definition file + * @param owc_path Output path to the original working-curve lookup table + * @param wc_formula Output working curve formula + * @param k1 Output first coefficient of the working curve formula + * @param k2 Output second coefficient of the working curve formula + * @return MOORDYN_SUCCESS if the file is read successfully, or an error + * code otherwise + * + * @note The input file is expected to use the format: + * `value key description...` + * + * Example: + * `../owc.dat OWC Original working curve lookup table path` + * `LINEAR WCType Working curve formula: LINEAR, QUADRATIC, or + * EXP` `0.25 k1 First parameter defining the working curve shape` + * `1.00 k2 Second parameter defining the working curve + * shape` + * + * @note Supported working-curve formulas are `LINEAR`, `QUADRATIC`, and + * `EXP`. For `LINEAR`, if `0 <= k1 < 1`, `k1` represents the ratio of + * strain at zero mean tension relative to the strain at `Tmax`. If `k1 >> + * 1`, it represents the static stiffness, that is, the slope of the working + * curve. `k2` is not used for the linear working curve, but it must still + * be provided. + * + * For `QUADRATIC`, `0 <= k1 < 1` and `0 < k2 < 1` are required. + * If `k2 = 1`, the curve reduces to the linear form. + * + * For `EXP`, `0 <= k1 < 1` and `k2 > 0` are required. + */ + + moordyn::error_id read_syrope_working_curves(const char* entry, + string& owc_path, + string& wc_formula, + double& k1, + double& k2); + /** @brief Get the value of a specific output channel * * This function might throw moordyn::invalid_value_error exceptions diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 108f526e..c85a02dd 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -43,6 +43,7 @@ set(CATCH2_TESTS math_tests state_tests testDecomposeString + syrope bodies beam conveying_fluid diff --git a/tests/Mooring/syrope/exp_wc/line.txt b/tests/Mooring/syrope/exp_wc/line.txt new file mode 100644 index 00000000..30bcf856 --- /dev/null +++ b/tests/Mooring/syrope/exp_wc/line.txt @@ -0,0 +1,31 @@ +One single segment. +------------------------- LINE TYPES -------------------------------------------------- +LineType Diam MassDenInAir EA BA/-zeta EI Can Cat Cdn Cdt +(-) (m) (kg/m) (-) (Pa-s/-) (n-m^2) (-) (-) (-) (-) +poly 0.203 40 SYROPE:syrope.dat|1.53e8|23.12 5.0e10|1.0e5 0.0 0.0 0.0 0.0 0.0 +----------------------- POINTS -------------------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed 0.0 0 -5.0 0 0 0 0 +2 Coupled 1.0124577 0 -5.0 0 0 0 0 +-------------------------- LINES ----------------------------------------------------------- +Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs +(-) (-) (-) (-) (m) (-) (-) +1 poly 2 1 1.0 1 tsc +-------------------------- SYROPE IC ------------------------------------------------------- +Line(s) Tmax0 Tmean0 +(-) (N) (N) +1 1.3886e6 4.339e5 +-------------------------- SOLVER OPTIONS--------------------------------------------------- +2 writeLog - Write a log file +0 g - gravitational acceleration +1025 rho - water density +5.0e-2 dtM - time step to use in mooring integration +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +70 WtrDpth - water depth +5.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen +1.0e-6 threshIC - threshold for IC convergence +1.0 TmaxIC - threshold for IC convergence +0.01 dtIC - Time lapse between convergence tests (s) +--------------------------- need this line ------------------------------------------------- \ No newline at end of file diff --git a/tests/Mooring/syrope/exp_wc/syrope.dat b/tests/Mooring/syrope/exp_wc/syrope.dat new file mode 100644 index 00000000..4750d032 --- /dev/null +++ b/tests/Mooring/syrope/exp_wc/syrope.dat @@ -0,0 +1,4 @@ +../owc.dat OWC Original working curve lookup table path, relative to the main input file +EXP WCType Working curve formula: LINEAR, QUADRATIC, or EXP +0.20 k1 First parameter defining the working curve shape +1.50 k2 Second parameter defining the working curve shape \ No newline at end of file diff --git a/tests/Mooring/syrope/linear_wc/line.txt b/tests/Mooring/syrope/linear_wc/line.txt new file mode 100644 index 00000000..91fe77d6 --- /dev/null +++ b/tests/Mooring/syrope/linear_wc/line.txt @@ -0,0 +1,31 @@ +One single segment. +------------------------- LINE TYPES -------------------------------------------------- +LineType Diam MassDenInAir EA BA/-zeta EI Can Cat Cdn Cdt +(-) (m) (kg/m) (-) (Pa-s/-) (n-m^2) (-) (-) (-) (-) +poly 0.203 40 SYROPE:syrope.dat|1.53e8|23.12 5.0e10|1.0e5 0.0 0.0 0.0 0.0 0.0 +----------------------- POINTS ---------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed 0.0 0 -5.0 0 0 0 0 +2 Coupled 1.0148657 0 -5.0 0 0 0 0 +-------------------------- LINES ------------------------------------------------- +Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs +(-) (-) (-) (-) (m) (-) (-) +1 poly 2 1 1.0 1 tsc +-------------------------- SYROPE IC ------------------------------------------------------- +Line(s) Tmax0 Tmean0 +(-) (N) (N) +1 1.3886e6 4.339e5 +-------------------------- SOLVER OPTIONS--------------------------------------------------- +2 writeLog - Write a log file +0 g - gravitational acceleration +1025 rho - water density +5.0e-2 dtM - time step to use in mooring integration +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +70 WtrDpth - water depth +5.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen +1.0e-6 threshIC - threshold for IC convergence +1.0 TmaxIC - threshold for IC convergence +0.01 dtIC - Time lapse between convergence tests (s) +--------------------------- need this line ------------------------------------------------- \ No newline at end of file diff --git a/tests/Mooring/syrope/linear_wc/syrope.dat b/tests/Mooring/syrope/linear_wc/syrope.dat new file mode 100644 index 00000000..a8e931c9 --- /dev/null +++ b/tests/Mooring/syrope/linear_wc/syrope.dat @@ -0,0 +1,4 @@ +../owc.dat OWC Original working curve lookup table path, relative to the main input file +LINEAR WCType Working curve formula: LINEAR, QUADRATIC, or EXP +1.25e8 k1 First parameter defining the working curve shape +0.0 k2 Second parameter defining the working curve shape \ No newline at end of file diff --git a/tests/Mooring/syrope/owc.dat b/tests/Mooring/syrope/owc.dat new file mode 100644 index 00000000..090a733d --- /dev/null +++ b/tests/Mooring/syrope/owc.dat @@ -0,0 +1,32 @@ +Strain Tension +(-) (N) +0.00000e+00 0.00000e+00 +2.06897e-03 1.71768e+05 +4.13793e-03 3.30952e+05 +6.20690e-03 4.78788e+05 +8.27586e-03 6.16510e+05 +1.03448e-02 7.45355e+05 +1.24138e-02 8.66556e+05 +1.44828e-02 9.81351e+05 +1.65517e-02 1.09097e+06 +1.86207e-02 1.19666e+06 +2.06897e-02 1.29964e+06 +2.27586e-02 1.40116e+06 +2.48276e-02 1.50245e+06 +2.68966e-02 1.60474e+06 +2.89655e-02 1.70927e+06 +3.10345e-02 1.81728e+06 +3.31034e-02 1.93000e+06 +3.51724e-02 2.04866e+06 +3.72414e-02 2.17450e+06 +3.93103e-02 2.30876e+06 +4.13793e-02 2.45267e+06 +4.34483e-02 2.60747e+06 +4.55172e-02 2.77439e+06 +4.75862e-02 2.95467e+06 +4.96552e-02 3.14954e+06 +5.17241e-02 3.36024e+06 +5.37931e-02 3.58800e+06 +5.58621e-02 3.83406e+06 +5.79310e-02 4.09965e+06 +6.00000e-02 4.38601e+06 \ No newline at end of file diff --git a/tests/Mooring/syrope/quadratic_wc/line.txt b/tests/Mooring/syrope/quadratic_wc/line.txt new file mode 100644 index 00000000..14c0d7a1 --- /dev/null +++ b/tests/Mooring/syrope/quadratic_wc/line.txt @@ -0,0 +1,31 @@ +One single segment. +------------------------- LINE TYPES -------------------------------------------------- +LineType Diam MassDenInAir EA BA/-zeta EI Can Cat Cdn Cdt +(-) (m) (kg/m) (-) (Pa-s/-) (n-m^2) (-) (-) (-) (-) +poly 0.203 40 SYROPE:syrope.dat|1.53e8|23.12 5.0e10|1.0e5 0.0 0.0 0.0 0.0 0.0 +----------------------- POINTS ---------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed 0.0 0 -5.0 0 0 0 0 +2 Coupled 1.0150575 0 -5.0 0 0 0 0 +-------------------------- LINES ------------------------------------------------- +Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs +(-) (-) (-) (-) (m) (-) (-) +1 poly 2 1 1.0 1 tsc +-------------------------- SYROPE IC ------------------------------------------------------- +Line(s) Tmax0 Tmean0 +(-) (N) (N) +1 1.3886e6 4.339e5 +-------------------------- SOLVER OPTIONS--------------------------------------------------- +2 writeLog - Write a log file +0 g - gravitational acceleration +1025 rho - water density +5.0e-2 dtM - time step to use in mooring integration +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +70 WtrDpth - water depth +5.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen +1.0e-6 threshIC - threshold for IC convergence +1.0 TmaxIC - threshold for IC convergence +0.01 dtIC - Time lapse between convergence tests (s) +--------------------------- need this line ------------------------------------------------- \ No newline at end of file diff --git a/tests/Mooring/syrope/quadratic_wc/syrope.dat b/tests/Mooring/syrope/quadratic_wc/syrope.dat new file mode 100644 index 00000000..540f88ed --- /dev/null +++ b/tests/Mooring/syrope/quadratic_wc/syrope.dat @@ -0,0 +1,4 @@ +../owc.dat OWC Original working curve lookup table path, relative to the main input file +QUADRATIC WCType Working curve formula: LINEAR, QUADRATIC, or EXP +0.25 k1 First parameter defining the working curve shape +1.00 k2 Second parameter defining the working curve shape \ No newline at end of file diff --git a/tests/syrope.cpp b/tests/syrope.cpp new file mode 100644 index 00000000..b07ac13f --- /dev/null +++ b/tests/syrope.cpp @@ -0,0 +1,639 @@ +/* + * This file is based on the C++ driver to verify the Syrope implementation in + * MoorDyn-C, which is available at + * https://github.com/zhilongwei/moordyn-syrope-tests.git. A Python script is + * used there to check the L2-error and plot the results, whereas here we use + * Catch2 to check the L2-error only. + */ + +#define _USE_MATH_DEFINES +#include "MoorDyn2.h" + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace { + +constexpr double kG = 9.80665; +constexpr double kMBL = 885.0e3 * kG; +constexpr double kTmax0 = 0.16 * kMBL; +constexpr double kL2Tol = 0.05; + +enum class WorkingCurveForm +{ + Linear, + Quadratic, + Exponential +}; + +constexpr double kLinearK1 = 1.25e8; +constexpr double kLinearK2 = 0.0; +constexpr double kQuadraticK1 = 0.25; +constexpr double kQuadraticK2 = 1.00; +constexpr double kExpK1 = 0.20; +constexpr double kExpK2 = 1.50; + +struct WcCase +{ + std::string name; + std::string input_file; + WorkingCurveForm form; + double eps_0; +}; + +struct SimulationResult +{ + Eigen::VectorXd times; + Eigen::VectorXd strain; + Eigen::VectorXd tension_output; +}; + +inline void +check_md(const int err, const std::string& msg) +{ + REQUIRE(err == MOORDYN_SUCCESS); + if (err != MOORDYN_SUCCESS) { + throw std::runtime_error(msg + " (err=" + std::to_string(err) + ")"); + } +} + +struct MoorDynRAII +{ + explicit MoorDynRAII(const std::string& input_file) + : sys(MoorDyn_Create(input_file.c_str())) + { + REQUIRE(sys != nullptr); + if (!sys) { + throw std::runtime_error("MoorDyn_Create failed for input: " + + input_file); + } + } + + ~MoorDynRAII() + { + if (sys) { + (void)MoorDyn_Close(sys); + } + } + + MoorDynRAII(const MoorDynRAII&) = delete; + MoorDynRAII& operator=(const MoorDynRAII&) = delete; + + MoorDyn sys = nullptr; +}; + +double +interpolate_clamped(double x, + const Eigen::VectorXd& xdata, + const Eigen::VectorXd& ydata) +{ + if (xdata.size() != ydata.size()) { + throw std::invalid_argument("interpolate_clamped: size mismatch"); + } + if (xdata.size() < 2) { + throw std::invalid_argument("interpolate_clamped: need >= 2 points"); + } + + for (Eigen::Index i = 1; i < xdata.size(); ++i) { + if (xdata[i] < xdata[i - 1]) { + throw std::invalid_argument( + "interpolate_clamped: xdata must be monotone increasing"); + } + } + + if (x <= xdata[0]) + return ydata[0]; + if (x >= xdata[xdata.size() - 1]) + return ydata[ydata.size() - 1]; + + Eigen::Index lo = 0; + Eigen::Index hi = xdata.size() - 1; + + while (hi - lo > 1) { + const Eigen::Index mid = lo + (hi - lo) / 2; + if (xdata[mid] <= x) + lo = mid; + else + hi = mid; + } + + const double x0 = xdata[lo], x1 = xdata[hi]; + const double y0 = ydata[lo], y1 = ydata[hi]; + const double dx = x1 - x0; + + if (std::abs(dx) <= std::numeric_limits::epsilon()) { + return 0.5 * (y0 + y1); + } + + const double t = (x - x0) / dx; + return y0 + t * (y1 - y0); +} + +double +find_mean_tension(double strain, + double Tmean, + double Tmax, + const Eigen::VectorXd& owc_strains, + const Eigen::VectorXd& owc_tensions, + WorkingCurveForm wc_form) +{ + (void)Tmean; + + double k1 = 0.0; + double k2 = 0.0; + switch (wc_form) { + case WorkingCurveForm::Linear: + k1 = kLinearK1; + k2 = kLinearK2; + break; + case WorkingCurveForm::Quadratic: + k1 = kQuadraticK1; + k2 = kQuadraticK2; + break; + case WorkingCurveForm::Exponential: + k1 = kExpK1; + k2 = kExpK2; + break; + default: + throw std::invalid_argument( + "find_mean_tension: unknown WorkingCurveForm"); + } + + const double eps_max = interpolate_clamped(Tmax, owc_tensions, owc_strains); + const double eps0 = owc_strains[0]; + + double eps_min = eps0 + k1 * (eps_max - eps0); + if (wc_form == WorkingCurveForm::Linear && k1 >= 1.0) { + eps_min = eps_max - Tmax / k1; + } + + const double denom = eps_max - eps_min; + if (std::abs(denom) <= std::numeric_limits::epsilon()) { + return interpolate_clamped(strain, owc_strains, owc_tensions); + } + + double xi = (strain - eps_min) / denom; + xi = std::clamp(xi, 0.0, 1.0); + + double tension_wc = 0.0; + + switch (wc_form) { + case WorkingCurveForm::Linear: + tension_wc = Tmax * xi; + break; + case WorkingCurveForm::Quadratic: + tension_wc = Tmax * xi * (k2 * xi + (1.0 - k2)); + break; + case WorkingCurveForm::Exponential: { + const double den = std::exp(k2) - 1.0; + if (std::abs(den) < 1e-14) + tension_wc = Tmax * xi; + else + tension_wc = Tmax * (std::exp(k2 * xi) - 1.0) / den; + break; + } + default: + throw std::invalid_argument( + "find_mean_tension: unknown WorkingCurveForm"); + } + + if (std::abs(tension_wc - Tmax) <= 1e-12 * (std::max)(1.0, Tmax)) { + return interpolate_clamped(strain, owc_strains, owc_tensions); + } + + return tension_wc; +} + +std::pair +read_strain_tension_table(const std::string& path) +{ + std::ifstream in(path); + if (!in) { + throw std::runtime_error("Cannot open file: " + path); + } + + std::string line; + if (!std::getline(in, line)) + throw std::runtime_error("Missing header line 1 in: " + path); + if (!std::getline(in, line)) + throw std::runtime_error("Missing header line 2 in: " + path); + + std::vector strain, tension; + strain.reserve(1024); + tension.reserve(1024); + + std::size_t lineno = 2; + while (std::getline(in, line)) { + ++lineno; + if (line.empty()) + continue; + + const auto first = line.find_first_not_of(" \t\r"); + if (first == std::string::npos) + continue; + const char c0 = line[first]; + if (c0 == '#' || c0 == '!') + continue; + + std::istringstream iss(line); + double eps = 0.0, ten = 0.0; + if (!(iss >> eps >> ten)) { + throw std::runtime_error("Failed to parse line " + + std::to_string(lineno) + " in " + path + + ": '" + line + "'"); + } + strain.push_back(eps); + tension.push_back(ten); + } + + if (strain.empty()) { + throw std::runtime_error("No data rows found in: " + path); + } + + Eigen::VectorXd eps(static_cast(strain.size())); + Eigen::VectorXd ten(static_cast(tension.size())); + for (Eigen::Index i = 0; i < eps.size(); ++i) { + eps[i] = strain[static_cast(i)]; + ten[i] = tension[static_cast(i)]; + } + + return { eps, ten }; +} + +Eigen::VectorXd +load_seg_te_column(const std::string& path) +{ + std::ifstream in(path); + if (!in) { + throw std::runtime_error("Cannot open " + path); + } + + std::string line; + if (!std::getline(in, line)) { + throw std::runtime_error("Missing header line in " + path); + } + + std::istringstream hdr(line); + std::vector headers; + for (std::string tok; hdr >> tok;) + headers.push_back(tok); + if (headers.empty()) { + throw std::runtime_error("Empty header line in " + path); + } + + const std::regex re(R"(^Seg\d+Te$)"); + int col = -1; + for (size_t i = 0; i < headers.size(); ++i) { + if (std::regex_match(headers[i], re)) { + col = static_cast(i); + break; + } + } + if (col < 0) { + throw std::runtime_error("No SegTe column found in " + path); + } + + if (!std::getline(in, line)) { + throw std::runtime_error("Missing units line in " + path); + } + + std::istringstream units_iss(line); + std::vector units; + for (std::string tok; units_iss >> tok;) + units.push_back(tok); + + if (static_cast(units.size()) <= col) { + throw std::runtime_error( + "Units line has fewer columns than header in " + path); + } + if (units[static_cast(col)] != "(N)") { + throw std::runtime_error("Unexpected unit for " + + headers[static_cast(col)] + ": got '" + + units[static_cast(col)] + + "', expected '(N)' in " + path); + } + + std::vector vals; + vals.reserve(2048); + + std::size_t lineno = 2; + while (std::getline(in, line)) { + ++lineno; + if (line.empty()) + continue; + + std::istringstream row(line); + double v = 0.0; + for (int i = 0; i <= col; ++i) { + if (!(row >> v)) { + throw std::runtime_error( + "Row has fewer numeric columns than expected at line " + + std::to_string(lineno) + " in " + path + ": '" + line + + "'"); + } + } + vals.push_back(v); + } + + Eigen::VectorXd out(static_cast(vals.size())); + for (Eigen::Index i = 0; i < out.size(); ++i) { + out[i] = vals[static_cast(i)]; + } + return out; +} + +double +jonswap_psd(double Hs, + double Tp, + double gamma, + double omega, + double sigma_a = 0.07, + double sigma_b = 0.09) +{ + if (!(omega > 0.0) || !(Tp > 0.0) || !(gamma > 0.0) || !(Hs >= 0.0)) { + return 0.0; + } + + const double wp = 2.0 * M_PI / Tp; + const double A = 1.0 - 0.287 * std::log(gamma); + const double sigma = (omega > wp) ? sigma_b : sigma_a; + const double rw = (omega - wp) / (sigma * wp); + const double a = std::pow(wp / omega, 4.0); + + return A * (5.0 / 16.0) * Hs * Hs * (a / omega) * std::exp(-1.25 * a) * + std::pow(gamma, std::exp(-0.5 * rw * rw)); +} + +double +slow_strain(double t, double seg_dur, double eps0) +{ + if (seg_dur <= 0.0) + return eps0; + + if (t < 1.0 * seg_dur) + return eps0; + if (t < 2.0 * seg_dur) + return eps0 + 2.0 * eps0 * (t - 1.0 * seg_dur) / seg_dur; + if (t < 3.0 * seg_dur) + return eps0 + 2.0 * eps0; + if (t < 4.0 * seg_dur) + return eps0 + 2.0 * eps0 - 1.0 * eps0 * (t - 3.0 * seg_dur) / seg_dur; + if (t < 5.0 * seg_dur) + return eps0 + 1.0 * eps0; + return eps0 + 1.0 * eps0 + 1.5 * eps0 * (t - 5.0 * seg_dur) / seg_dur; +} + +Eigen::VectorXd +surface_elevation_from_jonswap(double Hs, + double Tp, + double gamma, + const Eigen::VectorXd& times, + unsigned int n_omega_edges, + double omega_min, + double omega_max, + std::mt19937& rng) +{ + if (n_omega_edges < 2) { + throw std::runtime_error("n_omega_edges must be >= 2"); + } + if (!(omega_min > 0.0 && omega_max > omega_min)) { + throw std::runtime_error("Invalid omega_min/omega_max"); + } + + const Eigen::VectorXd omega_edges = + Eigen::VectorXd::LinSpaced(n_omega_edges, omega_min, omega_max); + const double domega = omega_edges[1] - omega_edges[0]; + + const Eigen::VectorXd omega_mid = + 0.5 * (omega_edges.head(n_omega_edges - 1) + + omega_edges.tail(n_omega_edges - 1)); + + const Eigen::VectorXd S = omega_mid.unaryExpr( + [&](double om) { return jonswap_psd(Hs, Tp, gamma, om); }); + + const Eigen::VectorXd a = (2.0 * S * domega).cwiseSqrt(); + + std::uniform_real_distribution unif(0.0, 2.0 * M_PI); + Eigen::VectorXd phi(n_omega_edges - 1); + for (Eigen::Index i = 0; i < phi.size(); ++i) { + phi[i] = unif(rng); + } + + Eigen::VectorXd eta = Eigen::VectorXd::Zero(times.size()); + for (Eigen::Index i = 0; i < times.size(); ++i) { + const double t = times[i]; + eta[i] = ((omega_mid * t + phi).array().cos() * a.array()).sum(); + } + return eta; +} + +std::string +line1_output_from_input(const std::string& input_path) +{ + const std::size_t sep = input_path.find_last_of("/\\"); + const std::size_t base = (sep == std::string::npos) ? 0 : (sep + 1); + + const std::size_t dot = input_path.find_last_of('.'); + const bool has_ext = (dot != std::string::npos) && (dot > base); + + const std::string stem = has_ext ? input_path.substr(0, dot) : input_path; + return stem + "_Line1.out"; +} + +SimulationResult +run_case(const WcCase& c, bool superimpose_fast) +{ + MoorDynRAII md(c.input_file); + + unsigned int ndof = 0; + check_md(MoorDyn_NCoupledDOF(md.sys, &ndof), + "MoorDyn_NCoupledDOF failed for: " + c.input_file); + + auto fairlead = MoorDyn_GetPoint(md.sys, 2); + REQUIRE(fairlead != nullptr); + + double r[3] = { 0.0, 0.0, 0.0 }; + double dr[3] = { 0.0, 0.0, 0.0 }; + check_md(MoorDyn_GetPointPos(fairlead, r), + "MoorDyn_GetPointPos failed for: " + c.input_file); + + const double seg_dur = 3.0 * 3600.0; + const double total_dur = 6.0 * seg_dur; + const double dt0 = 0.2; + const unsigned int nsteps = static_cast(total_dur / dt0); + + const Eigen::VectorXd times = Eigen::VectorXd::LinSpaced( + static_cast(nsteps) + 1, 0.0, total_dur); + + constexpr unsigned int n_omega_edges = 300; + std::mt19937 rng_wf(12345); + std::mt19937 rng_lf(54321); + + const double Hs_WF = 5.0; + const double Tp_WF = 12.0; + const double Tz_WF = Tp_WF / 1.402; + const double omega_min_WF = 1.0 / Tz_WF; + const double omega_max_WF = 20.0 / Tz_WF; + + const Eigen::VectorXd eta_WF = surface_elevation_from_jonswap(Hs_WF, + Tp_WF, + 3.3, + times, + n_omega_edges, + omega_min_WF, + omega_max_WF, + rng_wf); + + const double Hs_LF = 20.0; + const double Tp_LF = 120.0; + const double Tz_LF = Tp_LF / 1.402; + const double omega_min_LF = 1.0 / Tz_LF; + const double omega_max_LF = 20.0 / Tz_LF; + + const Eigen::VectorXd eta_LF = surface_elevation_from_jonswap(Hs_LF, + Tp_LF, + 3.3, + times, + n_omega_edges, + omega_min_LF, + omega_max_LF, + rng_lf); + + const double x0 = 1.0; + const double scale_WF = 4.00e-4; + const double scale_LF = 0.80e-4; + + Eigen::VectorXd strain_slow(times.size()); + for (Eigen::Index i = 0; i < times.size(); ++i) { + strain_slow[i] = slow_strain(times[i], seg_dur, c.eps_0); + } + + const Eigen::VectorXd strain = + superimpose_fast ? (strain_slow + scale_WF * eta_WF + scale_LF * eta_LF) + : strain_slow; + const Eigen::VectorXd x = + x0 * (Eigen::VectorXd::Ones(strain.size()) + strain); + + r[0] = x[0]; + dr[0] = (x[1] - x[0]) / dt0; + dr[1] = 0.0; + dr[2] = 0.0; + + check_md(MoorDyn_Init(md.sys, r, dr), + "MoorDyn_Init failed for: " + c.input_file); + + double t = 0.0; + double f[3] = { 0.0, 0.0, 0.0 }; + + for (unsigned int i = 0; i < nsteps; ++i) { + r[0] = x[static_cast(i)]; + dr[0] = (x[static_cast(i) + 1] - + x[static_cast(i)]) / + dt0; + + double t_in = t; + double dt_in = dt0; + + check_md(MoorDyn_Step(md.sys, r, dr, f, &t_in, &dt_in), + "MoorDyn_Step failed for: " + c.input_file); + + REQUIRE(std::abs(dt_in - dt0) <= 1e-12); + t = t_in; + } + + check_md(MoorDyn_Close(md.sys), + "MoorDyn_Close failed for: " + c.input_file); + md.sys = nullptr; + + SimulationResult out; + out.times = times; + out.strain = strain; + out.tension_output = + load_seg_te_column(line1_output_from_input(c.input_file)); + return out; +} + +double +relative_l2(const Eigen::VectorXd& ref, const Eigen::VectorXd& val) +{ + const Eigen::Index n = (std::min)(ref.size(), val.size()); + REQUIRE(n >= 2); + const double denom = ref.head(n).squaredNorm(); + REQUIRE(denom > 0.0); + return std::sqrt((ref.head(n) - val.head(n)).squaredNorm() / denom); +} + +} // namespace + +TEST_CASE("Syrope tests", "[syrope][working-curve]") +{ + const auto [owc_strains, owc_tensions] = + read_strain_tension_table("Mooring/syrope/owc.dat"); + + const std::vector cases = { + { "Linear", + "Mooring/syrope/linear_wc/line.txt", + WorkingCurveForm::Linear, + 1.48657e-02 }, + // For the quadratic and exponential cases, during the first phase + // Due to the inconsistency between Tmean0 and the initial strain, + // L2 error is large. + /* + { "Quadratic", + "Mooring/syrope/quadratic_wc/line.txt", + WorkingCurveForm::Quadratic, + 1.50575e-02 }, + { "Exponential", + "Mooring/syrope/exp_wc/line.txt", + WorkingCurveForm::Exponential, + 1.24577e-02 }, + */ + }; + + const bool superimpose_fast = true; + + for (const auto& c : cases) { + DYNAMIC_SECTION("Case: " << c.name) + { + const auto sim = run_case(c, superimpose_fast); + const Eigen::Index n = + (std::min)(sim.tension_output.size(), sim.strain.size()); + REQUIRE(n >= 2); + + Eigen::VectorXd tmax_mean(n); + tmax_mean[0] = kTmax0; + for (Eigen::Index i = 1; i < n; ++i) { + tmax_mean[i] = + (std::max)(tmax_mean[i - 1], sim.tension_output[i]); + } + + Eigen::VectorXd tension_analytical(n); + for (Eigen::Index i = 0; i < n; ++i) { + tension_analytical[i] = find_mean_tension(sim.strain[i], + sim.tension_output[i], + tmax_mean[i], + owc_strains, + owc_tensions, + c.form); + } + + const double l2 = + relative_l2(tension_analytical, sim.tension_output); + INFO("Relative L2 error = " << l2); + REQUIRE(l2 < kL2Tol); + } + } +} From f7c7dfb2eb3ab05b61ca6eaf04770f67cece9b37 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jose=20Luis=20Cerc=C3=B3s=20Pita?= Date: Tue, 12 May 2026 15:50:30 +0200 Subject: [PATCH 12/16] feat(core)!: Line breaking utilities (#379) --- CMakeLists.txt | 4 +- source/IO.cpp | 5 -- source/MoorDyn2.cpp | 60 +++++++++++++- source/MoorDyn2.h | 15 ++++ source/MoorDyn2.hpp | 11 +++ source/Point.cpp | 28 ++++++- source/Point.hpp | 9 +++ source/Time.hpp | 42 ++++++++++ tests/CMakeLists.txt | 1 + tests/line_break.cpp | 103 +++++++++++++++++++++++++ wrappers/fortran/MoorDyn.f90 | 9 ++- wrappers/matlab/MoorDynM_BreakLine.cpp | 50 ++++++++++++ wrappers/python/cmoordyn.cpp | 39 ++++++++++ wrappers/python/moordyn/moordyn.py | 14 ++++ 14 files changed, 379 insertions(+), 11 deletions(-) create mode 100644 tests/line_break.cpp create mode 100644 wrappers/matlab/MoorDynM_BreakLine.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index a252cd83..5a7c7e31 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10) set(MOORDYN_MAJOR_VERSION 2) -set(MOORDYN_MINOR_VERSION 6) -set(MOORDYN_PATCH_VERSION 2) +set(MOORDYN_MINOR_VERSION 7) +set(MOORDYN_PATCH_VERSION 0) set(MOORDYN_VERSION ${MOORDYN_MAJOR_VERSION}.${MOORDYN_MINOR_VERSION}) project(Moordyn VERSION ${MOORDYN_VERSION}) diff --git a/source/IO.cpp b/source/IO.cpp index fdb2ff4d..b4ef2131 100644 --- a/source/IO.cpp +++ b/source/IO.cpp @@ -278,11 +278,6 @@ IO::LoadFile(const std::string filepath) const uint8_t major, minor; f.read((char*)&major, sizeof(uint8_t)); f.read((char*)&minor, sizeof(uint8_t)); - std::cout << major << std::endl; - std::cout << minor << std::endl; - std::cout << _min_major_version << std::endl; - std::cout << _min_minor_version << std::endl; - std::cout << "number=" << 7 << std::endl; if ((major < _min_major_version) || ((major == _min_major_version) && (minor < _min_minor_version))) { LOGERR << "The file '" << filepath << "' was written by MoorDyn " diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 29e80b76..383717da 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -795,6 +795,41 @@ moordyn::MoorDyn::Step(const double* x, return MOORDYN_SUCCESS; } +void +MoorDyn::BreakLine(moordyn::Point* point, moordyn::Line* line) +{ + // Detach the line from the point + moordyn::EndPoints end_point; + auto pt_attachments = point->getLines(); + for (auto attachment : pt_attachments) { + if (attachment.line == line) { + end_point = attachment.end_point; + } + } + point->removeLine(line); + // Create the new point + moordyn::Point *pt = new Point(point, PointList.size()); + PointList.push_back(pt); + waves->addPoint(pt); + _t_integrator->AddPoint(pt); + // Set the state of the point + auto state = _t_integrator->r(0); + pt->initialize(state->get(pt)); + for (unsigned int i = 1; i < _t_integrator->GetNState(); i++) { + _t_integrator->r(i)->get(pt) = state->get(pt); + } + for (unsigned int i = 0; i < _t_integrator->GetNDeriv(); i++) { + _t_integrator->rd(i)->get(pt).row(0)(Eigen::seqN(0, 3)) = + state->get(pt).row(0)(Eigen::seqN(3, 3)); + // NOTE: Although when cloning free points we can actually get the + // acceleration, I (Jose Luis Cercos-Pita) do not think is worthy, so + // I am simply setting no acceleration + _t_integrator->rd(i)->get(pt).row(0)(Eigen::seqN(3, 3)) = vec::Zero(); + } + // Attach the line to the point + pt->addLine(line, end_point); +} + std::vector MoorDyn::Serialize(void) { @@ -1155,8 +1190,7 @@ moordyn::MoorDyn::ReadInFile() env->WtrDpth = -r0[2]; LOGWRN << "\t Water depth set to point " << PointList.size() + 1 << " z position because point was specified below the " - "seabed" - << endl; + "seabed" << endl; } // Check point ID is sequential starting from 1 @@ -3137,6 +3171,28 @@ MoorDyn_GetFASTtens(MoorDyn system, return MOORDYN_SUCCESS; } +int DECLDIR +MoorDyn_BreakLine(MoorDyn system, + MoorDynPoint point, + MoorDynLine line) +{ + CHECK_SYSTEM(system); + + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + try { + ((moordyn::MoorDyn*)system)->BreakLine((moordyn::Point*)point, + (moordyn::Line*)line); + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + cerr << "Error (" << err << ") at " << __FUNC_NAME__ << "():" << endl + << err_msg << endl; + return err; + } + return MOORDYN_SUCCESS; +} + int DECLDIR MoorDyn_GetDt(MoorDyn system, double* dt) { diff --git a/source/MoorDyn2.h b/source/MoorDyn2.h index 8d1f20e7..4677c29c 100644 --- a/source/MoorDyn2.h +++ b/source/MoorDyn2.h @@ -435,6 +435,21 @@ MoorDyn_GetFASTtens(MoorDyn system, float AnchHTen[], float AnchVTen[]); +/** @brief Break a line on a specific point + * + * This method is dettaching a line from the point, and in exchange is + * creating a point duplicate of type moordyn::Point::types::FREE + * @param system The Moordyn system + * @param point The discconection point + * @param line The line that is dettaching from the point + * @throw MOORDYN_SUCESS If the line is correctly dettached, an error code + * otherwise (see @ref moordyn_errors) + */ +int DECLDIR +MoorDyn_BreakLine(MoorDyn system, + MoorDynPoint point, + MoorDynLine line); + /** @brief Get the current model time step * @param system The Moordyn system * @param dt The output time step diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index fc449721..325e6c9c 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -268,6 +268,17 @@ class MoorDyn final : public io::IO waves->setWaveKinematics(U, Ud); } + /** @brief Break a line on a specific point + * + * This method is dettaching a line from the point, and in exchange is + * creating a point duplicate of type moordyn::Point::types::FREE + * @param point The discconection point + * @param line The line that is dettaching from the point + * @throw moordyn::invalid_value_error If the line is not attached to the + * point. + */ + void BreakLine(moordyn::Point* point, moordyn::Line* line); + /** @brief Produce the packed data to be saved * * The produced data can be used afterwards to restore the saved information diff --git a/source/Point.cpp b/source/Point.cpp index 06c3db10..1819db2d 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -38,12 +38,36 @@ namespace moordyn { Point::Point(moordyn::Log* log, size_t id) : Instance(log) + , waves(nullptr) , seafloor(nullptr) , pointId(id) { vtk.set_binary(); } +Point::Point(Point* visitor, size_t id) + : Instance(visitor->GetLogger()) + , env(visitor->env) + , waves(visitor->waves) + , seafloor(visitor->seafloor) + , pointM(visitor->pointM) + , pointV(visitor->pointV) + , pointF(visitor->pointF) + , pointCdA(visitor->pointCdA) + , pointCa(visitor->pointCa) + , r(visitor->r) + , rd(visitor->rd) + , Fnet(visitor->Fnet) + , t(visitor->t) + , M(visitor->M) + , acc(visitor->acc) + , pointId(id) + , number(id + 1) + , type(types::FREE) +{ + vtk.set_binary(); +} + Point::~Point() {} void @@ -150,7 +174,9 @@ Point::initialize() seafloor ? seafloor->getDepthAt(r[0], r[1]) : -env->WtrDpth; if (waterDepth > r[2]) { LOGERR << "Error: water depth is shallower than Point " << number - << "." << endl; + << "." << endl + << "\tseabed z = " << waterDepth << endl + << "\tpoint = " << r << endl; throw moordyn::invalid_value_error("Invalid water depth"); } } diff --git a/source/Point.hpp b/source/Point.hpp index d1304e26..d984ecb6 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -74,6 +74,15 @@ class DECLDIR Point final */ Point(moordyn::Log* log, size_t id); + /** @brief Point duplicator + * + * The duplicated point will have the same dynamics of the original point. + * It will be a ::types::FREE kind of point though + * @param visitor Point to duplicate + * @param id Unique identifier of this instance + */ + Point(Point* visitor, size_t id); + /** @brief Destructor */ ~Point(); diff --git a/source/Time.hpp b/source/Time.hpp index 9ef9a27b..764c5165 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -256,11 +256,26 @@ class Scheme : public io::IO */ virtual void Step(real& dt) { t_local += dt; }; + /** @brief Get the number of state variables + * @return The number of state variables + */ + virtual const unsigned int GetNState() const = 0; + + /** @brief Get the number of state derivative variables + * @return The number of state derivative variables + */ + virtual const unsigned int GetNDeriv() const = 0; + /** @brief Get the state variable * @param i The index of the state variable to take * @return The state variable + * @{ */ virtual moordyn::state::State GetState(unsigned int i = 0) = 0; + virtual moordyn::state::State* r(unsigned int i = 0) = 0; + /** + * @} + */ /** @brief Resume the simulation from the stationary solution * @param state The stationary solution @@ -288,6 +303,17 @@ class Scheme : public io::IO { } + /** @brief Get the state derivative variable + * @param i The index of the state derivative variable to take + * @return The state derivative variable + * @{ + */ + virtual moordyn::state::State GetDeriv(unsigned int i = 0) = 0; + virtual moordyn::state::State* rd(unsigned int i = 0) = 0; + /** + * @} + */ + protected: /** @brief Constructor * @param log Logging handler @@ -623,6 +649,16 @@ class SchemeBase : public Scheme */ virtual void Step(real& dt) { Scheme::Step(dt); }; + /** @brief Get the number of state variables + * @return The number of state variables + */ + inline const unsigned int GetNState() const { return NSTATE; } + + /** @brief Get the number of state derivative variables + * @return The number of state derivative variables + */ + inline const unsigned int GetNDeriv() const { return NDERIV; } + /** @brief Get the state * @param i The index of the state variable to take * @return The state variable @@ -720,6 +756,7 @@ class SchemeBase : public Scheme * @return The state derivative * @throws moordyn::invalid_value_error if the @p i index is greater or * equal than the number of state derivatives + * @{ */ inline state::State* rd(unsigned int i = 0) { @@ -732,6 +769,11 @@ class SchemeBase : public Scheme return _rd[i]; } + inline state::State GetDeriv(unsigned int i = 0) { return *rd(i); } + /** + * @} + */ + /** @brief Produce the packed data to be saved * * The produced data can be used afterwards to restore the saved information diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index c85a02dd..46dcc407 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -56,6 +56,7 @@ set(CATCH2_TESTS midpoint aca wilson + line_break ) function(make_executable test_name, extension) diff --git a/tests/line_break.cpp b/tests/line_break.cpp new file mode 100644 index 00000000..50856e29 --- /dev/null +++ b/tests/line_break.cpp @@ -0,0 +1,103 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file minimal.cpp + * Minimal tests that only checks the library is correctly initialized, + * running and closing + */ + +#include "MoorDyn2.h" +#include +#include +#include + +// #define SAVE_VTK + +using namespace std; + +TEST_CASE("Breaker") +{ + MoorDyn system = MoorDyn_Create("Mooring/lines.txt"); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 9); + + int err; + double x[9], dx[9]; + // Get the initial positions from the config file + for (unsigned int i = 0; i < 3; i++) { + // 4 = first fairlead id + auto point = MoorDyn_GetPoint(system, i + 4); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x + 3 * i) == MOORDYN_SUCCESS); + } + + auto point = MoorDyn_GetPoint(system, 4); + REQUIRE(point); + auto line = MoorDyn_GetLine(system, 1); + REQUIRE(line); + + std::fill(dx, dx + 9, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); +#ifdef SAVE_VTK + REQUIRE(MoorDyn_SaveVTK(system, "line_break.000.vtm") == MOORDYN_SUCCESS); +#endif + // Let's move the system at a 10.0m/s speed during 0.5 seconds + double f[9]; + dx[0] = 10.0; + double t = 0.0, dt = 0.5; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); +#ifdef SAVE_VTK + REQUIRE(MoorDyn_SaveVTK(system, "line_break.001.vtm") == MOORDYN_SUCCESS); +#endif + x[0] += dx[0] * dt; + + // Break a line and repeat 3 times + REQUIRE(MoorDyn_BreakLine(system, point, line) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); +#ifdef SAVE_VTK + REQUIRE(MoorDyn_SaveVTK(system, "line_break.002.vtm") == MOORDYN_SUCCESS); +#endif + x[0] += dx[0] * dt; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); +#ifdef SAVE_VTK + REQUIRE(MoorDyn_SaveVTK(system, "line_break.003.vtm") == MOORDYN_SUCCESS); +#endif + x[0] += dx[0] * dt; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); +#ifdef SAVE_VTK + REQUIRE(MoorDyn_SaveVTK(system, "line_break.004.vtm") == MOORDYN_SUCCESS); +#endif + x[0] += dx[0] * dt; + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} diff --git a/wrappers/fortran/MoorDyn.f90 b/wrappers/fortran/MoorDyn.f90 index 2f825f04..2358e4ad 100644 --- a/wrappers/fortran/MoorDyn.f90 +++ b/wrappers/fortran/MoorDyn.f90 @@ -56,7 +56,7 @@ module moordyn MD_ExternalWaveKinSet, MD_GetNumberBodies, MD_GetBody, & MD_GetNumberRods, MD_GetRod, MD_GetNumberPoints, MD_GetPoint, & MD_GetNumberLines, MD_GetLine, MD_GetFASTtens, & - MD_GetDt, MD_SetDt, MD_GetCFL, MD_SetCFL, & + MD_BreakLine, MD_GetDt, MD_SetDt, MD_GetCFL, MD_SetCFL, & MD_GetTimeScheme, MD_SetTimeScheme, & MD_SaveState, MD_LoadState, MD_Serialize, MD_Deserialize, & MD_Save, MD_Load, MD_SaveVTK, & @@ -256,6 +256,13 @@ function MoorDyn_GetFASTtens(instance, n, fht, fvt, aht, avt) bind(c, name='Moor integer(c_int) :: rc end function MoorDyn_GetFASTtens + integer(c_int) function MD_BreakLine(instance, point, line) bind(c, name='MoorDyn_BreakLine') + import :: c_ptr, c_int + type(c_ptr), value, intent(in) :: instance + type(c_ptr), value, intent(in) :: point + type(c_ptr), value, intent(in) :: line + end function MD_BreakLine + function MoorDyn_GetDt(instance, dt) bind(c, name='MoorDyn_GetDt') result(rc) import :: c_ptr, c_double, c_int type(c_ptr), value, intent(in) :: instance diff --git a/wrappers/matlab/MoorDynM_BreakLine.cpp b/wrappers/matlab/MoorDynM_BreakLine.cpp new file mode 100644 index 00000000..4e708fe5 --- /dev/null +++ b/wrappers/matlab/MoorDynM_BreakLine.cpp @@ -0,0 +1,50 @@ +/* + * Copyright (c) 2022, Matt Hall + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "mex.hpp" +#include "mexAdapter.hpp" + +#include "MoorDyn2.h" +#include "moordyn_matlab.h" + +using namespace matlab::data; +using matlab::mex::ArgumentList; + +MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 3, 0) +{ + const uint64_t _point_id = inputs[1][0]; + MoorDynPoint point = (MoorDynPoint)decode_ptr(_point_id); + const uint64_t _line_id = inputs[2][0]; + MoorDynLine line = (MoorDynLine)decode_ptr(_line_id); + + const int err = MoorDyn_BreakLine(instance, point, line); + MOORDYNM_CHECK_ERROR(err); +} +MOORDYNM_MEX_FUNCTION_END diff --git a/wrappers/python/cmoordyn.cpp b/wrappers/python/cmoordyn.cpp index 5f585ab6..7adc4ce1 100644 --- a/wrappers/python/cmoordyn.cpp +++ b/wrappers/python/cmoordyn.cpp @@ -862,6 +862,41 @@ get_fast_tens(PyObject*, PyObject* args) return lst; } +/** @brief Wrapper to MoorDyn_BreakLine() function + * @param args Python passed arguments + * @return None + */ +static PyObject* +break_line(PyObject*, PyObject* args) +{ + PyObject *capsule, *pt_capcule, *ln_capsule; + int num_lines; + + if (!PyArg_ParseTuple(args, "OOO", &capsule, &pt_capcule, &ln_capsule)) + return NULL; + + MoorDyn system = + (MoorDyn)PyCapsule_GetPointer(capsule, moordyn_capsule_name); + if (!system) + return NULL; + MoorDynPoint point = + (MoorDynPoint)PyCapsule_GetPointer(pt_capcule, point_capsule_name); + if (!point) + return NULL; + MoorDynLine line = + (MoorDynLine)PyCapsule_GetPointer(ln_capsule, line_capsule_name); + if (!line) + return NULL; + + const int err = MoorDyn_BreakLine(system, point, line); + if (err != 0) { + PyErr_SetString(PyExc_RuntimeError, "MoorDyn reported an error"); + return NULL; + } + + Py_RETURN_NONE; +} + /** @brief Wrapper to MoorDyn_GetDt() function * @param args Python passed arguments * @return The time step @@ -3008,6 +3043,10 @@ static PyMethodDef moordyn_methods[] = { get_fast_tens, METH_VARARGS, "Get vertical and horizontal forces in the mooring lines" }, + { "break_line", + break_line, + METH_VARARGS, + "Break a line on a certain point" }, { "get_dt", get_dt, METH_VARARGS, "Get the inner time step" }, { "set_dt", set_dt, METH_VARARGS, "Set the inner time step" }, { "get_cfl", get_cfl, METH_VARARGS, "Get the CFL factor" }, diff --git a/wrappers/python/moordyn/moordyn.py b/wrappers/python/moordyn/moordyn.py index 1af43490..bed89479 100644 --- a/wrappers/python/moordyn/moordyn.py +++ b/wrappers/python/moordyn/moordyn.py @@ -527,6 +527,20 @@ def GetFASTtens(instance, n_lines): return data[0], data[1], data[2], data[3] +def BreakLine(instance, point, line): + """Break a line on a specific point + This method is dettaching a line from the point, and in exchange is + creating a point duplicate of type FREE + + Parameters: + instance (cmoordyn.MoorDyn): The MoorDyn instance + point (cmoordyn.MoorDynPoint): The point instance + line (cmoordyn.MoorDynLine): The line instance + """ + import cmoordyn + cmoordyn.break_line(instance, point, line) + + def GetDt(instance): """Get the current model time step From 50de7b5c638e82fb8b6669e764e4875a1791b8de Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 8 Jun 2026 08:48:46 +0200 Subject: [PATCH 13/16] fix(core): Return an error code when points below the seabed are detected --- source/MoorDyn2.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 383717da..dc486d0a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -522,7 +522,12 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } // call this just to set WaterKin (may also set up output file in // future) - PointList[l]->initialize(); + try { + PointList[l]->initialize(); + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) + return err; ix += 3; } From 48006e32212cef603401b47e7cb5f9a598306440 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 9 Jun 2026 06:18:09 +0200 Subject: [PATCH 14/16] fix(core): Demote points below seabed from error to warning --- source/MoorDyn2.cpp | 14 +++++--------- source/Point.cpp | 3 +-- 2 files changed, 6 insertions(+), 11 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index dc486d0a..d9970cbb 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -522,12 +522,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } // call this just to set WaterKin (may also set up output file in // future) - try { - PointList[l]->initialize(); - } - MOORDYN_CATCHER(err, err_msg); - if (err != MOORDYN_SUCCESS) - return err; + PointList[l]->initialize(); ix += 3; } @@ -1193,9 +1188,10 @@ moordyn::MoorDyn::ReadInFile() // Note - this is not in MD-F if (r0[2] < -env->WtrDpth) { env->WtrDpth = -r0[2]; - LOGWRN << "\t Water depth set to point " << PointList.size() + 1 - << " z position because point was specified below the " - "seabed" << endl; + LOGWRN << "\t Water depth set to point " + << PointList.size() + 1 + << " z position because point was specified below the" + << " seabed" << endl; } // Check point ID is sequential starting from 1 diff --git a/source/Point.cpp b/source/Point.cpp index 1819db2d..9cddd0b6 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -173,11 +173,10 @@ Point::initialize() const real waterDepth = seafloor ? seafloor->getDepthAt(r[0], r[1]) : -env->WtrDpth; if (waterDepth > r[2]) { - LOGERR << "Error: water depth is shallower than Point " << number + LOGWRN << "Error: water depth is shallower than Point " << number << "." << endl << "\tseabed z = " << waterDepth << endl << "\tpoint = " << r << endl; - throw moordyn::invalid_value_error("Invalid water depth"); } } From a98c3a79e99eee2c5361155e04f1ac6bb13e0002 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 9 Jun 2026 06:22:51 +0200 Subject: [PATCH 15/16] fix(core): MATLAB wrappers trying to use the instance as a parameter (fixes #384) --- wrappers/matlab/MoorDynM_Load.cpp | 2 +- wrappers/matlab/MoorDynM_LoadState.cpp | 2 +- wrappers/matlab/MoorDynM_Save.cpp | 2 +- wrappers/matlab/MoorDynM_SaveBodyVTK.cpp | 2 +- wrappers/matlab/MoorDynM_SaveLineVTK.cpp | 2 +- wrappers/matlab/MoorDynM_SaveRodVTK.cpp | 2 +- wrappers/matlab/MoorDynM_SaveState.cpp | 2 +- wrappers/matlab/MoorDynM_SaveVTK.cpp | 2 +- wrappers/matlab/MoorDynM_SetLogFile.cpp | 2 +- wrappers/matlab/MoorDynM_SetTimeScheme.cpp | 2 +- 10 files changed, 10 insertions(+), 10 deletions(-) diff --git a/wrappers/matlab/MoorDynM_Load.cpp b/wrappers/matlab/MoorDynM_Load.cpp index 621d7fe6..06d35494 100644 --- a/wrappers/matlab/MoorDynM_Load.cpp +++ b/wrappers/matlab/MoorDynM_Load.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_Load(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_LoadState.cpp b/wrappers/matlab/MoorDynM_LoadState.cpp index 3a024270..8cec97ff 100644 --- a/wrappers/matlab/MoorDynM_LoadState.cpp +++ b/wrappers/matlab/MoorDynM_LoadState.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_LoadState(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_Save.cpp b/wrappers/matlab/MoorDynM_Save.cpp index ca77aa0a..c9d930ce 100644 --- a/wrappers/matlab/MoorDynM_Save.cpp +++ b/wrappers/matlab/MoorDynM_Save.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_Save(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SaveBodyVTK.cpp b/wrappers/matlab/MoorDynM_SaveBodyVTK.cpp index 4d3ae7b9..fb8a600f 100644 --- a/wrappers/matlab/MoorDynM_SaveBodyVTK.cpp +++ b/wrappers/matlab/MoorDynM_SaveBodyVTK.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDynBody, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SaveBodyVTK(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SaveLineVTK.cpp b/wrappers/matlab/MoorDynM_SaveLineVTK.cpp index 3f62c623..972e19de 100644 --- a/wrappers/matlab/MoorDynM_SaveLineVTK.cpp +++ b/wrappers/matlab/MoorDynM_SaveLineVTK.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDynLine, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SaveLineVTK(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SaveRodVTK.cpp b/wrappers/matlab/MoorDynM_SaveRodVTK.cpp index 7f2f4d1c..a20c4b87 100644 --- a/wrappers/matlab/MoorDynM_SaveRodVTK.cpp +++ b/wrappers/matlab/MoorDynM_SaveRodVTK.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDynRod, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SaveRodVTK(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SaveState.cpp b/wrappers/matlab/MoorDynM_SaveState.cpp index 21a36162..607719d2 100644 --- a/wrappers/matlab/MoorDynM_SaveState.cpp +++ b/wrappers/matlab/MoorDynM_SaveState.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SaveState(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SaveVTK.cpp b/wrappers/matlab/MoorDynM_SaveVTK.cpp index 4438cc37..f3918362 100644 --- a/wrappers/matlab/MoorDynM_SaveVTK.cpp +++ b/wrappers/matlab/MoorDynM_SaveVTK.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SaveVTK(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SetLogFile.cpp b/wrappers/matlab/MoorDynM_SetLogFile.cpp index 19eab347..6d096547 100644 --- a/wrappers/matlab/MoorDynM_SetLogFile.cpp +++ b/wrappers/matlab/MoorDynM_SetLogFile.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray filename_matlab = inputs[0]; + const CharArray filename_matlab = inputs[1]; std::string filename(filename_matlab.toAscii()); const int err = MoorDyn_SetLogFile(instance, filename.c_str()); MOORDYNM_CHECK_ERROR(err); diff --git a/wrappers/matlab/MoorDynM_SetTimeScheme.cpp b/wrappers/matlab/MoorDynM_SetTimeScheme.cpp index a2c810c3..2955b83b 100644 --- a/wrappers/matlab/MoorDynM_SetTimeScheme.cpp +++ b/wrappers/matlab/MoorDynM_SetTimeScheme.cpp @@ -39,7 +39,7 @@ using matlab::mex::ArgumentList; MOORDYNM_MEX_FUNCTION_BEGIN(MoorDyn, 2, 0) { - const CharArray name_matlab = inputs[0]; + const CharArray name_matlab = inputs[1]; std::string name(name_matlab.toAscii()); const int err = MoorDyn_SetTimeScheme(instance, name.c_str()); MOORDYNM_CHECK_ERROR(err); From f8f208a02708f8a820248b655944b384e116fa0c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 9 Jun 2026 08:21:22 +0200 Subject: [PATCH 16/16] Update the CHANGELOG for v2.7.0 --- CHANGELOG.md | 34 ++++++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3b05383a..08c8b1d6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,3 +1,37 @@ +## [2.7.0] - 2026-06-09 + +### 🚀 Features + +- *(core)* Implementation of the Syrope model for polyester ropes +- *(core)* [**breaking**] Line breaking utilities (#379) + +### 🐛 Bug Fixes + +- *(core)* Memory leak on lean-vtk +- *(core)* Segmentation Fault when trying to print Td output +- *(core)* Return an error code when points below the seabed are detected +- *(core)* Demote points below seabed from error to warning +- *(core)* MATLAB wrappers trying to use the instance as a parameter (fixes #384) + +### 💼 Other + +- *(deps)* Bump actions/upload-artifact from 6 to 7 +- *(deps)* Bump actions/download-artifact from 7 to 8 +- *(deps)* Bump docker/setup-qemu-action from 3 to 4 +- *(deps)* Bump pypa/cibuildwheel from 3.3.1 to 3.4.0 +- *(deps)* Bump pypa/cibuildwheel from 3.4.0 to 3.4.1 +- *(deps)* Bump matlab-actions/run-command from 2 to 3 +- *(deps)* Bump matlab-actions/setup-matlab from 2 to 3 +## [2.6.1] - 2026-02-20 + +### 🐛 Bug Fixes + +- *(core)* Save with VTP extension +- *(core)* Wrong Fortran indexes + +### ⚙️ Miscellaneous Tasks + +- *(doc)* Moved to git-cliff to produce the CHANGELOG file ## [2.6.0] - 2026-02-17 ### 🚀 Features