diff --git a/.github/workflows/build-mingw.yml b/.github/workflows/build-mingw.yml index 1208dd1d..40d0519b 100644 --- a/.github/workflows/build-mingw.yml +++ b/.github/workflows/build-mingw.yml @@ -1,8 +1,8 @@ -name: CMake +name: MinGW on: push: - branches: [ $default-branch, master, v2 ] + branches: [ $default-branch, master ] pull_request: branches: - "**" @@ -21,7 +21,7 @@ jobs: os: [windows-latest] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Create folders run: | @@ -32,5 +32,4 @@ jobs: run: cmake -B ${{github.workspace}}/build -G "MinGW Makefiles" -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DFORTRAN_WRAPPER:BOOL=ON -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=OFF -DBUILD_TESTING=ON - name: Build - id: build run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} diff --git a/.github/workflows/build-test.yml b/.github/workflows/build-test.yml index debd2a1a..36daddf5 100644 --- a/.github/workflows/build-test.yml +++ b/.github/workflows/build-test.yml @@ -2,7 +2,7 @@ name: CMake on: push: - branches: [ $default-branch, master, v2 ] + branches: [ $default-branch, master ] pull_request: branches: - "**" @@ -24,23 +24,33 @@ jobs: release_id: ${{ steps.create_release.outputs.id }} upload_url: ${{ steps.create_release.outputs.upload_url }} steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 if: github.event_name == 'push' - - uses: dev-drprasad/delete-tag-and-release@v0.2.1 - continue-on-error: true - with: - delete_release: true - tag_name: "nightly" - env: - GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + - name: moordyn_tag_name + id: moordyn_tag_name + shell: bash + run: | + major=`cat CMakeLists.txt | grep MOORDYN_MAJOR_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + minor=`cat CMakeLists.txt | grep MOORDYN_MINOR_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + patch=`cat CMakeLists.txt | grep MOORDYN_PATCH_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + echo "moordyn_tag_name=v$major.$minor.$patch" >> $GITHUB_OUTPUT if: github.event_name == 'push' + # - uses: dev-drprasad/delete-tag-and-release@v1.0.1 + # continue-on-error: true + # with: + # delete_release: true + # tag_name: "nightly" + # env: + # GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + # if: github.event_name == 'push' + - uses: rickstaa/action-create-tag@v1 id: create_tag with: - tag: "nightly" - message: "Latest release" + tag: ${{steps.moordyn_tag_name.outputs.moordyn_tag_name}} + message: "Latest release (${{steps.moordyn_tag_name.outputs.moordyn_tag_name}})" force_push_tag: true if: github.event_name == 'push' @@ -50,8 +60,8 @@ jobs: env: GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} with: - tag_name: "nightly" - release_name: "nightly" + tag_name: ${{steps.moordyn_tag_name.outputs.moordyn_tag_name}} + release_name: ${{steps.moordyn_tag_name.outputs.moordyn_tag_name}} draft: false prerelease: false if: github.event_name == 'push' @@ -64,7 +74,7 @@ jobs: os: [ubuntu-22.04, windows-latest, macOS-latest] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: moordyn_version id: moordyn_version @@ -75,19 +85,15 @@ jobs: patch=`cat CMakeLists.txt | grep MOORDYN_PATCH_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` echo "moordyn_version=$major.$minor.$patch" >> $GITHUB_OUTPUT - - name: Setup GCC Fortran (Linux & Mac) + - name: Setup GCC Fortran (Linux) uses: awvwgk/setup-fortran@main id: setup-fortran with: compiler: gcc if: runner.os == 'Linux' - - name: Setup Intel Fortran - uses: modflowpy/install-intelfortran-action@v1 - if: runner.os == 'Windows' - - name: download pre-built VTK static library - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-x86_64.tar.gz target: ${{github.workspace}}/ @@ -106,22 +112,32 @@ jobs: if: runner.os == 'Linux' - name: Configure CMake (Windows) - run: cmake -B ${{github.workspace}}/build -G Ninja -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DFORTRAN_WRAPPER:BOOL=ON -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DVTK_DIR=${{github.workspace}}/vtk/lib/cmake/vtk-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}/ -DBUILD_TESTING=OFF + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DVTK_DIR=${{github.workspace}}/vtk/lib/cmake/vtk-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}/ -DBUILD_TESTING=ON if: runner.os == 'Windows' - name: Configure CMake (Mac) - run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DVTK_DIR=${{github.workspace}}/vtk/lib/cmake/vtk-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}/ -DBUILD_TESTING=OFF + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DVTK_DIR=${{github.workspace}}/vtk/lib/cmake/vtk-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}/ -DBUILD_TESTING=ON if: runner.os == 'macOS' - name: Build id: build run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} - - name: Test (Linux) + # We do a little hack here. We install the library so we perfectly know the + # path. Then we set the environment variable to let the OS find the + # libraries + + - name: Install + run: cmake --install ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Set $PATH (Windows) + run: Add-Content $env:GITHUB_PATH "${{github.workspace}}\install\bin" + if: runner.os == 'Windows' + + - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux run: ctest -C ${{env.BUILD_TYPE}} - if: runner.os == 'Linux' - name: Install working-directory: ${{github.workspace}}/build diff --git a/.github/workflows/check-version.yml b/.github/workflows/check-version.yml new file mode 100644 index 00000000..738520ec --- /dev/null +++ b/.github/workflows/check-version.yml @@ -0,0 +1,31 @@ +name: Check version + +on: + pull_request: + branches: [ $default-branch, master ] + +jobs: + check: + name: Check that the version is valid + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v4 + + - name: moordyn_version + id: moordyn_version + shell: bash + run: | + major=`cat CMakeLists.txt | grep MOORDYN_MAJOR_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + minor=`cat CMakeLists.txt | grep MOORDYN_MINOR_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + patch=`cat CMakeLists.txt | grep MOORDYN_PATCH_VERSION | head -1 | awk -F' ' '{print $2}' | awk -F')' '{print $1}'` + echo "moordyn_version=$major.$minor.$patch" >> $GITHUB_OUTPUT + + - name: Tag check + uses: mukunku/tag-exists-action@v1.4.0 + id: checkTag + with: + tag: "v${{steps.moordyn_version.outputs.moordyn_version}}" + + - name: Stop if tag exists + run: | + if [ ${{ steps.checkTag.outputs.exists }} == true ]; then exit 1; else exit 0; fi diff --git a/.github/workflows/python-wheels.yml b/.github/workflows/python-wheels.yml index 3e1ca3f2..b7fe66a2 100644 --- a/.github/workflows/python-wheels.yml +++ b/.github/workflows/python-wheels.yml @@ -2,7 +2,7 @@ name: Python-Wheels on: push: - branches: [ $default-branch, master, v2-make-wheels ] + branches: [ $default-branch, master ] permissions: write-all @@ -29,10 +29,12 @@ jobs: tar -xvzf vtk-Linux-`uname -m`.tar.gz -C vtk/ steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 # Used to host cibuildwheel - - uses: actions/setup-python@v3 + - uses: actions/setup-python@v4 + with: + python-version: '3.x' - name: Create setup.py run: | @@ -47,42 +49,42 @@ jobs: run: python -m pip install cibuildwheel - name: download pre-built VTK static library (non-Linux) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-x86_64.tar.gz target: ${{github.workspace}}/ if: runner.os != 'Linux' - name: download pre-built VTK static library (Linux-x86_64) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-x86_64.tar.gz target: ${{github.workspace}}/ if: runner.os == 'Linux' - name: download pre-built VTK static library (Linux-aarch64) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-aarch64.tar.gz target: ${{github.workspace}}/ if: runner.os == 'Linux' - name: download pre-built VTK static library (Linux-armv7) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-armv7.tar.gz target: ${{github.workspace}}/ if: runner.os == 'Linux' - name: download pre-built VTK static library (Linux-ppc64le) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-ppc64le.tar.gz target: ${{github.workspace}}/ if: runner.os == 'Linux' - name: download pre-built VTK static library (Linux-s390x) - uses: suisei-cn/actions-download-file@v1.0.1 + uses: suisei-cn/actions-download-file@v1.4.0 with: url: https://github.com/sanguinariojoe/vtk-builds/releases/download/VTK-${{env.VTK_VERSION_MAJOR}}.${{env.VTK_VERSION_MINOR}}.${{env.VTK_VERSION_PATCH}}-static/vtk-${{runner.os}}-s390x.tar.gz target: ${{github.workspace}}/ @@ -98,10 +100,40 @@ jobs: tar -xvzf vtk-${{runner.os}}-x86_64.tar.gz -C vtk/ if: runner.os != 'Linux' + - name: Build the source distribution + run: python setup.py sdist + if: runner.os == 'Linux' + - name: Build wheels - run: python -m cibuildwheel --output-dir wheelhouse + run: python -m cibuildwheel --output-dir dist - uses: actions/upload-artifact@v3 + id: build_wheels + with: + name: python-package-distributions + path: ./dist/* + + publish: + runs-on: ${{ matrix.os }} + needs: [build_wheels] + strategy: + matrix: + os: [ubuntu-22.04] + + steps: + - uses: actions/checkout@v4 + + - name: Download all the dists + uses: actions/download-artifact@v3 + with: + name: python-package-distributions + path: dist/ + + - name: Publish package to TestPyPI + uses: pypa/gh-action-pypi-publish@release/v1 with: - name: "Python wheels" - path: ./wheelhouse/*.whl + # password: ${{ secrets.MOORDYN_TESTPYPI_API }} + # repository-url: https://test.pypi.org/legacy/ + password: ${{ secrets.MOORDYN_PYPI_API }} + repository-url: https://upload.pypi.org/legacy/ + skip-existing: true diff --git a/.gitignore b/.gitignore index 06f71d0a..3be253f2 100644 --- a/.gitignore +++ b/.gitignore @@ -65,3 +65,4 @@ dist /source/.vscode .vscode/* +docs/_build/* \ No newline at end of file diff --git a/.readthedocs.yaml b/.readthedocs.yaml new file mode 100644 index 00000000..31026592 --- /dev/null +++ b/.readthedocs.yaml @@ -0,0 +1,16 @@ + +version: 2 + +build: + os: ubuntu-22.04 + tools: + python: "3.11" + apt_packages: + - graphviz + +sphinx: + configuration: docs/conf.py + +python: + install: + - requirements: docs/requirements.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index 2271226b..3e815cf0 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 2) -set(MOORDYN_PATCH_VERSION 0) +set(MOORDYN_PATCH_VERSION 1) set(MOORDYN_VERSION ${MOORDYN_MAJOR_VERSION}.${MOORDYN_MINOR_VERSION}) project(Moordyn VERSION ${MOORDYN_VERSION}) @@ -21,7 +21,7 @@ set(BUILD_DOCS OFF CACHE BOOL "Build the documentation for users and developers") set(BUILD_BENCHMARKS OFF CACHE BOOL "Build the benchmarks. Makes use of Google's Benchmark library and requires an internet connection to download.") -set(EXTERNAL_EIGEN ON CACHE BOOL +set(EXTERNAL_EIGEN OFF CACHE BOOL "Use the Eigen3 installed in the system") set(USE_VTK OFF CACHE BOOL "Link with VTK to produce output binary files") diff --git a/README.md b/README.md index 3b0557d0..463170a8 100644 --- a/README.md +++ b/README.md @@ -1,70 +1,37 @@ MoorDyn v2 ========== -MoorDyn v2 is a lumped-mass mooring dynamics model intended for coupling with -floating structure codes. As of 2022 it is available under the BSD 3-Clause +MoorDyn is a lumped-mass model for simulating the dynamics of mooring systems connected to floating offshore structures. As of 2022 it is available under the BSD 3-Clause license. -More information about MoorDyn is now available at moordyn-v2.readthedocs.io +Read the docs here: [moordyn.readthedocs.io](https://moordyn.readthedocs.io/en/latest/) -## Roadmap +It accounts for internal axial stiffness and damping forces, weight and buoyancy forces, hydrodynamic forces from Morison's equation (assuming calm water so far), and vertical spring-damper forces from contact with the seabed. MoorDyn's input file format is based on that of [MAP](https://www.nrel.gov/wind/nwtc/map-plus-plus.html). The model supports arbitrary line interconnections, clump weights and floats, different line properties, and six degree of freedom rods. -The version 2 is currently under development: +MoorDyn is implemented both in Fortran and in C++. The Fortran version of MoorDyn (MoorDyn-F) is a core module in [OpenFAST](https://github.com/OpenFAST/openfast) and can be used as part of an OpenFAST or FAST.Farm simulation, or used in a standalone form. The C++ version of MoorDyn (MoorDyn-C) is more adaptable to different use cases and couplings. It can be compiled as a dynamically-linked library or wrapped for use in Python (as a module), Fortran, or Matlab. It features simpler functions for easy coupling with models or scripts coded in C/C++, Fortran, Matlab/Simulink, etc., including a coupling with [WEC-Sim](https://wec-sim.github.io/WEC-Sim/master/index.html). - - [X] BSD-3 license - - [X] Rigid bodies - - [X] Rigid cylindrical Rod objects, with surface-piercing capabilities - - [ ] Wave kinematics - - [X] Bending stiffness for power cable simulation - - [X] pinned (3 DOF) and rigid (6 DOF) coupling options - - [X] Replace the custom algebra code by [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) - - [X] Different time integrators - - [X] Save/load - - [X] VTK exporter - - [X] New C API - - [ ] New C++ API - - [X] Standarize code styling with [clang-format](https://clang.llvm.org/docs/ClangFormat.html) - - [X] Replace the custom compilation scripts by [CMake](https://cmake.org/) autotools - - [X] FORTRAN wrappers - - [X] Python wrappers - - [X] MATLAB mex files - - [X] Rust wrappers - - [ ] Documentation for users - - [X] Documentation for developers - - [ ] Tests +Both forms of MoorDyn feature the same underlying mooring model, use the same input and output conventions, and are being updated and improved in parallel. They follow the same version numbering, with a "C" or "F" suffix for differentiation. -There are also some other additional tasks to be carried out prior to the final -release: +Further information on MoorDyn can be found on the [documentation site](https://moordyn.readthedocs.io/en/latest/). MoorDyn-F is available in the [OpenFAST repository](https://github.com/OpenFAST/openfast/tree/main/modules/moordyn). MoorDyn-C is available in this repository. - - [X] Test in Linux with GCC - - [X] Test in Linux with Clang - - [X] Test in Windows with MinGW - - [X] Test in Windows with CLang (No Fortran) - - [X] Test in Windows with Visual Studio CE (No C++, no Fortran) - - [X] Make a windows installer (CMake + CPack + NSIS) - - [X] Upload the doxygen documentation somewhere (ideally in readthedocs) - - [X] Fix the SCUDS missiles bug - - [ ] Ask DualSphysics devs to join back the mainstream - - [X] pip package (with wheels?) +## Acknowledgments -## Aknowledgments - -Many thanks to all the team of the [National Renewable Energy Laboratory (NREL)](https://www.nrel.gov/): - [Matt Hall](http://matt-hall.ca/moordyn.html) + - Ryan Davies + - Andy Platt + - Stein Housner + - Lu Wang - Jason Jonkman -Thanks also to [CoreMarine](https://www.core-marine.com/) for the help with the -version 2 development: +[CoreMarine](https://www.core-marine.com/) [MoorDyn-C v2]: - Jose Luis Cercos-Pita - Aymeric Devulder - Elena Gridasova -We must also express our gratitude to some other developers that have -contributed +[Kelson Marine](https://kelsonmarine.com) [MoorDyn-C v2]: -From [Kelson Marine](https://kelsonmarine.com): - [David Joseph Anderson](https://davidjosephanderson.com/) - [Alex Kinley](https://github.com/AlexWKinley) diff --git a/docs/api_cpp.rst b/docs/api_cpp.rst deleted file mode 100644 index f21a584e..00000000 --- a/docs/api_cpp.rst +++ /dev/null @@ -1,10 +0,0 @@ -.. _api_cpp: - -C++ API -======= - - - - - - diff --git a/docs/compiling.rst b/docs/compiling.rst new file mode 100644 index 00000000..b7d29af4 --- /dev/null +++ b/docs/compiling.rst @@ -0,0 +1,392 @@ +.. _compiling: + +Compiling +========= + +MoorDyn is available in two forms, C and F, with two different versions, v1 and v2. V1 is +the original MoorDyn code, containing just point and line objects. V2 is the upgraded +version of MoorDyn v1. You can read more on the :ref:`home page `. It includes that +capability to simulate rigid bodies, non-linear tension, wave kinematics, bending +stiffness, and more. Further details can be found in the :ref:`theory section ` +and :ref:`structure section `. + +This page describes compiling options for MoorDyn-C. For MoorDyn-F (whether as part of +OpenFAST/Fast.Farm or with its own driver), please refer to the +`OpenFAST documentation `_. +MoorDyn-F in a standalone form can be compiled as moordyn_driver inside of the build folder. + +MoorDyn-C is available on `GitHub `_. The +latest version can be found in the V2 branch. MoorDyn-C v1 is currently in the master branch +of this repo, and it can be compiled using these :ref:`instructions `. + +The following sections describe how to install MoorDyn-C +:ref:`using the python wrapper `, how to +:ref:`compile all features `, and how to +:ref:`compile a simple library ` (version 1 method). These compile instructions +are broken down by operating system. + +.. Binaries and installers +.. ----------------------- + +.. .. _starting_binaries: + +.. Two different cases must be considered when installing binaries, the +.. :ref:`C/C++ libraries <_starting_binaries_lib>` (with the Fortran wrapper), and +.. the :ref:`Python package <_starting_binaries_python>`. + +.. C/C++ Library +.. ^^^^^^^^^^^^^ + +.. .. _starting_binaries_lib: + +.. To install the C/C++ library (and the Fortran wrappers), please clone the V2 repository. Pre-compiled releases can be found at +.. `Releases page `_. +.. Along this line you would probably want to consider either the latest version +.. identified with a number, or the one named "nightly". +.. The former is the latest stable version, while the latter is the latest version +.. uploaded to the repository, which tends to be a bit less stable. + +.. Once you already chosen a release, click on the assets and select the most +.. appropriate one for your platform. +.. More specifically, if you are in Windows you probably want to download and +.. execute Moordyn-X.Y.Z-win64.exe (with X.Y.Z replaced by the specific version), +.. in Linux you can download and execute Moordyn-X.Y.Z-Linux.sh and +.. in MacOS you can download and execute Moordyn-X.Y.Z-Darwin.sh. + +.. NOTE: When you download the self-extracting files for Linux and MacOS they +.. cannot be launched until you give them execution permissions. + +.. Now you can checkout +.. :ref:`how to integrate MoorDyn in your project <_starting_using>` below. + +Compile as a Simple Library +--------------------------- +.. _compile_simple: + +MoorDyn-C v2/v1 can be compiled as a simple library that can be run in the driver file. +The installation location is dependent on your operating system. This is the easiest way +to compile MoorDyn from the source code. This method does not compile any of the wrappers +that allow MoorDyn to be packaged into other codes. For an example in python of driving +MoorDyn compiled via this simple method see the :ref:`Python C API section `. + +Before you begin, make sure the following tools are installed, along with a C++ +compiler. On MacOS, the built in compiler is clang. + +* `Git `_ +* `CMake `_ + +Ensure you have the MoorDyn V2 source code. This can be obtained by cloning with git or +downloading from the GitHub repository. Next, navigate to the compile directory in +terminal that corresponds to your operating system: + +* `MoorDyn/compile/SO` for Linux +* `MoorDyn/compile/DYLIB` for MacOS +* `MoorDyn/compile/DLL` for Windows + +Once inside one of the three directories above, run the `make` command. MoorDyn +will compile into a collection of object files (.o) and the library file (.so, .dylib, +.dll). This library file is what the driver function will call. + +The above steps can also be used to compile MoorDyn v1. Run the make command from the +corresponding directory to compile the library: + +* `MoorDyn/compileSO` for Linux +* `MoorDyn/compileDYLIB` for MacOS +* `MoorDyn/compileDLL` for Windows + +Compile using CMake +------------------- + +.. _CMake_compile: + +The CMake installation of MoorDyn v2 installs all the libraries of MoorDyn as well and +builds all the wrappers. It is the most useful installation method but can run into +issues when compiling. Instructions for a simpler compile method that skips all the +additional features and just makes a MoorDyn library are available in the :ref:`simple +library section `. The CMake installation process is slightly different +depending on your operating system. Please see the corresponding section below: + +Windows +^^^^^^^ + +This section will show how to install Eigen3 and MoorDyn in the default folders +(C:\Program Files (x86)\Eigen3 and C:\Program Files (x86)\Moordyn) using CMake +This documentation assumes that you are building in an MSYS2 build environment. + +Install the following necessary tools: + +* `Git `_ +* `CMake `_ +* `MSYS2 `_ + +During the installation of Git, check that you install all the components +shown below, and add them to the PATH: + +.. figure:: win_git_install.png + :alt: Installing Git in Windows + + Recommended options while installing Git in Windows + +The same holds for CMake: + +.. figure:: win_cmake_install.png + :alt: Installing CMake in Windows + + Recommended options while installing CMake in Windows + +The installation of MSYS2 is well documented on +`the project web page `_. However, +additional tools are needed for this process. After running "MSYS MinGW 64-bit", type +the following command + +.. code-block:: bash + + pacman -S mingw-w64-x86_64-python-setuptools mingw-w64-x86_64-python-pip mingw64/mingw-w64-x86_64-make mingw-w64-x86_64-gcc mingw-w64-x86_64-gdb mingw-w64-x86_64-cmake + +Now we need to make the MinGW stack available across the whole system by adding +it to the PATH environment variable. +To achieve this, run "Edit the system environment variables" from the windows start menu and in the +Window the pops up, click on "Environment Variables..." +Double click on Path (in the System variables box), and add a new entry: +"C:\msys64\mingw64\bin" + +.. figure:: win_msys2_env.png + :alt: Adding MinGW to the PATH + + Adding MinGW to the PATH + +Now MoorDyn can be setup. First we must create a folder where we will +download and compile the MoorDyn code, for example C:\MoorDyn. +In this folder, right click inside and select "Git GUI Here". In +the Git window select "Clone Existing Repository". + +.. figure:: win_git_gui.png + :alt: Git GUI in Windows + + The Git GUI to clone repositories + +As a default, MoorDyn uses the Egien package that is internal in the source code. +If you would like to use an external copy of Eigen, please follow the instructions +in the :ref:`installing with external eigen ` note at this point. + +We will install MoorDyn following a very similar process. +Launch CMake again, and set "C:\MoorDyn\MoorDyn" in the source box and +"C:\MoorDyn\MoorDyn.build" in the binaries box, clicking "Configure" afterwards. +Select again the "MinGW Makefiles" for the generator. +When the configuration options appear, set CMAKE_BUILD_TYPE as "Release", and +enable FORTRAN_WRAPPER and PYTHON_WRAPPER: + +.. figure:: win_cmake_moordyn.png + :alt: Configuration options for MoorDyn + + Configuration options for MoorDyn + +You can also enable MATLAB_WRAPPER if you have MATLAB installed in your system. +We are ready, click "Configure" once more and then "Generate". + +Now go back to your Command Prompt from earlier (which has administrative rights), and +type the following commands: + +.. code-block:: bash + + cd C:\MoorDyn\MoorDyn.build + mingw32-make + mingw32-make install + +This will generate three libraries in the MoorDyn/build/source directory labeled +libmoordyn, libmoordyn.2, and libmoordyn.2.2. The first two are symbolic links to the +latter, setup that way for development purposes. In your project you should use +libmoordyn. + + +NOTE: If you want to generate a Windows installer, disable the PYTHON_WRAPPER +option and type + +.. code-block:: bash + + cd C:\MoorDyn\MoorDyn.build + mingw32-make + cpack -C Release + +NOTE: If you are working on a proxy serveryou may need to add the .crt file for your proxy +configuration to the folder ``C:/msys64/etc/pki/ca-trust/source/anchors`` or equivalent for your +system. + +NOTE: You may need to upgrade or install the build tool using pip + +.. code-block:: bash + + \/python.exe -m pip install --upgrade build + +NOTE: Installing External Eigen + +.. _external_eigen: + +To use an external copy of Eigen, ensure that the DEXTERNAL_EIGEN flag is turned on. +In the first box of the window that pops up set +"https://gitlab.com/libeigen/eigen.git", and in the second "C:\MoorDyn\eigen": + +.. figure:: win_git_eigen.png + :alt: Options to clone Eigen3 + + Cloning Eigen3 repository + +Press "Clone" and let Git download the repository. +Now you can repeat, setting "https://github.com/FloatingArrayDesign/MoorDyn.git", and +"C:\MoorDyn\MoorDyn" to download MoorDyn: + +.. figure:: win_git_moordyn.png + :alt: Options to clone MoorDyn + + Cloning MoorDyn repository + +Now, create two additional folders in C:\MoorDyn named eigen.build and +MoorDyn.build. These folders are where we will +actually build the source code we just cloned from GitHub. To do this, we'll +be using CMake as our build tool. + +Start CMake from the Windows Init menu. To prepare Eigen3 set +"C:\MoorDyn\eigen" in the source box and "C:\MoorDyn\eigen.build" in the +binaries box, and press "Configure". +The first time you configure a new project, CMake will ask you for the toolchain +to use. Select "MinGW Makefiles": + +.. figure:: win_cmake_selectcompiler.png + :alt: Selecting the MinGW generator + + Selecting the MinGW toolchain as generator + +Click on "Finish" and let CMake work. After a short while you will see a lot of +new red boxes. +Don't worry, these are not errors - they are red because they are new, and you +must specify some additional parameters for CMake. +Remember to set CMAKE_BUILD_TYPE as "Release" (unless you are working on the +source code, in which case you may wish to set the build type to "Debug" so +as to run the built program through a debugger). +It is also recommended to disable BUILD_TESTING, EIGEN_BUILD_DOC and +EIGEN_BUILD_TESTING: + +.. figure:: win_cmake_eigen.png + :alt: Configuration options for Eigen3 + + Configuration options for Eigen3 + +Press "Configure" once again, and then "Generate". Now you can close CMake. + +Now, since we are installing Eigen in C:\Program Files (x86)\Eigen3, we need +to execute a Command Prompt with administrative rights. +Search for "cmd" in the Windows Init menu and right click on +"Command Prompt", selecting Run as Administrator: + +.. figure:: win_cmd_admin.png + :alt: Launching an admin cmd + + Launching a Command Prompt with administrative rights + +Now you just need to type the following commands: + +.. code-block:: bash + + cd C:\MoorDyn\eigen.build + mingw32-make + mingw32-make install + +We will need to use cmd with administrative rights later on, so do not close it. + +Linux and Mac +^^^^^^^^^^^^^ + +To begin, use your package manager to install the following packages: + +* `Git `_ +* `CMake `_ +* `Python `_ +* `Eigen3 `_ + +In Linux you can use either `GCC `_ or +`Clang `_. On Mac OS, Clang is the built-in +compiler and any calls to GCC will be compiled with Clang unless setup otherwise. +The process to compile and install is the same no matter which compiler you have +installed. + +However, it should be noted that Clang does not provide a Fortran compiler. +To get Fortran support (for compiling MoorDyn-F and the MoorDyn-C Fortran wrapper) you +would need to install another compatible compiler (e.g. GCC). + +In this tutorial we are assuming you have administrative rights in your system, +although it is also possible to install MoorDyn and the wrappers in the user +space. The following commands need to be run from the terminal: + +First, download the MoorDyn source code from the repository using git: + +.. code-block:: bash + + cd $HOME + git clone https://github.com/FloatingArrayDesign/MoorDyn.git + cd MoorDyn + +Now, ask CMake to configure everything by typing + +.. code-block:: bash + + mkdir build + cd build + CMake -DCMAKE_INSTALL_PREFIX=/usr -DCMAKE_BUILD_TYPE=Release ../ + +If Eigen3 has not been installed, you can still configure +MoorDyn by adding the flag -DEXTERNAL_EIGEN=OFF to the above CMake command. In that +case you will only be able to use the :ref:`C API `, not the +C++ API. + +Finally, compile and install MoorDyn: + +.. code-block:: bash + + make -j + make install + +That will install the C and C++ headers in /usr/include/moordyn folder, the +library and the CMake configuration files (to allow other projects to easily +find and link it) in /usr/lib/ folder, and the Python wrapper in the appropriate +Python folder under /usr/lib/. It will also generate three libraries in the +MoorDyn/build/source directory labeled libmoordyn, libmoordyn.2, and libmoordyn.2.2. +The first two are symbolic links to the latter, set up that way for development purposes. +In your project you should use libmoordyn. + +If you want to use MoorDyn with the python wrapper, you need to run `pip install ./` in +the MoorDyn/build/wrappers/python/directory. This will install the MoorDyn module in your +python site packages. + +In case you do not have administrative privileges, you can install MoorDyn +anywhere else just changing the option -DCMAKE_INSTALL_PREFIX=/usr/local while +configuring CMake (running cmake ../ in the build folder). You will also want to +ask the Python wrapper to be installed in the user space with the option +-DPYTHON_WRAPPER_USERINSTALL=ON. + +If you have also installed the Fortran compiler, you can also compile and install the +Fortran wrapper by setting the option -DFORTRAN_WRAPPER=ON. Note that the Fortran wrapper +of MoorDyn-C is not the same as MoorDyn-F, it is intended for use in standalone Fortran +projects. Similarly if you have Matlab installed in your system, you can add the option +to install the Matlab wrapper -DMATLAB_WRAPPER=ON. + +Install as Python module +------------------------ + +.. _compile_python: + +MoorDyn-C is available as python module. This module is not always update with the most +recent version of MoorDyn-C on GitHub, so it is important to check the date of the last +release at https://pypi.org/project/moordyn/. To install, type + +.. code-block:: bash + + python -m pip install moordyn + +in your system terminal. Pip will take care of everything by you. + +**If you want to use the most up to date version of MoorDyn-C as a python module**, follow the +instructions in the :ref:`CMake compile section `. Once you have succesfully +compiled MoorDyn on your system, change to `MoorDyn/build/wrappers/python/` and execute the +following command `pip install ./`. This will build the python module locally from +the source code you have installed. In order to update this module in the future you will need +to update your local source code and follow the same steps above. diff --git a/docs/conf.py b/docs/conf.py index 5de6980a..9319686b 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -25,15 +25,13 @@ breathe_projects = {} os.makedirs("_build/doxygen", exist_ok=True) -if read_the_docs_build: - subprocess.call('doxygen', shell=True) -else: +if not read_the_docs_build: subprocess.call('make clean', shell=True) - subprocess.call('doxygen', shell=True) -os.makedirs("_build/doxygen/out", exist_ok=True) +subprocess.call('doxygen', shell=True) +os.makedirs("_build/doxygen/out/doxygen", exist_ok=True) if os.path.exists('_build/doxygen/out/doxygen/html'): - os.remove('_build/doxygen/out/doxygen/html') -shutil.rmtree('_build/doxygen/html', '_build/doxygen/out/doxygen') + shutil.rmtree('_build/doxygen/out/doxygen/html') +shutil.move('_build/doxygen/html', '_build/doxygen/out/doxygen/html') breathe_projects['MoorDyn'] = "_build/doxygen/xml" breathe_default_project = "MoorDyn" @@ -45,7 +43,7 @@ # -- Project information ----------------------------------------------------- project = 'MoorDyn' -copyright = '2021, National Renewable Energy Laboratory' +copyright = '2023, National Renewable Energy Laboratory' author = 'Matt Hall' # The full version, including alpha/beta/rc tags diff --git a/docs/coupling.rst b/docs/coupling.rst deleted file mode 100644 index d1a67deb..00000000 --- a/docs/coupling.rst +++ /dev/null @@ -1,498 +0,0 @@ -.. _coupling: - -Coupling with your own code -=========================== - -Established couplings ---------------------- - -FAST/OpenFAST -^^^^^^^^^^^^^ - -The Moordyn fortran incarnation, MoorDyn-F, is a core module within OpenFAST and -is available in -`OpenFAST releases `_. -Originally, it was coupled to a modified form of FAST v7. - -WEC-Sim -^^^^^^^ - -WEC-Sim is currently coupled with MoorDyn v1. Support for the current version, -MoorDyn v2, will be added in the future when the opportunity arises. - -DualSPHysics -^^^^^^^^^^^^ - -After developing a coupling with MoorDyn, the DualSPHysics team has forked it in -a seperate version called MoorDyn+, specifically dedicated to the coupling with -DualSPHysics. -MoorDyn v2 should on the other hand provide all the functionality required by -DualSPHysics, so DualSPHysics team will be queried to merge back on the -upstream. - -Basic coupling with MoorDyn ---------------------------- - -MoorDyn v2 can be used in several languages, at a high level of abstraction. It -is even possible to micromanage MoorDyn in a much lower level, using the -:ref:`C++ API `. - -Thus we are first discussing how to make the most basic coupling operations -with MoorDyn in each language. That will illustrate the similarities and -differences between languages. - -Afterwards, you can visit the :ref:`C API ` documentation to figure out -how to carry out more complex couplings. - -Note: You would probably read first the :ref:`"Getting Started" ` -documentation to learn more about how to install MoorDyn with support for each -language. - -Note: As it is documented on :ref:`the model structure `, several -entities can be fully controled by the user. -Namely points, rods and bodies. -To this end, the user should pass their positions and velocities when calling - -.. doxygenfunction:: MoorDyn_Step - -More specifically, the vectors **x** and **xd**, which are the states and the -variation rates respectively, should contain: - -- 6 components for each coupled body, containing the 3 spatial coordinates and - the 3 angles at the center of the body. -- 6 for each coupled rod, containing the 3 spatial coordinates of the first - point of the rod and the 3 components of the normalized director vector. -- 3 components for each coupled point, containing the spatial coordinates. - -They shall be provided on that specific order. Thus **xd** is just the time -derivative of **x**. - -For optimal results, **x** ( **t** ) and **xd** ( **t** + **dt** ) should be -provided. -However, with a small enough time step, **dt**, **xd** ( **t** ) can be safely -applied. - -C -^^^^^^ - -This is the primary language to use MoorDyn and it is always provided "out -of the box" when you install it. It is strongly recommended to use CMake to link -MoorDyn into your project (see :ref:`"Getting Started" `), although it -is not strictly required. For instance, if you installed it in the default -folder in Linux, you just need to add the flag "-lmoording" while linking -(either with GCC or CLang). - -We can start considering the following basic example, consisting in 3 lines -anchored at the sea bed, and connected to 3 coupled fairleads that we are -controlling: - -.. code-block:: c - - #include - #include - #include - - int main(int, char**) - { - int err; - MoorDyn system = MoorDyn_Create("Mooring/lines.txt"); - if (!system) - return 1; - - // 3 coupled points x 3 components per point = 9 DoF - double x[9], dx[9]; - memset(dx, 0.0, sizeof(double)); - // Get the initial positions from the system itself - for (unsigned int i = 0; i < 3; i++) { - // 4 = first fairlead id - MoorDynPoint point = MoorDyn_GetPoint(system, i + 4); - err = MoorDyn_GetConnectPos(point, x + 3 * i); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - } - - // Setup the initial condition - err = MoorDyn_Init(system, x, dx); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - - // Make the points move at 0.5 m/s to the positive x direction - for (unsigned int i = 0; i < 3; i++) - dx[3 * i] = 0.5; - double t = 0.0, dt = 0.5; - double f[9]; - err = MoorDyn_Step(system, x, dx, f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - - // Print the position and tension of the line nodes - unsigned int n_lines; - err = MoorDyn_GetNumberLines(system, &n_lines); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - for (unsigned int i = 0; i < n_lines; i++) { - const unsigned int line_id = i + 1; - printf("Line %u\n", line_id); - printf("=======\n"); - MoorDynLine line = MoorDyn_GetLine(system, line_id); - if (!line) { - MoorDyn_Close(system); - return 1; - } - unsigned int n_nodes; - err = MoorDyn_GetLineNumberNodes(line, &n_nodes); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - for (unsigned int j = 0; j < n_nodes; j++) { - printf(" node %u:\n", j); - double pos[3], ten[3]; - err = MoorDyn_GetLineNodePos(line, j, pos); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - printf(" pos = [%g, %g, %g]\n", pos[0], pos[1], pos[2]); - err = MoorDyn_GetLineNodeTen(line, j, ten); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return 1; - } - printf(" ten = [%g, %g, %g]\n", ten[0], ten[1], ten[2]); - } - } - - // Alright, time to finish! - err = MoorDyn_Close(system); - if (err != MOORDYN_SUCCESS) - return 1; - - return 0; - } - -In the example above everything starts calling - -.. doxygenfunction:: MoorDyn_Create - -and checking that it returned a non-NULL system. A NULL system would means that -there were some error building up the system. You can always know more about the -error in the information printed on the terminal. - -In C you always need to very explicit, while in C++ you can be a little bit more -abstract, not needing indeed to worry about the type names, i.e. you can do -something like this: - -.. code-block:: c - - auto system = MoorDyn_Create("Mooring/lines.txt"); - auto line = MoorDyn_GetLine(system, 1); - -Anyway, the next step is initializing the system, that is computing the -static solution. But to this end, we need first to know the positions of the -coupled fairleads, so we use the functions - -.. doxygenfunction:: MoorDyn_GetPoint -.. doxygenfunction:: MoorDyn_GetConnectPos - -As you can appreciate, the :ref:`C API ` is always returning either an -object or an error code: - -.. doxygengroup:: moordyn_errors_c - -Thus, you can always programatically check that everything properly worked. - -With the information of the initial positions of the fairlead, you can compute -the initial condition with the function - -.. doxygenfunction:: MoorDyn_Init - -Afterwards, you can start running MoorDyn by calling - -.. doxygenfunction:: MoorDyn_Step - -In this example, we are just calling it once. In a more complex application that -function will be called in a loop over time. Probably you need to feed back your -application with some information. In this example we are just collecting -information about the positions and forces at the line nodes, but you can -collect much more useful information. See the :ref:`C API `. - -Finally, it is very important that you always properly close the MoorDyn system, -so the allocated resources are released: - -.. doxygenfunction:: MoorDyn_Close - -Python -^^^^^^ - -You love Python! Who doesn't! Well, today it is your lucky day because MoorDyn -v2 is deploying its own Python wrapper. You can read :ref:`here ` how -to install MoorDyn to have Python support. - -Following you can find the equivalent example discussed above for C language, -this time developed in Python: - -.. code-block:: python - - import moordyn - - system = moordyn.Create("Mooring/lines.txt") - - # 3 coupled points x 3 components per point = 9 DoF - dx = [0] * 9 - # Get the initial positions from the system itself - x = [] - for i in range(3): - # 4 = first fairlead id - point = moordyn.GetPoint(system, i + 4) - x = x + moordyn.GetConnectPos(point) - - # Setup the initial condition - moordyn.Init(system, x, dx) - - # Make the points move at 0.5 m/s to the positive x direction - for i in range(3): - dx[3 * i] = 0.5 - t, dt = 0.0, 0.5 - f = moordyn.Step(system, x, dx, t, dt) - - # Print the position and tension of the line nodes - n_lines = moordyn.GetNumberLines(system) - for line_id in range(1, n_lines + 1): - print("Line {}".format(line_id)) - print("=======") - line = moordyn.GetLine(system, line_id) - n_nodes = moordyn.GetLineNumberNodes(line) - for node_id in range(n_nodes): - print(" node {}:".format(node_id)) - pos = moordyn.GetLineNodePos(line, node_id) - printf(" pos = {}".format(pos)) - ten = moordyn.GetLineNodeTen(line, node_id) - printf(" ten = {}".format(ten)) - } - } - - # Alright, time to finish! - moordyn.Close(system) - -That's all! You probably noticed that there are some differences with the C -code shown above, which makes it a bit simpler. -First, you obviously do not need to worry much about the variables typing. -Second, in Python the functions are not returning error codes. Instead, they are -triggering exceptions if errors are detected. Thus you can let Python to -stop the execution when an error is detected, but it is even better if you -enclose your code in a function within a try: - -.. code-block:: python - - import moordyn - - system = moordyn.Create("Mooring/lines.txt") - try: - your_coupling_code(system) - except Exception: - raise - finally: - moordyn.Close(system) - -So you can assert that the resources are always correctly released, no matter -if the code worked properly or exceptions were triggered. - -Fortran -^^^^^^^ - -If you are used to program in ancient languages, you are also welcome! Again, -you probably would check out :ref:`here ` how to install MoorDyn -with Fortran support, which is disable by default. - -The same example discussed above, for C and Python languages, can be considered -again, this time in Fortran: - -.. code-block:: fortran - - program main - use, intrinsic :: iso_fortran_env, only: real64 - use, intrinsic :: iso_c_binding, only: c_ptr, c_associated - use moordyn - - character(len=28) :: infile - real(real64), allocatable, target :: x(:) - real(real64), allocatable, target :: xd(:) - real(real64), allocatable, target :: f(:) - real(real64), allocatable, target :: r(:) - real(real64) :: t, dt - integer :: err, n_dof, n_points, i_point. n_lines, i_line, n_nodes, i_node - type(c_ptr) :: system, point, line - - infile = 'Mooring/lines.txt' - - system = MD_Create(infile) - if ( .not.c_associated(system) ) then - stop 1 - end if - - err = MD_NCoupledDOF( system, n_dof ) - if ( err /= MD_SUCESS ) then - stop 1 - elseif ( n_dof /= 9 ) then - print *,"3x3 = 9 DOFs were expected, not ", n_dof - end if - - allocate ( x(0:8) ) - allocate ( xd(0:8) ) - allocate ( f(0:8) ) - allocate ( r(0:2) ) - xd = 0.0 - f = 0.0 - - ! Get the positions from the points - err = MD_GetNumberPoints( system, n_points ) - if ( err /= MD_SUCESS ) then - stop 1 - elseif ( n_points /= 6 ) then - print *,"6 points were expected, not ", n_points - end if - do i_point = 1, 3 - point = MD_GetPoint( system, i_point + 3 ) - if ( .not.c_associated(point) ) then - stop 1 - end if - err = MD_GetConnectPos( point, r ) - if ( err /= MD_SUCESS ) then - stop 1 - end if - do j = 1, 3 - x(3 * i + j) = r(j) - end do - end do - - err = MD_Init(system, x, xd) - if ( err /= MD_SUCESS ) then - stop 1 - end if - - t = 0 - dt = 0.5 - err = MD_Step(system, x, xd, f, t, dt) - if ( err /= MD_SUCESS ) then - stop 1 - end if - - ! Print the position and tension of the line nodes - err = MD_GetNumberLines(system, n_lines) - if ( err /= MD_SUCESS ) then - stop 1 - end if - do i_line = 1, n_lines - print *,"Line ", i_line - print *, "=======" - line = MD_GetLine(system, i_line) - err = MD_GetLineNumberNodes(line, n_nodes) - do i_node = 0, n_nodes - 1 - print *," node ", i_node, ":" - err = MD_GetLineNodePos(line, i_node, r) - print *," pos = ", r - err = MD_GetLineNodeTen(line, i_node, r) - print *," ten = ", r - end do - end do - - err = MD_Close(system) - if ( err /= MD_SUCESS ) then - stop 1 - end if - - deallocate ( x ) - deallocate ( xd ) - deallocate ( f ) - deallocate ( r ) - - end program main - -It is again very similar to the C code, although the functions have a different -prefix. On top of that, all the objects (the simulator, the points, the -lines...) take the type type(c_ptr), from the iso_c_binding module. The rest of -differences are just caused by the language. - -Matlab -^^^^^^ - -Woha! You are still using Matlab! You really need to consider moving to Python -soon. Yesterday would be a good moment to do that... - -Anyway, MoorDyn might also works with Matlab for your entire convenience. -Unfortunately, it is not currently possible to automate the Matlab wrapper -building, so no binaries will be provided, so you must compile and install -MoorDyn with that support by yourself. Please, check out the -:ref:`getting started documenation ` to know how to get the Matlab -wrapper working. - -Considering the same example above, the resulting Matlab code would look like -the following: - -.. code-block:: matlab - - system = MoorDynM_Create('Mooring/lines.txt'); - - %% 3 coupled points x 3 components per point = 9 DoF - x = zeros(9,1); - dx = zeros(9,1); - %% Get the initial positions from the system itself - for i=1:3 - %% 4 = first fairlead id - point = MoorDynM_GetPoint(system, i + 3); - x(1 + 3 * (i - 1):3 * i) = MoorDynM_GetConnectPos(point); - end - - %% Setup the initial condition - MoorDynM_Init(system, x, dx); - - %% Make the points move at 0.5 m/s to the positive x direction - for i=1:3 - dx(1 + 3 * (i - 1)) = 0.5; - end - t = 0.0; - dt = 0.5; - [t, f] = MoorDynM_Step(system, x, dx, t, dt); - - %% Print the position and tension of the line nodes - n_lines = MoorDynM_GetNumberLines(system); - for line_id=1:n_lines - line_id - line = MoorDynM_GetLine(system, line_id); - n_nodes = MoorDynM_GetLineNumberNodes(line); - for node_id=1:n_nodes - node_id - pos = MoorDynM_GetLineNodePos(line, node_id - 1); - pos - ten = MoorDynM_GetLineNodeTen(line, node_id - 1); - ten - end - end - - %% Alright, time to finish! - MoorDynM_Close(system); - -As it was already mentioned, it is pretty similar to Python. The functions are -not returning error codes, but the queried information. -However, the functions are triggering exceptions, that can be catched by Matlab. -Again, that feature shall be used at least to grant that MoorDynM_Close() is -called even if the excution fails. - -Simulink -^^^^^^^^ - -MoorDyn can be used with Simulink (and SimMechanics) models. The challenge is in -supporting MoorDyn's loose-coupling approach where it expects to be called for -sequential time steps and never for correction steps that might repeat a time -step. -A pulse/time-triggering block can be used in Simulink to ensure MoorDyn is -called correctly. An example of this can be seen in WEC-Sim. diff --git a/docs/drivers.rst b/docs/drivers.rst new file mode 100644 index 00000000..4b9667a4 --- /dev/null +++ b/docs/drivers.rst @@ -0,0 +1,796 @@ +MoorDyn Wrappers and Drivers +============================ + +.. _drivers: + +The following discussion explains how to drive MoorDyn-C using a driver function. +MoorDyn-F contains a driver script that has a :ref:`separate input file ` +and MoorDyn-F compiles in OpenFAST as moordyn_driver. The MoorDyn-F driver follows all +the same principles as the examples below. See :ref:`compiling ` and +:ref:`inputs ` sections for instructions on how to use the MoorDyn-F driver. + +Currently MoorDyn-C v2 can be used in Python, C/C++, Fortran, and Matlab. You can +read more on how to install MoorDyn for each different language in +the :ref:`compiling documentation `. + +All the wrappers are built off :ref:`the C API ` which can be found in the +MoorDyn2.h file, so it is the best place to find a list of available functions. + +For MoorDyn to be run, it needs a driver script written in one of the compatible +languages using the corresponding wrapper. MoorDyn-C v2 allows for multiple instances of +MoorDyn to be run simultaneously, while MoorDyn-F v2 and MoorDyn-C/F v1 only allow once +instance at a time. Any driver function will call at least the following MoorDyn +functions: + +* Create (MoorDyn-C v2 only) +* Initialize +* Step +* Close + +The initialize function takes the state vectors at time 0 and sets up MoorDyn for a time +series simulation. It will also find the steady state of the system if the input file +calls for it. The step function takes the state vectors (r - positions and +rd - velocities) at a given time, the time, and the time step size. The step function +needs to be called for each time step in your timeseries. The close function clears up +memory. For both the step and the initialize functions, the input state vector size needs +to correspond to the DOF of the coupled object or objects. The input vector is 1D with a +length of: degree of freedom of coupled object * number of coupled objects. If you have +multiple different types of coupled objects then the order in the state vector is +body (6 DOF), rod (6 DOF for cantilevered/coupled, 3 DOF for pinned), and then +points (3 DOF). The same order applies for the state derivative input vector, with each +value being the time derivative of the respective value. The degrees of freedom are as +follows: + + - Bodies and cantilevered/coupled Rods: cartesian positions followed by the Euler angles + relative to the non-inertial reference frame. + - Pinned rods: Euler angles relative to the non-inertial reference frame. + - Coupled points: cartesian positions relative to the non-inertial reference frame. + + +For example, the r vector for a coupled body and coupled point would be: + + [ x1, y1, z1, roll1, pitch1, yaw1, x2, y2, z2 ] + +Driving MoorDyn-C v1 is a similar process as MoorDyn v2. MoorDyn-C v1 has no built in +couplings and needs to be driven based on the C API in the MoorDyn.h file. An example on +how to do this in python is provided at the end of the +:ref:`python section `. + +Note: the dt value that you give to the step function needs to be the same value that you specify as dtM in the input file. + +MoorDyn-C Coupling +------------------ + +MoorDyn-C can be compiled as a dynamically linked library with C bindings or a more +sophisticated API functions and wrappers, making it accessible from a wide range of +programming languages. + +Python +^^^^^^ +.. _python_wrapper: + +If you have pip installed MoorDyn then you are good to go. If not, see the +:ref:`compiling section ` for instructions on how to pip install the python +module, how to compile the python module locally (CMake compile method), or how to +compile a library that is called from python (simple library compile method). + +We can start considering the following example, consisting of 3 lines +anchored at the seabed connected to 3 coupled fairleads that we +control: + +.. code-block:: python + + import moordyn + + system = moordyn.Create("Mooring/lines.txt") + + # 3 coupled points x 3 components per point = 9 DoF + dx = [0] * 9 + # Get the initial positions from the system itself + x = [] + for i in range(3): + # 4 = first fairlead id + point = moordyn.GetPoint(system, i + 4) + x = x + moordyn.GetPointPos(point) + + # Setup the initial condition + moordyn.Init(system, x, dx) + + # Make the points move at 0.5 m/s to the positive x direction + for i in range(3): + dx[3 * i] = 0.5 + t, dt = 0.0, 0.5 + f = moordyn.Step(system, x, dx, t, dt) + + # Print the position and tension of the line nodes + n_lines = moordyn.GetNumberLines(system) + for line_id in range(1, n_lines + 1): + print("Line {}".format(line_id)) + print("=======") + line = moordyn.GetLine(system, line_id) + n_nodes = moordyn.GetLineNumberNodes(line) + for node_id in range(n_nodes): + print(" node {}:".format(node_id)) + pos = moordyn.GetLineNodePos(line, node_id) + printf(" pos = {}".format(pos)) + ten = moordyn.GetLineNodeTen(line, node_id) + printf(" ten = {}".format(ten)) + } + } + + # Alright, time to finish! + moordyn.Close(system) + +In Python the functions trigger exceptions if errors are detected. Python can stop +execution when an error is detected using a try: + +.. code-block:: python + + import moordyn + + system = moordyn.Create("Mooring/lines.txt") + try: + your_coupling_code(system) + except Exception: + raise + finally: + moordyn.Close(system) + +So you can assert that the resources are always correctly released, no matter +if the code worked properly or exceptions were triggered. + +MoorDyn-C v1 and v2 can also be run in python using the C API with the use of the ctypes +library. Below is an example of this on MacOS with MoorDyn compiled as a +:ref:`simple library `, assuming a stationary coupled body: + +.. code-block:: python + + import ctypes + import numpy as np + + rootname = 'lines' + extension = '.txt' + path = 'Mooring/' + tMax = 25.0 + dtM = 0.001 + time = np.arange(0, tMax, dtM) + vector_size = 6 # 6DOF coupled object + size = (len(time), vector_size) + + x = np.zeros(size) + xd = np.zeros(size) + + dylib_path = 'MoorDyn/compile/DYLIB/libmoordyn2.dylib' + filename = path+rootname+extension + + # Double vector pointer data type + double_p = ctypes.POINTER(ctypes.c_double) + + # -------------------- load the MoorDyn DYLIB --------------------- + # Make MoorDyn function prototypes and parameter lists (remember, first entry is return type, rest are args) + MDInitProto = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.POINTER(ctypes.c_double*vector_size), ctypes.POINTER(ctypes.c_double*vector_size), ctypes.c_char_p) #need to add filename option here, maybe this c_char works? #need to determine char size + MDStepProto = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.POINTER(ctypes.c_double*vector_size), ctypes.POINTER(ctypes.c_double*vector_size), ctypes.POINTER(ctypes.c_double*vector_size), double_p, double_p) + MDClosProto = ctypes.CFUNCTYPE(ctypes.c_int) + + MDInitParams = (1, "x"), (1, "xd"), (1, "infilename") # 1 flag is input, 2 flag is output + MDStepParams = (1, "x"), (1, "xd"), (2, "f"), (1, "t"), (1, "dtC") + + MDdylib = ctypes.CDLL(dylib_path) #load moordyn dylib + + MDInit = MDInitProto(("MoorDynInit", MDdylib), MDInitParams) + MDStep = MDStepProto(("MoorDynStep", MDdylib), MDStepParams) + MDClose= MDClosProto(("MoorDynClose", MDdylib)) + + # ------------------------ run MoorDyn --------------------------- + # initialize some arrays for communicating with MoorDyn + t = double_p() # pointer to t + + # parameters + dtC = ctypes.pointer(ctypes.c_double(dtM)) + infile = ctypes.c_char_p(bytes(filename, encoding='utf8')) + + # initialize MoorDyn at origin + MDInit((x[0,:]).ctypes.data_as(ctypes.POINTER(ctypes.c_double*vector_size)),(xd[0,:]).ctypes.data_as(ctypes.POINTER(ctypes.c_double*vector_size)),infile) + print("MoorDyn initialized - now performing calls to MoorDynStep...") + + # loop through coupling time steps + for i in range(len(time)): + t = ctypes.pointer(ctypes.c_double(time[i])) + MDStep((x[i,:]).ctypes.data_as(ctypes.POINTER(ctypes.c_double*vector_size)), (xd[i,:]).ctypes.data_as(ctypes.POINTER(ctypes.c_double*vector_size)), t, dtC) + print("Succesffuly simulated for {} seconds - now closing MoorDyn...".format(tMax)) + + # close MoorDyn simulation (clean up the internal memory, hopefully) when finished + MDClose() + +Notes on the Python C API: + +- The C API includes support for the v1 and v2 API. This example uses the v1 API + (MoorDyn.h in v1 and v2). A similar approach could be taken for the v2 API found in the + :ref:`C API section ` and also in the MoorDyn2.h file. +- The available functions can be found in the MoorDyn.h files. + - These functions are declared in the following way: + + .. code-block:: python + + functionPROTO = ctypes.CFUNCTYPE(ctypes.c_int, ) + functionParams = (1, ""), (2, "") # a tuple of tuples where each item in the function inputs list is given an input (1) or output (2) flag + function = functionPROTO(("", MDdylib), functionParams) + +- Using this method does not call the create function because the v1 API does not allow + for simultaneous MoorDyn instances. +- The initialize function is MDInit. +- MoorDyn functions require C data types as inputs. + +C/C++ +^^^^^^ + +The easiest way to link MoorDyn to your C/C++ project is using CMake. The following +Is a code snippet where MoorDyn is included in a project with only a C source +code file named example.c: + +.. code-block:: cmake + + CMake_minimum_required (VERSION 3.10) + project (myproject) + + find_package (MoorDyn REQUIRED) + + add_executable (example example.c) + target_link_libraries (example MoorDyn::moordyn) + +CMake itself will take care of everything. In the example.c file you only +need to include the MoorDyn2.h header and start using the :ref:`C API `, +as it is discussed in the :ref:`coupling documentation `. + +.. code-block:: c + + #include + + int main(int, char**) + { + MoorDyn system = MoorDyn_Create("Mooring/lines.txt"); + MoorDyn_Close(system); + } + +The same CMake code for C is equally valid for C++. In your C++ +code you must remember to start by including the MoorDyn configuration header and then +the main header, i.e. + +.. code-block:: cpp + + #include + #include + + int main(int, char**) + { + auto system = new moordyn::MoorDyn("Mooring/lines.txt"); + delete system; + } + +It is recommended to use CMake to link +MoorDyn into your project (see :ref:`"Compiling" `), although it +is not strictly required. For instance, if you installed it in the default +folder in Linux, you just need to add the flag "-lmoording" while linking +(either with GCC or CLang). + +Below you can find the equivalent example discussed above for the Moordyn python module, +this time developed in C: + + +.. code-block:: c + + #include + #include + #include + + int main(int, char**) + { + int err; + MoorDyn system = MoorDyn_Create("Mooring/lines.txt"); + if (!system) + return 1; + + // 3 coupled points x 3 components per point = 9 DoF + double x[9], dx[9]; + memset(dx, 0.0, sizeof(double)); + // Get the initial positions from the system itself + for (unsigned int i = 0; i < 3; i++) { + // 4 = first fairlead id + MoorDynPoint point = MoorDyn_GetPoint(system, i + 4); + err = MoorDyn_GetPointPos(point, x + 3 * i); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + } + + // Setup the initial condition + err = MoorDyn_Init(system, x, dx); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + + // Make the points move at 0.5 m/s to the positive x direction + for (unsigned int i = 0; i < 3; i++) + dx[3 * i] = 0.5; + double t = 0.0, dt = 0.5; + double f[9]; + err = MoorDyn_Step(system, x, dx, f, &t, &dt); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + + // Print the position and tension of the line nodes + unsigned int n_lines; + err = MoorDyn_GetNumberLines(system, &n_lines); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + for (unsigned int i = 0; i < n_lines; i++) { + const unsigned int line_id = i + 1; + printf("Line %u\n", line_id); + printf("=======\n"); + MoorDynLine line = MoorDyn_GetLine(system, line_id); + if (!line) { + MoorDyn_Close(system); + return 1; + } + unsigned int n_nodes; + err = MoorDyn_GetLineNumberNodes(line, &n_nodes); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + for (unsigned int j = 0; j < n_nodes; j++) { + printf(" node %u:\n", j); + double pos[3], ten[3]; + err = MoorDyn_GetLineNodePos(line, j, pos); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + printf(" pos = [%g, %g, %g]\n", pos[0], pos[1], pos[2]); + err = MoorDyn_GetLineNodeTen(line, j, ten); + if (err != MOORDYN_SUCCESS) { + MoorDyn_Close(system); + return 1; + } + printf(" ten = [%g, %g, %g]\n", ten[0], ten[1], ten[2]); + } + } + + // Alright, time to finish! + err = MoorDyn_Close(system); + if (err != MOORDYN_SUCCESS) + return 1; + + return 0; + } + +In the example above everything starts calling + +.. doxygenfunction:: MoorDyn_Create + +and checking that it returned a non-NULL system. A NULL system would mean that +there were an error building up the system. You can learn more about the +error in the information printed on the terminal. + +In C requires explicit type names, while in C++ you can be more +abstract, i.e. you can do something like this: + +.. code-block:: c + + auto system = MoorDyn_Create("Mooring/lines.txt"); + auto line = MoorDyn_GetLine(system, 1); + +The next step is initializing the system, which computes the +static solution if the TmaxIC flag in the options section is greater than 0. This +requires the position of the coupled fairleads. + +.. doxygenfunction:: MoorDyn_GetPoint +.. doxygenfunction:: MoorDyn_GetPointPos + +The :ref:`C API ` always returns either an +object or an error code: + +.. doxygengroup:: moordyn_errors_c + +Thus, you can always check that everything properly worked. + +With the information of the initial positions of the fairlead, you can initialize MoorDyn: + +.. doxygenfunction:: MoorDyn_Init + +Afterwards you can run MoorDyn by calling: + +.. doxygenfunction:: MoorDyn_Step + +In this example, we are just calling it once. In a more complex application the +function will be called in a loop over a time series. In the API there are a number of +functions that can return information at each timestep that can be implemented in more +complex drivers. The full list of functions can be found in the +:ref:`C API section `. + +It is important to close the MoorDyn system, so that the allocated resources are released: + +.. doxygenfunction:: MoorDyn_Close + +Fortran +^^^^^^^ +This is not to be confused with MoorDyn-F, which relies on modules within the openFAST +library. MoorDyn-F when compiled includes a driver function with its own driver input +file. + +This coupling packages MoorDyn-C to be used in standalone Fortran projects. +Linking the Fortran wrapper of MoorDyn-C is almost the same as linking the C +library. For instance, if you have a Fortran project consisting of a single +source code file, example.f90, then you can compile the driver with the +following CMake code: + +.. code-block:: CMake + + CMake_minimum_required (VERSION 3.10) + project (myproject) + + find_package (MoorDyn REQUIRED) + + add_executable (example example.f90) + target_link_libraries (example MoorDyn::MoorDyn-F) + +Please, note that now you are linking against MoorDyn::MoorDyn-F (not the same as +the MoorDyn-F in OpenFAST). + +Here is the same example from above, displayed in Fortran: + +.. code-block:: fortran + + program main + use, intrinsic :: iso_fortran_env, only: real64 + use, intrinsic :: iso_c_binding, only: c_ptr, c_associated + use moordyn + + character(len=28) :: infile + real(real64), allocatable, target :: x(:) + real(real64), allocatable, target :: xd(:) + real(real64), allocatable, target :: f(:) + real(real64), allocatable, target :: r(:) + real(real64) :: t, dt + integer :: err, n_dof, n_points, i_point, n_lines, i_line, n_nodes, i_node + type(c_ptr) :: system, point, line + + infile = 'Mooring/lines.txt' + + system = MD_Create(infile) + if ( .not.c_associated(system) ) then + stop 1 + end if + + err = MD_NCoupledDOF( system, n_dof ) + if ( err /= MD_SUCESS ) then + stop 1 + elseif ( n_dof /= 9 ) then + print *,"3x3 = 9 DOFs were expected, not ", n_dof + end if + + allocate ( x(0:8) ) + allocate ( xd(0:8) ) + allocate ( f(0:8) ) + allocate ( r(0:2) ) + xd = 0.0 + f = 0.0 + + ! Get the positions from the points + err = MD_GetNumberPoints( system, n_points ) + if ( err /= MD_SUCESS ) then + stop 1 + elseif ( n_points /= 6 ) then + print *,"6 points were expected, not ", n_points + end if + do i_point = 1, 3 + point = MD_GetPoint( system, i_point + 3 ) + if ( .not.c_associated(point) ) then + stop 1 + end if + err = MD_GetPointPos( point, r ) + if ( err /= MD_SUCESS ) then + stop 1 + end if + do j = 1, 3 + x(3 * i + j) = r(j) + end do + end do + + err = MD_Init(system, x, xd) + if ( err /= MD_SUCESS ) then + stop 1 + end if + + t = 0 + dt = 0.5 + err = MD_Step(system, x, xd, f, t, dt) + if ( err /= MD_SUCESS ) then + stop 1 + end if + + ! Print the position and tension of the line nodes + err = MD_GetNumberLines(system, n_lines) + if ( err /= MD_SUCESS ) then + stop 1 + end if + do i_line = 1, n_lines + print *,"Line ", i_line + print *, "=======" + line = MD_GetLine(system, i_line) + err = MD_GetLineNumberNodes(line, n_nodes) + do i_node = 0, n_nodes - 1 + print *," node ", i_node, ":" + err = MD_GetLineNodePos(line, i_node, r) + print *," pos = ", r + err = MD_GetLineNodeTen(line, i_node, r) + print *," ten = ", r + end do + end do + + err = MD_Close(system) + if ( err /= MD_SUCESS ) then + stop 1 + end if + + deallocate ( x ) + deallocate ( xd ) + deallocate ( f ) + deallocate ( r ) + + end program main + +It is very similar to the C code, although the functions have a different +prefix. All the objects (the simulator, the points, the +lines...) take the type type(c_ptr), from the iso_c_binding module. The rest of +the differences are just language syntax. + +MATLAB +^^^^^^ +To use this feature, insure you used the CMake compile method with the MATLAB install +turned on. Using MoorDyn in MATLAB is similar to using it in Python. However, in +MATLAB you must manually add the folder where the wrapper files are located to the path. +To achieve this, in MATLAB go to the HOME menu, section ENVIRONMENT, and click on +"Set Path". In the window appearing click on "Add Folder...", and set the folder that +contains the contents of MoorDyn/build/wrappers/matlab/, which by default is: + +* C:\Program Files (x86)\MoorDyn\bin in Windows +* /usr/lib in Linux and MacOS + +After that you are good to go! + +Considering the same example above, the resulting Matlab code would look like +the following: + +.. code-block:: matlab + + system = MoorDynM_Create('Mooring/lines.txt'); + + %% 3 coupled points x 3 components per point = 9 DoF + x = zeros(9,1); + dx = zeros(9,1); + %% Get the initial positions from the system itself + for i=1:3 + %% 4 = first fairlead id + point = MoorDynM_GetPoint(system, i + 3); + x(1 + 3 * (i - 1):3 * i) = MoorDynM_GetPointPos(point); + end + + %% Setup the initial condition + MoorDynM_Init(system, x, dx); + + %% Make the points move at 0.5 m/s to the positive x direction + for i=1:3 + dx(1 + 3 * (i - 1)) = 0.5; + end + t = 0.0; + dt = 0.5; + [t, f] = MoorDynM_Step(system, x, dx, t, dt); + + %% Print the position and tension of the line nodes + n_lines = MoorDynM_GetNumberLines(system); + for line_id=1:n_lines + line_id + line = MoorDynM_GetLine(system, line_id); + n_nodes = MoorDynM_GetLineNumberNodes(line); + for node_id=1:n_nodes + node_id + pos = MoorDynM_GetLineNodePos(line, node_id - 1); + pos + ten = MoorDynM_GetLineNodeTen(line, node_id - 1); + ten + end + end + + %% Alright, time to finish! + MoorDynM_Close(system); + +It is fairly similar to Python. The functions do +not return error codes, only the queried information. +However, the functions do trigger exceptions that can be caught by Matlab. +That feature should be used so that MoorDynM_Close() is +called even if the execution fails. + +Simulink +^^^^^^^^ +MoorDyn can be used with Simulink (and SimMechanics) models. The challenge is in +supporting MoorDyn's loose-coupling approach where it expects to be called for +sequential time steps and never for correction steps that might repeat a time +step. +A pulse/time-triggering block can be used in Simulink to ensure MoorDyn is +called correctly. An example of this can be seen in WEC-Sim. + + +Established couplings +--------------------- +.. _coupling: + +MoorDyn-F with FAST.Farm +^^^^^^^^^^^^^^^^^^^^^^^^ + +In FAST.Farm, a new ability to use MoorDyn at the array level to simulate shared mooring +systems has been developed. It is described in +https://doi.org/10.1016/j.apenergy.2022.120513. An example of the full input file setup +can be found at https://github.com/FloatingArrayDesign/FASTFarm_10Turbines_Shared. + +General Organization +"""""""""""""""""""" + +The regular ability for each OpenFAST instance to have its own MoorDyn simulation is +unchanged in FAST.Farm. This ability can be used for any non-shared mooring lines in all +cases. To enable simulation of shared mooring lines, which are coupled with multiple +turbines, an additional farm-level MoorDyn instance has been added. This MoorDyn instance +is not associated with any turbine but instead is called at a higher level by FAST.Farm. +Attachments to different turbines within this farm-level MoorDyn instance are handled by +specifying "TurbineN" as the type for any connections that are attached to a turbine, +where "N" is the specific turbine number as listed in the FAST.Farm input file. + + +MoorDyn Input File +"""""""""""""""""" + +The following input file excerpt shows how connections can be specified as attached to +specific turbines (turbines 3 and 4 in this example). When a connection has "TurbineN" +as its type, it acts similarly to a "Vessel" type, where the X/Y/Z inputs specify the +relative location of the fairlead on the platform. In the farm-level MoorDyn input file, +"Vessel" connection types cannot be used because it is ambiguous which turbine they +attach to. + +.. code-block:: none + :emphasize-lines: 5,6,12 + + ----------------------- POINTS ---------------------------------------------- + ID Attachment X Y Z Mass Volume CdA Ca + (-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) + 1 Turbine3 10.0 0 -10.00 0 0 0 0 + 3 Turbine4 -10.0 0 -10.00 0 0 0 0 + 2 Fixed 267.0 80 -70.00 0 0 0 0 + -------------------------- LINES -------------------------------------------- + ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs + + (-) (-) (-) (-) (m) (-) (-) + 1 sharedchain 1 2 300.0 20 p + 2 anchorchain 1 3 300.0 20 p + + +In this example, Line 1 is a shared mooring line and Line 2 is an anchored mooring line +that has a fairlead connection in common with the shared line. Individual mooring systems +can be modeled in the farm-level MoorDyn instance as well. + + + +FAST.Farm Input File +"""""""""""""""""""" + +In the branch of FAST.Farm the supports shared mooring capabilities, several additional +lines have been added to the FAST.Farm primary input file. These are highlighted in the +example input file excerpt below + + +.. code-block:: none + :emphasize-lines: 9,10,13,14,15 + + FAST.Farm v1.10.* INPUT FILE + Sample FAST.Farm input file + --- SIMULATION CONTROL --- + False Echo Echo input data to .ech? (flag) + FATAL AbortLevel Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} + 2000.0 TMax Total run time (s) [>=0.0] + False UseSC Use a super controller? (flag) + 1 Mod_AmbWind Ambient wind model (-) (switch) {1: high-fidelity precursor in VTK format, 2: one InflowWind module, 3: multiple instances of InflowWind module} + 2 Mod_WaveField Wave field handling (-) (switch) {1: use individual HydroDyn inputs without adjustment, 2: adjust wave phases based on turbine offsets from farm origin} + 3 Mod_SharedMooring Shared mooring system model (-) (switch) {0: None, 3: MoorDyn} + --- SUPER CONTROLLER --- [used only for UseSC=True] + "SC_DLL.dll" SC_FileName Name/location of the dynamic library {.dll [Windows] or .so [Linux]} containing the Super Controller algorithms (quoated string) + --- SHARED MOORING SYSTEM --- [used only for Mod_SharedMooring > 0] + "FarmMoorDyn.dat" FarmMoorDyn-File Name of file containing shared mooring system input parameters (quoted string) [used only when Mod_SharedMooring > 0] + 0.01 DT_Mooring Time step for farm-level mooring coupling with each turbine (s) [used only when Mod_SharedMooring > 0] + --- AMBIENT WIND: PRECURSOR IN VTK FORMAT --- [used only for Mod_AmbWind=1] + 2.0 DT_Low-VTK Time step for low -resolution wind data input files ; will be used as the global FAST.Farm time step (s) [>0.0] + 0.3333333 DT_High-VTK Time step for high-resolution wind data input files (s) [>0.0] + "Y:\Wind\Public\Projects\Projects F\FAST.Farm\AmbWind\steady" WindFilePath Path name to VTK wind data files from precursor (string) + False ChkWndFiles Check all the ambient wind files for data consistency? (flag) + --- AMBIENT WIND: INFLOWWIND MODULE --- [used only for Mod_AmbWind=2 or 3] + 2.0 DT_Low Time step for low -resolution wind data interpolation; will be used as the global FAST.Farm time step (s) [>0.0] + +Model Stability and Segment Damping +""""""""""""""""""""""""""""""""""" + +Two of the trickier input parameters are the internal damping (BA) for each line type, +and the mooring simulation time step (dtM). Both relate to the discretization of the +lines. The highest axial vibration mode of the lumped-mass cable representation would be +when adjacent nodes oscillate out of phase with each other, as depicted below. + +In this mode, the midpoint of each segment would not move. The motion of each node can +then be characterized by mass-spring-damper values of + +.. math:: + + m=w L/N \; c=4NBA/L \; k=4NEA/L. + +The natural frequency of this mode is then + +.. math:: + + \omega_n=\sqrt{k/m}=2/l \sqrt{EA/w}=2N/L \sqrt{EA/w} + +and the damping ratio, ζ, is related to the internal damping coefficient, BA, by + +.. math:: + + \zeta =c/c_{crit} = B/l \sqrt{A/Ew} = NBA/L \sqrt{(1/EAw} \;\; BA=\zeta \frac{L}{N}\sqrt{EAw}. + +The line dynamics frequencies of interest should be lower than ω_n in order to be +resolved by the model. Accordingly, line dynamics at ω_n, which are likely to be +dominated by the artificial resonance created by the discretization, can be damped out +without necessarily impacting the line dynamics of interest. This is advisable because +the resonances at ω_n can have a large impact on the results. To damp out the segment +vibrations, a damping ratio approaching the critical value (ζ=1) is recommended. Care +should be taken to ensure that the line dynamics of interest are not affected. + +To simplify things, a desired line segment damping ratio can be specified in the input +file. This is done by entering the negative of the desired damping ratio in the BA/-zeta +field of the Line Types section. A negative value here signals MoorDyn to interpret it as +a desired damping ratio and then calculate the damping coefficient (BA) for each mooring +line that will give every line segment that damping ratio (accounting for possible +differences in segment length between lines). + +Note that the damping ratio is with respect to the critical damping of each segment along +a mooring line, not with respect to the line as a whole or the floating platform as a +whole. It is just a way of letting MoorDyn calculate the damping coefficient +automatically from the perspective of damping non-physical segment resonances. If the +model is set up right, this damping can have a negligible contribution to the overall +damping provided by the moorings on the floating platform. However, if the damping +contribution of the mooring lines on the floating platform is supposed to be significant, +it is best to (1) set the BA value directly to ensure that the expected damping is +provided and then (2) adjust the number of segments per line to whatever provides +adequate numerical stability. + +FAST/OpenFAST +^^^^^^^^^^^^^ + +MoorDyn-F, is a core module within OpenFAST and +is available in +`OpenFAST releases `_. +Originally, it was coupled to a modified form of FAST v7. + +WEC-Sim +^^^^^^^ + +WEC-Sim is currently coupled with MoorDyn v1. Support for the current version of +MoorDyn-C v2, is in the process of being developed. The WEC-Sim source code can be found +`here `_. + +DualSPHysics +^^^^^^^^^^^^ + +After developing a coupling with MoorDyn, the DualSPHysics team has forked it in +a seperate version called MoorDyn+, specifically dedicated to the coupling with +DualSPHysics. + diff --git a/docs/index.rst b/docs/index.rst index 912875be..b3a97bfa 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -3,63 +3,102 @@ You can adapt this file completely to your liking, but it should at least contain the root `toctree` directive. -MoorDyn v2 - Lumped-Mass Mooring Dynamics -========================================= +MoorDyn - Lumped-Mass Mooring Dynamics +====================================== +.. _index: .. toctree:: - :maxdepth: 2 + :maxdepth: 5 :hidden: - starting + compiling + drivers + inputs structure - usage - theory - coupling api_c - api_cpp - wrappers troubleshooting waterkinematics + theory +Welcome to MoorDyn's online documentation. MoorDyn is a simple, efficient, +and versatile mooring system dynamics model designed to work in concert +with other simulation tools. It is based on a +lumped-mass discretization of a mooring line's dynamics, and adds point-mass +and rigid-body objects to enable simulation of a wide variety of mooring and +cabling arrangements. Hydrodynamics are included using a version of the +Morison equation, and there is support for wave loads on surface-piercing +cylinders. -Welcome to MoorDyn's (UNDER CONSTRUCTION) online documentation. -See the pages on this site for information about the operation, -:ref:`usage `, and :ref:`theory ` of MoorDyn. +The pages on this site provide information +about :ref:`compiling `, MoorDyn's :ref:`input files `, +how to :ref:`drive a simulation `, how MoorDyn is :ref:`structured `, +and its :ref:`theory `. MoorDyn is available in multiple forms, +which are outlined below. Note: This documentation is meant for users, a -`Doxygen documentation <./doxygen/index.html>`_ has been deployed for the +`Doxygen documentation <./doxygen/html/index.html>`_ has been deployed for the developers. About MoorDyn ------------- -MoorDyn is a simple, efficient, and versatile mooring system dynamics model -designed to work in concert with other simulation tools. It is based on a -lumped-mass discretization of a mooring line's dynamics, and adds point-mass -and rigid-body objects to enable simulation of a wide variety of mooring and -cabling arrangements. Hydrodynamics are included using a version of the Morison -equation. +MoorDyn was originally developed in 2014 as a C++ library that could be +easily coupled with other codes (such as WEC-Sim and DualSPHysics). Soon +after, a second form was created as a module of the floating wind turbine +simulator FAST, which is a FORTRAN code following the `FAST Modularization +Framework `_. Both forms of +MoorDyn have the same underlying physics modes but are different in how they +can be used with other codes. An effort is made to keep the physics modeling +in both forms synchronized when new capabilities get added to one of them. +To distinguish, the two forms can be referred to as MoorDyn-C and +MoorDyn-F. + +Beginning in 2019, a set of new features was added to MoorDyn including +rigid bodies and support for wave loading at the free surface. This set of +new capabilities is referred to as Version 2 (v2). Version 2 has been +realized in both C++ and FORTRAN forms of MoorDyn. The MoorDyn source code +is available on GitHub. The MoorDyn-C v1 and v2 is +`here `_ and +the MoorDyn-F code is included in the `OpenFAST repository +`_. + +As of version 2, the input file formats of MoorDyn-C and MoorDyn-F are +identical. We recommend using MoorDyn v2 for all applications unless +you have a specific reason to use MoorDyn v1. + +MoorDyn-C v2 contains wrappers that make it available as a python library and allow +it to be easily packaged into other languages. It is released under the `3-clause BSD +license `_. + +This website serves as a public-facing guide for MoorDyn in all forms. It +focuses on MoorDyn’s principles of operation, setup of the input files, +common problems, etc. It will also have guidance for coupling with +MoorDyn in standalone form, as well as a guide for the API. For +information about use of MoorDyn-F in the larger context of OpenFAST +simulations, refer also to the `OpenFAST documentation `_. + +In this documentation, when MoorDyn is mentioned without specifying C or +F then it is applicable to both. If a version number is not stated, +then version 2 is assumed. -There are two main forms. The standalone form is coded in C++, is very easy to -couple with a variety of models and programming languages, and is released under -the `3-clause BSD license `_. This -is the original form of the model, and it is used with WEC-Sim, DualSPHysics, -and various :ref:`wrappers in different languages `. -The other form is MoorDyn-F, a full rewrite of MoorDyn in FORTRAN that follows -the FAST Modularization Framework. This form is a core module in the OpenFAST -floating wind turbine simulator. +Ways of Using MoorDyn: +---------------------- -Both forms of MoorDyn have the same underlying physics model, and nearly -identical input file formats. +As a mooring dynamics library, MoorDyn needs some other program +to run it. This other “driver” program can be a simple script that moves +(or holds still) the ends of the mooring lines, or a full dynamics model +for other parts of a floating system. -This website focuses though on the standalone form. +MoorDyn-F is usually run as part of the full OpenFAST simulation model, +driven by the OpenFAST or FAST.Farm “glue code”. It also comes with a +dedicated “MoorDyn driver ” code that allows MoorDyn-F to run in +isolation with only an input file of floating platform motions. Instructions +for the use of the MoorDyn-F driver can be found :ref:`here `. -For information about use of MoorDyn-F in the larger context of OpenFAST -simulations, refer also to the -`OpenFAST documentation `_. +MoorDyn-C is designed for coupling with a wide number of codes. Some +couplings already exist and can be found :ref:`here ` (e.g. WEC-Sim +and DualSPHysics). For Coupling with other codes or more manual driving of +MoorDyn from your own script, several APIs, wrappers, and example driver +scripts are available :ref:`here `. -The MoorDyn source code is available on GitHub. The standalone C++ code is -`here `_ and -code of MoorDyn-F in FORTRAN is available within the -`OpenFAST repository `_. diff --git a/docs/inputs.rst b/docs/inputs.rst new file mode 100644 index 00000000..0bcef1fc --- /dev/null +++ b/docs/inputs.rst @@ -0,0 +1,911 @@ +Input Files +=========== +.. _inputs: + +.. + customize code highlight color through "hll" span css + +.. raw:: html + + + + + +.. role:: fast +.. role:: stnd + +The V1 Input File +----------------- +.. _v1_inputs: + +MoorDyn v1 uses a plain-text input file for its description of the mooring system as well as +simulation settings. This file is divided into sections identified by header lines. The exact +whitespace and alignment of the lines of the file is not important, so long as values are +separated by at least one space. + +Most of the sections are set up to contain a table of input information. The table begins with two +preset lines that contain the column names and the corresponding units. These lines are followed by +any number of lines containing the entries in that section's table of inputs. + +Front matter +^^^^^^^^^^^^ + +The first lines of the input file until a section heading is provided are reserved for free-form +user input, for labeling the input file, writing notes, etc. + +.. code-block:: none + :emphasize-lines: 2 + + MoorDyn input file... + MoorDyn v1 sample input file + True Echo echo the input file data (flag) + +Line Types +^^^^^^^^^^ + +The Line Types section of the file contains one or more definitions of physical line properties and +four hydrodynamic coefficients. + +.. code-block:: none + :emphasize-lines: 2 + + ------------------------- LINE TYPES -------------------------------------------------- + LineType Diam MassDen EA BA/-zeta Can Cat Cdn Cdt + (-) (m) (kg/m) (N) (Pa-s/-) (-) (-) (-) (-) + nylon 0.124 13.76 2515288.0 -0.8 1.0 0.0 1.6 0.05 + +The columns in order are as follows: + + - Name – an identifier word for the line type + - 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) + - 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 – see Section 4.1 for more information) + - Can – transverse added mass coefficient (with respect to line displacement) + - Cat – tangential added mass coefficient (with respect to line displacement) + - Cdn – transverse drag coefficient (with respect to frontal area, d*l) + - Cdt – tangential drag coefficient (with respect to surface area, π*d*l) + +Point Properties +^^^^^^^^^^^^^^^^^^^^^ + +The Point Properties section defines the point node points which mooring lines can be connected to. + +.. code-block:: none + :emphasize-lines: 2 + + ----------------------- POINT PROPERTIES ---------------------------------------------- + Node Type X Y Z M V FX FY FZ CdA CA + (-) (-) (m) (m) (m) (kg) (m^3) (kN) (kN) (kN) (m^2) (-) + 1 Vessel 0.0 0 -10.00 0 0 0 0 0 0 0 + 2 Fixed 267.0 0 -70.00 0 0 0 0 0 0 0 + 3 Connect 0.0 0 -10.00 0 0 0 0 0 0 0 + +The columns are as follows: + + - Node – the ID number of the point (must be sequential starting with 1) + - Type – one of “Fixed”, “Vessel”, or “Connect”, as described :ref:`here ` + - X, Y, Z – Coordinates of the point (relative to inertial reference frame if “fixed” or “point”, + relative to platform reference frame if “vessel”). In the case of “point” nodes, it is simply + an initial guess for position before MoorDyn calculates the equilibrium initial position.(m) + - M – node mass in the case of clump weights (kg) + - V – node displacement in the case of floats (m^3) + - FX, FY, FZ – any steady external forces applied to the node (N) + - CdA – product of drag coefficient and projected area (assumed constant in all directions) to + calculate a drag force for the node (m^2) + - Ca – added mass coefficient used along with V to calculate added mass on node + +Lines list +^^^^^^^^^^ + +The Line Properties section defines each uniform-property section of mooring line to be simulated. + +.. code-block:: none + :emphasize-lines: 2 + + -------------------------- LINE PROPERTIES ------------------------------------------------- + Line LineType UnstrLen NumSegs NodeAnch NodeFair Flags/Outputs + (-) (-) (m) (-) (-) (-) (-) + 1 nylon 300.0 50 2 1 p + 2 nylon 300.0 50 4 3 p + 3 nylon 300.0 50 6 5 p + +The columns are as follows: + + - Line - the ID number of the line (must be sequential starting with 1) + - LineType - a string matching a Line Dictionary entry, specifying which physical properties it + uses + - 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) + - NodeAnch - the ID number of the point that the first (anchor) end of the line is attached to + - NodeFair - the ID number of the point that the final (fairlead) end of the line is attached to + - flags/outputs - 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 +activating a given output property. A placeholder character such as “-” should be used if no +outputs are wanted. Eight output properties are currently possible: + + - p – node positions + - v – node velocities + - U – wave velocities at each node + - D – hydrodynamic drag force at each node + - t – tension force at each segment + - c – internal damping force at each segment + - s – strain of each segment + - d – rate of strain of each segment + +For example, outputting node positions and segment tensions could be achieved by writing “pt” for +this last column. These outputs will go to a dedicated output file for each line only. For +sending values to the global output file, use the Outputs section instead. + + +Options +^^^^^^^ + +The Solver Options section can contain any number of optional settings for the overall model, +including seabed properties, initial condition (IC) generation settings, and the time step size. + +.. code-block:: none + + -------------------------- SOLVER OPTIONS--------------------------------------------------- + 0.001 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 + 0.001 ICthresh - threshold for IC convergence + 0 ICTmax - threshold for IC convergence (set to zero for debugging) + +Any of these lines can be omitted, in which case default values will be used (shown in +parenthesis). As such, they are all optional settings, although some of them (such as time step +size) often need to be set by the user for proper operation. The list of possible options (with any +default value provided in parentheses) is: + + - dtM (0.001) – desired mooring model time step (s) + - g (9.8) – gravitational constant (m/s^2) + - rhoW (1025.0)– water density (kg/m^3) + - WtrDpth (0.0) – water depth (m) + - SeafloorFile (none) – Relative path of a 3D Seafloor file + - kBot (3.0e6) – bottom stiffness constant (Pa/m) + - cBot (3.0e5)– bottom damping constant (Pa-s/m) + - dtIC (1.0)– period for analyzing convergence of dynamic relaxation IC generation (s) + - TmaxIC (120.0) – maximum simulation time to allow for IC generation without convergence (s) + - CdScaleIC (5.0) – factor by which to scale drag coefficients to accelerate convergence of IC + generation (-) + - ThreshIC (0.001) – convergence threshold for IC generation, acceptable relative difference + between three successive fairlead tension measurements (-) + +The bottom contact parameters, kBot and cBot, result in a pressure which is then applied to the +cross-sectional area (d*l) of each contacting line segment to give a resulting vertical contact +force for each segment. + +Outputs +^^^^^^^ + +The Outputs section is used to specify general outputs, which are written to the main MoorDyn +output file. + +.. code-block:: none + :emphasize-lines: 8 + + ---------------------- OUTPUTS ----------------------------------------- + FairTen1 + FairTen2 + AnchTen1 + Con2px + Con2py + Con2Fz + END + ------------------------- need this line ------------------------------------- + +Each output channel name should have its own line. There are keywords for fairlead and anchor +tensions of a given line: fairten# and anchten#, where # is the line number. There is also a +flexible naming system for outputting other quantities. There are currently five supported types of +output quantities: + + - pX, pY , pZ – x/y/z coordinate (m) + - vX, vY, vZ – velocity (m/s) + - aX, aY, aZ – acceleration (m/s^2) + - T or Ten – tension (N) + - fX, fY, fZ – net force in x/y/z direction (N) + +These can be produced at a point object, denoted by the prefix Con#, where # is the point number. +Or, they can be produced at a node along a line, denoted by the prefix L#N@, where # is the line +number and @ is the number of the node along that line. For example, + + - Con3vY outputs the point 3 y velocity, + - L2N4pX outputs the line 2, node 4 x position. + +The V2 Input File +----------------- +.. _v2_inputs: + +MoorDyn v2 uses a standardized plain-text input file for its description of the +mooring system and simulation settings that has some important additions and +changes from V1. + +Most helpfully, this new format is identical between C++ and FORTRAN versions of +MoorDyn, and it is designed to support future capability enhancements without +requiring changes. + +This file is divided into sections, some of which are optional. Each section is +identified (and detected) by a header line consisting of a key phrase (e.g. Line +Types) surrounded by dashes. While a couple sections are optional, the order of +the sections cannot be changed. The exact whitespace and alignment of the lines of the file is not +important, as long as values are separated by at least one space. However, every column must have +a value. + +To successfully run a simulation, MoorDyn requires at least one line. If you are aiming to simulate +a system with no lines, the best approach is to create a short taut vertical line stretched between +two fixed points located far from where your system is located. + +Most of the sections are set up to contain a table of input information. These +tables begin with two preset lines that contain the column names and the +corresponding units. These lines are followed by any number of lines containing +the entries in that section's table of inputs. + +Front matter +^^^^^^^^^^^^ + +The first lines of the input file are reserved for free-form user input, for +labeling the input file, writing notes, etc. +There is not a limit on the number of lines you can write here. + +.. code-block:: none + + --------------------- MoorDyn Input File ------------------------------------ + MoorDyn v2 sample input file + +Line Types +^^^^^^^^^^ + +This section is required and describes the list of mooring line properties +that will be used in the simulation + +.. code-block:: none + + ---------------------- LINE TYPES ----------------------------------- + TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx + (name) (m) (kg/m) (N) (N-s/-) (N-m^2) (-) (-) (-) (-) + Chain 0.1 150.0 1e8 -1 0 2.3 1 1.0 0.5 + +The columns in order are as follows: + + - TypeName – an identifier word for the line type + - 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) + - 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) + - EI – the line bent stiffness, product of elasticity modulus and inertia of the cross-sectional + area (N) + - Cd – transverse drag coefficient (with respect to frontal area, d*l) + - Ca – transverse added mass coefficient (with respect to line displacement) + - CdAx – tangential drag coefficient (with respect to surface area, π*d*l) + - CaAx – tangential added mass coefficient (with respect to line displacement) + +Non-linear values for the stiffness (EA), internal damping (BA/-zeta) and bent +stiffness (EI) are accepted. +For this, a file name can be provided (located in the same folder as the +main MoorDyn input file) instead of a number. +Such file is a tabulated file with a time column and a data column, separated by a blank space. +The columns that should be provided for each non-linear magnitude are the following: + + - Stiffness: Strain rate - EA/Stretching rate (N) + - Internal damping: Curvature - EI/Curvature (N-m^2) + - Bent stiffness: Stretching rate - Damping coefficient/Stretching rate (N-s^2/s) + +Rod Types +^^^^^^^^^ + +This section (required if there are any rod objects) describes the list of rod property sets that +will be used in the simulation. + +.. code-block:: none + + ---------------------- ROD TYPES ------------------------------------ + TypeName Diam Mass/m Cd Ca CdEnd CaEnd + (name) (m) (kg/m) (-) (-) (-) (-) + Buoy 10 1.0e3 0.6 1.0 1.2 1.0 + +The columns are as follows: + - TypeName – an identifier word for the rod type + - Diam – the cylinder diameter (m) + - Mass/m – the mass per unit length of the rod (kg/m) + - Cd – the normal rod drag coefficient (with respect to the central axis of the rod) + - Ca – the normal rod added mass coefficient (with respect to the central axis of the rod) + - CdEnd – the axial drag coefficient of the rod + - CaEnd – the axial added mass coefficient of the rod + +Bodies list +^^^^^^^^^^^ + +This section (optional) describes the 6DOF body objects to be simulated. + +.. code-block:: none + + ---------------------- BODIES --------------------------------------- + ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca* + (#) (word) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) + 1 coupled 0 0 0 0 0 0 0 0 0 0 0 0 + +The columns are as follows: + - ID – the ID number of the Body (must be sequential starting with 1) + - Attachment – one of “Fixed”, “Vessel”, “Free”, etc, as described :ref:`here ` + - X0/Y0/Z0 – Coordinates of the body relative to the inertial reference frame. Note that bodies + must have Z0 <= 0 (m) + - r0/p0/y0 – Orientation of the body relative to the inertial reference frame in Euler angles + (deg) + - Mass – Body mass not including attached rods and points. Typically used to account for above + surface mass such as a turbine (kg) + - CG – Body center of gravity. If one value given, it is along the Z axis. To specify a coordinate + point, the XYZ values are listed separated by | with no spaces (m) + - I – Body moment of inertia diagonals for the 3x3 inertia matrix. If one value given, it is used + for all three values. To specify different values, the inputs are listed separated by | with no + spaces (kg-m^2) + - Volume – The body displaced volume used in buoyancy calculations excluding attached rod and + point volume contributions (m^3) + - CdA – The body drag coefficient + - Ca – The body added mass coefficient + +Rods list +^^^^^^^^^ + +This section (optional) describes the rigid Rod objects + +.. code-block:: none + + ---------------------- RODS ---------------------------------------- + ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs + (#) (name) (word/ID) (m) (m) (m) (m) (m) (m) (-) (-) + 1 Can Body1 0 0 2 0 0 15 8 p + 2 Can Body1Pinned 2 0 2 5 0 15 8 p + +The columns are as follows: + - ID – the ID number of the Rod (must be sequential starting with 1) + - RodType + - Attachment – one of “Fixed”, “Vessel”, “Pinned”, etc, as described :ref:`here ` + - Xa/Ya/Za – Coordinates of the A end of the relative to the inertial reference frame (m) + - Xb/Yb/Zb – Coordinates of the A end of the relative to the inertial reference frame (m) + - NumSegs - how many segments the rod is discretized into (it will have NumSegs+1 nodes total, + including its two end nodes) + - RodOutputs - any data to be output in a dedicated output file for the rod. + +This last 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. Eight output properties are currently possible: + + - p – node positions + - v – node velocities + - U – wave velocities at each node + - D – hydrodynamic drag force at each node + - t – tension force at each segment + - c – internal damping force at each segment + - s – strain of each segment + - d – rate of strain of each segment + +For example, outputting node positions and segment tensions could be achieved by writing “pt” for +this last column. These outputs will go to a dedicated output file for each rod. For sending +values to the global output file, use the Outputs section instead. + +Points list +^^^^^^^^^^^ + +This section (optional) describes the Point objects + +.. code-block:: none + + ---------------------- POINTS --------------------------------------- + ID Attachment X Y Z Mass Volume CdA Ca + (#) (word/ID) (m) (m) (m) (kg) (mˆ3) (m^2) (-) + 1 Fixed -500 0 -150 0 0 0 0 + 2 Coupled 0 0 -9 0 0 0 0 + 3 Body2 0 0 1.0 0 0 0 0 + +The columns are as follows: + + - ID – the ID number of the point (must be sequential starting with 1) + - Attachment – one of “Fixed”, “Vessel”, “Connect”, etc, as described :ref:`here ` + - X, Y, Z – Coordinates of the point (relative to inertial reference frame if “fixed/point/free”, + or relative to platform/body reference frame if “vessel” or “body#”). In the case of + “point/free” nodes, it is simply an initial guess for position before MoorDyn calculates the + equilibrium initial position. (m) + - Mass – node mass in the case of clump weights (kg) + - Volume – node displacement in the case of floats (m^3) + - CdA – product of drag coefficient and projected area (assumed constant in all directions) to + calculate a drag force for the node (m^2) + - Ca – added mass coefficient used along with V to calculate added mass on node + +Lines list +^^^^^^^^^^ + +This section (required) describes the Line objects, typically used for mooring lines or dynamic +power cables. + +.. code-block:: none + + ---------------------- LINES ---------------------------------------- + ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs + (#) (name) (ID) (ID) (m) (-) (-) + 1 Chain 1 2 300 20 p + +The columns are as follows: + + - ID - the ID number of the line (must be sequential starting with 1) + - LineType - a string matching a Line Dictionary entry, specifying which physical properties it + uses + - AttachA - the ID number of the point (or Rod end) that the first (anchor) end of the line is + attached to. For lines connected to rod ends, the value should be R#A or R#B where # is the rod + number and A/B refer to which end of the rod the line is connected to. + - AttachB - the ID number of the point (or Rod end) that the final (fairlead) end of the line is + attached to. For lines connected to rod ends, the value should be R#A or R#B where # is the rod + number and A/B refer to which end of the rod the line is connected to. + - 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. + +This last 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. Eight output properties are currently possible: + + - p – node positions + - v – node velocities + - U – wave velocities at each node + - D – hydrodynamic drag force at each node + - t – tension force at each segment + - c – internal damping force at each segment + - s – strain of each segment + - d – rate of strain of each segment + +For example, outputting node positions and segment tensions could be achieved by writing “pt” for +this last column. These outputs will go to a dedicated output file for each line only. For +sending values to the global output file, use the Outputs section instead. + +Failure +^^^^^^^ + +This section (optional) describes the failure conditions of the system. + +.. code-block:: none + + ---------------------- FAILURE ---------------------- + Node Line(s) FailTime FailTen + () (,) (s or 0) (N or 0) + any 1,2,3,4 0 1200e3 + 3 1 0 1200e3 + R1a 1,2,3 12 0 + + +Control (MoorDyn-F only) +^^^^^^^^^^^^^^^^^^^^^^^^ + +This section (optional) is only available for MoorDyn-F and describes the control channels of the +system. + +.. code-block:: none + + ---------------------- CONTROL ---------------------- + ChannelID Line(s) + () (,) + 1 1,2,3,4 + 2 5 + +Options +^^^^^^^ + +This section (required) describes the simulation options + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + 0.002 dtM time step to use in mooring integration (s) + 3000000 kbot bottom stiffness (Pa/m) + 300000 cbot bottom damping (Pa-s/m) + 0.5 dtIC time interval for analyzing convergence during IC gen (s) + 10 TmaxIC max time for ic gen (s) + 0.001 threshIC threshold for IC convergence (-) + +Any of these lines can be omitted, in which case default values will be used (shown in +parentheses). Default value swith a C or an F indicates which version has that as the default. +As such, they are all optional settings, although some of them (such as time step +size) often needs to be set by the user for proper operation. The list of possible options is: + + - writeLog (0 C, -1 F): If >0 a log file is written recording information. The bigger the number + the more verbose. Please, be mindful that big values would critically reduce the performance! + - dtM (0.001 C): The time step (s). In MoorDyn-F if this is left blank it defaults to the + :ref:`driver file ` dtC value. + - tScheme (RK2): The time integrator. It should be one of Euler, Heun, RK2, RK4, AB2, AB3, AB4, + BEuler2, BEuler3, BEuler4, BEuler5, Midpoint2, Midpoint3, Midpoint4, Midpoint5. RK stands for + Runge-Kutta while AB stands for Adams-Bashforth + - g (9.81): The gravity acceleration (m/s^2) + - rho (1025): The water density (kg/m^3) + - WtrDpth (0.0): The water depth (m). In MoorDyn-F the bathymetry file path can be inputted here. + - kBot (3.0e6): The bottom stiffness (Pa/m) + - cBot (3.0e5): The bottom damping (Pa-s/m) + - dtIC (1.0 C, 2.0 F): The time lapse between convergency checks during the initial condition + computation (s) + - TmaxIC (120.0 C, 60.0 F): The maximum simulation time to run in order to find a stationary + initial condition (s) + - CdScaleIC (5.0 C, 4.0 F): The damping scale factor during the initial condition computation + - threshIC (0.001 C, 0.01 F): The lines tension maximum relative error to consider that the + initial condition have converged + - WaveKin (0): The waves model to use. 0 = none, 1 = waves externally driven, 2 = FFT in a regular + grid, 3 = kinematics in a regular grid, 7 = Wave Component Summing. Details on these flags can + be found :ref:`here `. + - dtWave (0.25): The time step to evaluate the waves, only for wave grid (WaveKin = 3) (s) + - Currents (0): The currents model to use. 0 = none, 1 = steady in a regular grid, 2 = dynamic in + a regular grid, 3 = WIP, 4 = WIP, 5 = 4D Current Grid. Details on these flags can + be found :ref:`here `. + - UnifyCurrentGrid (1): When both waves and currents are defined using a grid method, you may want + to pre-combine those grids into a single grid that stores the summed wave and current kinematics. + When this option is 1 the wave grid points get the interpolated current grid values added to + them. When this option is 0 the wave grid and current grid are kept separate + - WriteUnits (1): 0 to do not write the units header on the output files, 1 otherwise + - FrictionCoefficient (0.0): The seabed friction coefficient + - FricDamp (200.0): The seabed friction damping, to scale from no friction at null velocity to + full friction when the velocity is large + - StatDynFricScale (1.0): Rate between Static and Dynamic friction coefficients + - dtOut (0.0): Time step size to be written to output files. A value of zero will use dtM as a + step size (s) + - Seafloor file: A path to the :ref:`bathymetry file ` + +In MoorDyn-F, the default values for g, rhoW, and WtrDpth are the values provided by FAST, so it is +recommended to not use custom values for the sake of consistency. + +The following MoorDyn-C options are not supported by MoorDyn-F: + + - WaveKin & Currents: In MoorDyn-F waves and currents are combined into a single option called + WaterKin which takes a file path as a value and defaults to an empty string (i.e. no WaterKin). + The file provided should be formatted as described in the additional MoorDyn inputs + :ref:`section `. Further details on its implementation can be found in the + :ref:`water kinematics section `. + - tScheme: MoorDyn-F only uses the Runge-Kutta 2 method for time integration. + - dtWave: MoorDyn-F uses the dtWave value from the :ref:`water kinematics file `. + - unifyCurrentGrid: Not available in MoorDyn-F because currents and waves are handled in the same + input file. + - writeUnits: Units are always written to output file headers + - Seafloor file: MoorDyn-F accepts a bathymetry file path as an alternative to a number in the + WtrDpth option + - FrictionCoefficient: MoorDyn-F contains friction coefficients for lines in both the axial and + transverse directions while MoorDyn-C only has a general seafloor contact coefficient of friction + - FricDamp: Same as CV in MoorDyn-F. + - StatDynFricScale: Same as MC in MoorDyn-F. + +The following options from MoorDyn-F are not supported by MoorDyn-C: + + - WaterKin (Null): Path to the water kinematics file. Allows the inputs of wave and current + coefficients formatted as described in the :ref:`water kinematics file `. + - MU_KT (0.0): Transverse line coefficient of friction. + - MU_KA (0.0): Axial line coefficient of friction. + - MC (1.0): Same as StatDynFricScale in MoorDyn-C. + - CV (200.0): Same as FricDamp in MoorDyn-C. + +Outputs +^^^^^^^ + +This section (optional) lists any specific output channels to be written in the main output file. +All output flags need to be all caps. The section needs to end with another header-style line (as +shown below) for MoorDyn to know when to stop reading inputs. + +.. code-block:: none + + ---------------------- OUTPUTS ----------------------------------------- + BODY1PX + BODY1PY + BODY1PZ + BODY1ROLL + BODY1PITCH + FAIRTEN1 + FAIRTEN2 + FAIRTEN3 + ANCHTEN1 + ANCHTEN2 + ANCHTEN3 + END + ------------------------- need this line ------------------------------------- + + +The avaible output flags are decribed in the table below: + +========= ============================ ========= =========== ============== =========== =========== +Suffix Description Units Line Rod Body Point +========= ============================ ========= =========== ============== =========== =========== +PX/PY/PZ Position [m] Node Object/Node Object Object +RX/RY Roll, Pitch [deg] Object Object +RZ Yaw [deg] Object +VX/VY/VZ Velocity [m/s] Node Object/Node Object Object +RVX/RVY Rotational Velocity X/Y [deg/s] Object Object +RVZ Rotational Velocity Z [deg/s] Object +AX/AY/AZ Acceleration [m/s^2] Object Object Object +RAX/RAY Rotational acceleration X/Y [deg/s^2] Object Object +RAZ Rotational acceleration Z [deg/s^2] Object +FX/FY/FZ Force [N] Node(1) Object/Node(2) Object Object +MX/MY/MZ Moments [Nm] Object Object +TEN/T Net force [N] Node(3) Object Object +TENA/B Net force on ends [N] Object Object +SUB Submergence (frac of length) [frac] Object +========= ============================ ========= =========== ============== =========== =========== + +When a node number is specified, the output pertains to that node and its kinematics or associated +loads. When no node number is specified, the output pertains to the object as a whole and the +values are of the object’s reference point (about the reference point for rotations). Reference +Points: + +- Rods: End A (Node 0) + - No z rotations for rods (rotations along axis of rod negligible) + - A vertical rod with end A below end B is defined as a rod with zero rotation. ROD#RX and ROD#RY + will be zero for this case. +- Bodies: Center of Mass +- Points: Center of Mass +- Lines: End A (Node 0) + +Footnotes: + +- The tension on the Line n fairlead can be output with the FAIRTEN[n] flag (see examples above) +- The tension on the Line n anchor can be output with the ANCHTEN[n] flag (see examples above) +- Object indicates output is for whole object, Node indicates output is for node of object +- Coupled/fixed bodies and points will output acceleration 0 because no forces are calculated +- There are a couple additional outputs left over from OpenFAST conventions that don’t follow the + same format: FairTen and AnchTen. FairTen[n] is the same as Line[n]TenB. For example, the + fairlead tension of line 1 would be FAIRTEN1 or LINE1TENB. + +1. Line node forces: Line node forces output the net force on the node, which includes the tension + vectors of the adjacent segments plus the weight, buoyancy, seabed-contact, and hydrodynamic + forces on the node. +2. Rod node forces: The rod node forces contain weight, buoyancy (from pressure integration over + the surface), and hydrodynamics. No internal structural forces are accounted for in rod force + outputs. +3. Line node tension: Node tensions for lines output different values depending on whether it is an + end node or an internal node. End nodes output the net force on the end node, i.e. the magnitude + of the Fnet vector. Internal nodes output the average tension from the segments on either side + of the node. + +Additional MoorDyn Files +------------------------ + +MoorDyn-F Driver Input File +^^^^^^^^^^^^^^^^^^^^^^^^^^^ +.. _MDF_driver_in: + +The MoorDyn-F driver that compiles with Openfast requires its own input file (located in the same +with the following format in addition to the MoorDyn input file). The exact whitespace and +alignment of the lines of the file is not important, so long as values are separated by at least +one space. + +.. code-block:: none + + MoorDyn driver input file + another comment line + FALSE Echo - Echo the input file data (flag) + ---------------------- ENVIRONMENTAL CONDITIONS ------------------------------- + 9.80665 Gravity - Gravity (m/s^2) + 1025.0 rhoW - Water density (kg/m^3) + 75.0 WtrDpth - Water depth (m) + ---------------------- MOORDYN ------------------------------------------------ + "" MDInputFile - Primary MoorDyn input file name + (quoted string) + "Mooring/F" OutRootName - The name which prefixes all MoorDyn + generated files (quoted string) + 10.0 TMax - Number of time steps in the simulations (-) + 0.001 dtC - TimeInterval for the simulation (sec) + 0 InputsMode - MoorDyn coupled object inputs (0: all inputs + are zero for every timestep, 1: time-series inputs) (switch) + "PtfmMotions.dat" InputsFile - Filename for the MoorDyn inputs file for when + InputsMod = 1 (quoted string) + 0 NumTurbines - Number of wind turbines (-) [>=1 to use + FAST.Farm mode. 0 to use OpenFAST mode.] + ---------------------- Initial Positions -------------------------------------- + ref_X ref_Y surge_init sway_init heave_init roll_init pitch_init yaw_init + (m) (m) (m) (m) (m) (rad) (rad) (rad) + [followed by MAX(1,NumTurbines) rows of data] + 0 0 0.0 0.0 0.0 0.0 0.0 0.0 + END of driver input file + +If InputsMode is set to 1, MoorDyn-F will require a platform motions time series dataset of the +coupled object movements. For a single coupled body, the order of the data columns would look like +the following (the column header names are not read by MoorDyn): + +.. code-block:: none + + Time PtfmSurge PtfmSway PtfmHeave PtfmRoll PtfmPitch PtfmYaw + +If there are multiple coupled objects then the general order of columns beyond the time column +follows the order of the state vector: Body degrees of freedom, rod degrees of freedom, and points +degrees of freedom. + +Seafloor/Bathymetry File +^^^^^^^^^^^^^^^^^^^^^^^^ +.. _seafloor_in: + +For bathymetry inputs, MoorDyn-C takes a Seafloor file. +This file allows you to define a square grid of points and define depths at each of these points. + +.. code-block:: none + + num_x_points num_y_points + x_1 x_2 ... x_num_x_points + y_1 y_2 ... y_num_y_points + x_pos y_pos depth + x_pos y_pos depth + x_pos y_pos depth + etc, etc + +The two values on the first line define the number of points in each axis of the grid. +The second line defines the actual locations along the x axis for the x grid points. +The third line defines the locations along the y axis for the y grid points. +The remaining lines are (x, y, z) coordinates for the seafloor on grid points. +It is important that the x_pos be a value found in line 2 and y_pos be a value found in line 3. + +The bathymetry file in MoorDyn-F looks slightly different but functions the same. + +.. code-block:: none + + ----- MoorDyn Bathymetry Input File ---- + nGridX 2 + nGridY 2 + -1500 900 + -1200 1000 700 + 1200 1000 700 + +In this the -1500, 900 are x location, the -1200, and 1200 are y location +while the 1000 and 700 are the depths at the corresponding x and y. + +For both MoorDyn-C and MoorDyn-F what happens if one of these points does not fall on the grid is +not defined and may overwrite other depth values. + +If some part of the simulation falls outside of the defined grid area, it will use the depth of the +nearest grid edge. + +The V2 snapshot file +^^^^^^^^^^^^^^^^^^^^ + +In MoorDyn-C v2 two new functions have been added: + +.. doxygenfunction:: MoorDyn_Save +.. doxygenfunction:: MoorDyn_Load + +With the former a snapshot of the simulation can be saved, so that it can +be resumed in a different session using the latter function. +It is required to create the system using the same input file in both +sessions. +However, the initial equilibrium condition computation can be skipped in the second session by +calling + +.. doxygenfunction:: MoorDyn_Init_NoIC + +Wave Kinematics file (MoorDyn-C) +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +If the WaveKin option is nonzero then wave kinematics inputs need to be provided by a file with the +formats described in the :ref:`water kinematics section `. + +Water Kinematics file (MoorDyn-F) +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +.. _MDF_wtrkin: + +The file provided to MoorDyn-F for water Kinematics should have the following format, which +specifies the inputted waves and current. Details on this format can be found in the +:ref:`water kinematics section `. + +.. code-block:: none + + MoorDyn Waves and Currents input file + ...any notes here... + --------------------------- WAVES ------------------------------------- + 3 WaveKinMod - type of wave input {0 no waves; 3 set up grid of + wave data based on time series} + "waveelev.dat" WaveKinFile - file containing wave elevation time series at + 0,0,0 + 0.5 dtWave - time step to use in setting up wave kinematics + grid (s) + 0 WaveDir - wave heading (deg) + 1 - X wave input type (0: not used; 1: list values in ascending order; 2: uniform specified by -xlim, xlim, num) + -24, -18,-14,-10, -6,-2, 0, 4, 8, 12, 16, 20, 24, 28, 32, 36, 40, 45, 50, 55, + 60, 65, 70, 90, 120, 150 - X wave grid point data + 1 - Y wave input type (0: not used; 1: list values in ascending order; 2: uniform specified by -xlim, xlim, num) + 0 - Y wave grid point data + 1 - Z wave input type (0: not used; 1: list values in ascending order; 2: uniform specified by -xlim, xlim, num) + -600,-400,-200,-100,-40, -35,-30, -25, -20, -17,-16,-15, -14,-13,-12, -11,-10,-9, - + 8,-7,-6, -5,-4, -3,-2, -1, 0 - Z wave grid point data + --------------------------- CURRENT ------------------------------------- + 1 CurrentMod - type of current input {0 no current; 1 steady current profile described below} + z-depth x-current y-current + (m) (m/s) (m/s) + 0.0 0.9 0.0 + 150 0.5 0.0 + 1000 0.25 0.0 + 1500 0.2 0.0 + 5000 0.15 0.0 + --------------------- need this line ------------------ + +MoorDyn with FAST.Farm - Inputs +------------------------------- + +In FAST.Farm, a new ability to use MoorDyn at the array level to simulate shared mooring systems +has been developed. Until the main branch of OpenFAST, the FAST.Farm capability, and the MoorDyn-C +capability are merged, the shared moorings capability in FAST.Farm uses the MoorDyn v1 input file +format, with a small adjustment to reference attachments to multiple turbines. + +https://github.com/mattEhall/openfast/tree/f/fast-farm + +General Organization +^^^^^^^^^^^^^^^^^^^^ + +The regular ability for each OpenFAST instance to have its own MoorDyn simulation is unchanged in +FAST.Farm. This ability can be used for any non-shared mooring lines in all cases. To enable +simulation of shared mooring lines, which are coupled with multiple turbines, an additional +farm-level MoorDyn instance has been added. This MoorDyn instance is not associated with any +turbine but instead is called at a higher level by FAST.Farm. Attachments to different turbines +within this farm-level MoorDyn instance are handled by specifying "TurbineN" as the type for any +points that are attached to a turbine, where "N" is the specific turbine number as listed in the +FAST.Farm input file. + +MoorDyn Input File +^^^^^^^^^^^^^^^^^^ + +The following input file excerpt shows how points can be specified as attached to specific turbines +(turbines 3 and 4 in this example). When a point has "TurbineN" as its type, it acts similarly to a +"Vessel" type, where the X/Y/Z inputs specify the relative location of the fairlead on the platform. +In the farm-level MoorDyn input file, "Vessel" point types cannot be used because it is ambiguous +which turbine they attach to. + +.. code-block:: none + :emphasize-lines: 5,6,12 + + ----------------------- POINTS ---------------------------------------------- + Node Type X Y Z M V CdA CA + (-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) + 1 Turbine3 10.0 0 -10.00 0 0 0 0 + 3 Turbine4 -10.0 0 -10.00 0 0 0 0 + 2 Fixed 267.0 80 -70.00 0 0 0 0 + -------------------------- LINE PROPERTIES ---------------------------------- + 2 NLines - the number of lines + Line LineType UnstrLen NumSegs NodeA NodeB Flags/Outputs + (-) (-) (m) (-) (-) (-) (-) + 1 sharedchain 300.0 20 1 2 p + 2 anchorchain 300.0 20 1 3 p + +In this example, Line 1 is a shared mooring line and Line 2 is an anchored mooring line that has a +fairlead point in common with the shared line. Individual mooring systems can be modeled in the +farm-level MoorDyn instance as well. + + +FAST.Farm Input File +^^^^^^^^^^^^^^^^^^^^ + +In the branch of FAST.Farm that supports shared mooring capabilities, several additional lines have +been added to the FAST.Farm primary input file. These are highlighted in the example input file +excerpt below: + +.. code-block:: none + :emphasize-lines: 9,10,13,14,15 + + FAST.Farm v1.10.* INPUT FILE + Sample FAST.Farm input file + --- SIMULATION CONTROL --- + False Echo Echo input data to .ech? (flag) + FATAL AbortLevel Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} + 2000.0 TMax Total run time (s) [>=0.0] + False UseSC Use a super controller? (flag) + 1 Mod_AmbWind Ambient wind model (-) (switch) {1: high-fidelity precursor in VTK format, 2: one InflowWind module, 3: multiple instances of InflowWind module} + 2 Mod_WaveField Wave field handling (-) (switch) {1: use individual HydroDyn inputs without adjustment, 2: adjust wave phases based on turbine offsets from farm origin} + 3 Mod_SharedMooring Shared mooring system model (-) (switch) {0: None, 3: MoorDyn} + --- SUPER CONTROLLER --- [used only for UseSC=True] + "SC_DLL.dll" SC_FileName Name/location of the dynamic library {.dll [Windows] or .so [Linux]} containing the Super Controller algorithms (quoated string) + --- SHARED MOORING SYSTEM --- [used only for Mod_SharedMooring > 0] + "FarmMoorDyn.dat" FarmMoorDyn-File Name of file containing shared mooring system input parameters (quoted string) [used only when Mod_SharedMooring > 0] + 0.01 DT_Mooring Time step for farm-level mooring coupling with each turbine (s) [used only when Mod_SharedMooring > 0] + --- AMBIENT WIND: PRECURSOR IN VTK FORMAT --- [used only for Mod_AmbWind=1] + 2.0 DT_Low-VTK Time step for low -resolution wind data input files ; will be used as the global FAST.Farm time step (s) [>0.0] + 0.3333333 DT_High-VTK Time step for high-resolution wind data input files (s) [>0.0] + "Y:\Wind\Public\Projects\Projects F\FAST.Farm\AmbWind\steady" WindFilePath Path name to VTK wind data files from precursor (string) + False ChkWndFiles Check all the ambient wind files for data consistency? (flag) + --- AMBIENT WIND: INFLOWWIND MODULE --- [used only for Mod_AmbWind=2 or 3] + 2.0 DT_Low Time step for low -resolution wind data interpolation; will be used as the global FAST.Farm time step (s) [>0.0] diff --git a/docs/requirements.txt b/docs/requirements.txt index 188f51e6..c6d34064 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1 +1,2 @@ -breathe \ No newline at end of file +breathe +sphinx_rtd_theme diff --git a/docs/starting.rst b/docs/starting.rst deleted file mode 100644 index ec2f8cbc..00000000 --- a/docs/starting.rst +++ /dev/null @@ -1,436 +0,0 @@ -.. _starting: - -Getting Started -=============== - -The latest version of MoorDyn v2 is now available on -`GitHub `_. -Here it is describe both, how to install MoorDyn -:ref:`using the distributed binaries <_starting_binaries>`, -and how to :ref:`compile by yourself <_starting_compile>`. - -Binaries and installers ------------------------ - -.. _starting_binaries: - -Two different cases must be considered when installing binaries, the -:ref:`C/C++ libraries <_starting_binaries_lib>` (with the Fortran wrapper), and -the :ref:`Python package <_starting_binaries_python>`. - -C/C++ Library -^^^^^^^^^^^^^ - -.. _starting_binaries_lib: - -To install the C/C++ library (and the Fortran wrappers), please visit the -`Releases page `_, and select the -version you want to install. -Along this line you would probably want to consider either the latest version -identified with a number, or the one named "nightly". -The former is the latest stable version, while the latter is the latest version -uploaded to the repository, which tends to be a bit less stable. - -Once you already chosen a release, click on the assets and select the most -appropriate one for your platform. -More specifically, if you are in Windows you probably want to download and -execute Moordyn-X.Y.Z-win64.exe (with X.Y.Z replaced by the specific version), -in Linux you can download and execute Moordyn-X.Y.Z-Linux.sh and -in MacOS you can download and execute Moordyn-X.Y.Z-Darwin.sh. - -NOTE: When you donwload the self-extracting files for Linux and MacOS they -cannot be launched until you give them execution permissions. - -Now you can checkout -:ref:`how to integrate MoorDyn in your project <_starting_using>` below. - -Python package -^^^^^^^^^^^^^^ - -.. _starting_binaries_python: - -Installing the Python package is extremelly easy, just type - -.. code-block:: bash - - python -m pip install moordyn - -in your system terminal. Pip will take care of everything by you. - -Compile and install MoorDyn ---------------------------- - -.. _starting_compile: - -The process is sligthly different in Windows than in the other platforms, so it -will be documented separatelly - -Windows -^^^^^^^ - -In this tutorial we will install Eigen3 and MoorDyn in the default folders -(C:\Program Files (x86)\Eigen3 and C:\Program Files (x86)\Moordyn). -We will acquire the latest versions available with Git and build them -using CMake. This documentation assumes that you are building -in an MSYS2 build environment. - -Please, install all the tools we need: - -* `Git `_ -* `CMake `_ -* `MSYS2 `_ - -During the installation of Git, please check that you install all the components -shown below, and add it to the PATH: - -.. figure:: win_git_install.png - :alt: Installing Git in Windows - - Recommended options while installing Git in Windows - -The same holds for CMake: - -.. figure:: win_cmake_install.png - :alt: Installing CMake in Windows - - Recommended options while installing CMake in Windows - -The installation of MSYS2 is pretty well documented in -`the project web page `_. However, we need some -additional tools, so after running "MSYS MinGW 64-bit", please type -the following command - -.. code-block:: bash - - pacman -S mingw-w64-x86_64-python-setuptools mingw-w64-x86_64-python-pip mingw64/mingw-w64-x86_64-make mingw-w64-x86_64-gcc mingw-w64-x86_64-gdb mingw-w64-x86_64-cmake - -Now we need to make the MinGW stack available across the whole system by adding -it to the PATH environment variable. -To this end, execute "System" from the Windows Init menu, and look for -"environment". -Then click on "Edit the system environment variables" and in the popping up -window on "Enviroment Variables..." -Double click on Path (in the System variables box), and add a new entry: -"C:\msys64\mingw64\bin" - -.. figure:: win_msys2_env.png - :alt: Adding MinGW to the PATH - - Adding MinGW to the PATH - -Now we are ready to work! First we must create a folder where we will -download and compile the MoorDyn code, let's say C:\MoorDyn. -Create such a folder, and right click inside, selecting "Git GUI Here". In -the Git window select "Clone Existing Repository". - -.. figure:: win_git_gui.png - :alt: Git GUI in Windows - - The Git GUI to clone repositories - -We are starting with Eigen3, so in the first box of the window that pops up set -"https://gitlab.com/libeigen/eigen.git", and in the second "C:\MoorDyn\eigen": - -.. figure:: win_git_eigen.png - :alt: Options to clone Eigen3 - - Cloning Eigen3 repository - -Press "Clone" and let Git download the repository. -Now you can repeat, setting "https://github.com/mattEhall/MoorDyn.git", and -"C:\MoorDyn\MoorDyn" to download MoorDyn: - -.. figure:: win_git_moordyn.png - :alt: Options to clone MoorDyn - - Cloning MoorDyn repository - -Now, create two additional folders in C:\MoorDyn named eigen.build and -MoorDyn.build. As suggested by the names, these folders are where we will -actually build the source code we just cloned from GitHub. To do this, we'll -be using CMake as our build tool. - -Start CMake from the Windows Init menu. To prepare Eigen3 set -"C:\MoorDyn\eigen" in the source box and "C:\MoorDyn\eigen.build" in the -binaries box, and press "Configure". -The first time you configure a new project, CMake will ask you for the toolchain -to use. Select "MinGW Makefiles": - -.. figure:: win_cmake_selectcompiler.png - :alt: Selecting the MinGW generator - - Selecting the MinGW toolchain as generator - -Click on "Finish" and let CMake work. After a short while you will see a lot of -new red boxes. -Don't worry, these are not errors - they are red because they are new, and you -must specify some additional parameters for CMake. -Remember to set CMAKE_BUILD_TYPE as "Release" (unless you are working on the -source code, in which case you may wish to set the build type to "Debug" so -as to run the built program through a debugger). -It is also recommended to disable BUILD_TESTING, EIGEN_BUILD_DOC and -EIGEN_BUILD_TESTING: - -.. figure:: win_cmake_eigen.png - :alt: Configuration options for Eigen3 - - Configuration options for Eigen3 - -Press "Configure" once again, and then "Generate". Now you can close CMake. - -Now, since we are installing Eigen in C:\Program Files (x86)\Eigen3, we need -to execute a Command Prompt with administrative rights. -Search for "cmd" in the Windows Init menu and right click on -"Command Prompt", selecting Run as Administrator: - -.. figure:: win_cmd_admin.png - :alt: Launching an admin cmd - - Launching a Command Prompt with administrative rights - -Now you just need to type the following commands: - -.. code-block:: bash - - cd C:\MoorDyn\eigen.build - mingw32-make - mingw32-make install - -We will need to use cmd with administrative rights later on, so do not close it. - -Now we will install MoorDyn following a very similar process. -Launch CMake again, and set "C:\MoorDyn\MoorDyn" in the source box and -"C:\MoorDyn\MoorDyn.build" in the binaries box, clicking "Configure" afterwards. -Select again the "MinGW Makefiles" for the generator. -When the configuration options appear, set CMAKE_BUILD_TYPE as "Release", and -enable FORTRAN_WRAPPER and PYTHON_WRAPPER: - -.. figure:: win_cmake_moordyn.png - :alt: Configuration options for MoorDyn - - Configuration options for MoorDyn - -You can also enable MATLAB_WRAPPER if you have Matlab installed in your system. -We are ready, click "Configure" once more and then "Generate". - -Now go back to your Command Prompt from earlier (which has adminsitrative rights), and -type the following commands: - -.. code-block:: bash - - cd C:\MoorDyn\MoorDyn.build - mingw32-make - mingw32-make install - -NOTE: If you want to generate a Windows installer, disable the PYTHON_WRAPPER -option and type - -.. code-block:: bash - - cd C:\MoorDyn\MoorDyn.build - mingw32-make - cpack -C Release - - -Linux and MAC -^^^^^^^^^^^^^ - -First of all, use your package manager to install the following packages - -* `Git `_ -* `CMake `_ -* `Python `_ -* `Eigen3 `_ - -In Linux you can use either `GCC `_ or -`CLang `_, while in MAC the latter is the very only -option. -The process to compile and install is the same no matters the compiler you have -chosen. -However, it should be noticed that CLang does not provides a Fortran compiler. -To get Fortran support you would therefore install another compiler (e.g. the -GCC one) - -In this tutorial we are assuming you have administrative rights in your system, -although it is also possible to install MoorDyn and the wrappers in the user -space. - -First we are downloading the MoorDyn source code from the repository using git, - -.. code-block:: bash - - cd $HOME - git clone https://github.com/mattEhall/MoorDyn.git - cd MoorDyn - -Now we will ask cmake to configure everything typing - -.. code-block:: bash - - mkdir build - cd build - cmake -DCMAKE_INSTALL_PREFIX=/usr -DCMAKE_BUILD_TYPE=Release ../ - -If for some reason you decided to do not install -`Eigen3 `_ (although -it can be easily installed with your packages manager), you can still configure -MoorDyn adding the option -DEXTERNAL_EIGEN=OFF. Remember that in that case -you will only have available the :ref:`C API `, not the -:ref:`C++ API ` one. - -Finally you can compile and install MoorDyn: - -.. code-block:: bash - - make -j - make install - -That will install the C and C++ headers in /usr/include/moordyn folder, the -library and the CMake configuration files (to allow other projects to easily -find and link it) in /usr/lib/ folder, and the Python wrapper in the appropriate -Python folder under /usr/lib/. - -In case you do not have administrative priviledges, you can install MoorDyn -anywhere else just changing the option -DCMAKE_INSTALL_PREFIX=$HOME/.local while -configuring CMake. You also want to ask the Python wrapper get installed in the -user space with the option -DPYTHON_WRAPPER_USERINSTALL=ON. -You would need to edit the LD_LIBRARY_PATH environment variable afterwards. - -If you have also installed the Fortran compiler, which is usually the case in -most Linux distributions, you can also compile and install the Fortran wrapper, -just setting the option -DFORTRAN_WRAPPER=ON. -Along the same line, if you have Matlab installed in your system, feel free to -add also the option -DMATLAB_WRAPPER=ON. - -Use MoorDyn in your project ---------------------------- - -.. _starting_using: - -The way you can use MoorDyn in your project depends of course on the language. -Below it is documented the way you can integrate MoorDyn in your project in -different languages. The details on the system definition file are provided -:ref:`here `, while the code is further documented -:ref:`here `. If you have any problem try to give a look to the -:ref:`troubleshooting documentation ` - -C -^^^^^^ - -The easiest way to link MoorDyn to your C project is using CMake. Following -a code snippet where MoorDyn is integrated in a project with only a C source -code file named example.c: - -.. code-block:: cmake - - cmake_minimum_required (VERSION 3.10) - project (myproject) - - find_package (MoorDyn REQUIRED) - - add_executable (example example.c) - target_link_libraries (example MoorDyn::moordyn) - -CMake itself will already take care on everything. In the example.c you only -need to include the MoorDyn2.h header and start using the :ref:`C API `, -as it is further discussed in the :ref:`coupling documentation `. - -.. code-block:: c - - #include - - int main(int, char**) - { - MoorDyn system = MoorDyn_Create("Mooring/lines.txt"); - MoorDyn_Close(system); - } - -C++ -^^^^^^ - -The same CMake code snippet show above is equally valid for C++. In your C++ -code you must remember start including the MoorDyn configuration header and then -the main header, i.e. - -.. code-block:: cpp - - #include - #include - - int main(int, char**) - { - auto system = new moordyn::MoorDyn("Mooring/lines.txt"); - delete system; - } - -Python -^^^^^^ - -If you have installed the MoorDyn Python wrapper you are just ready to go! Open -a Python console and give it a shot! - -.. code-block:: python - - import moordyn - - system = moordyn.Create("Mooring/lines.txt") - moordyn.CLose(system) - -Fortran -^^^^^^^ - -Linking the MoorDyn Fortran wrapper is almost the same than linking the C -library. For instance, if you have a Fortran project consisting in a single -source code file, example.f90, then you can integrate MoorDyn with the -following CMake code: - -.. code-block:: cmake - - cmake_minimum_required (VERSION 3.10) - project (myproject) - - find_package (MoorDyn REQUIRED) - - add_executable (example example.f90) - target_link_libraries (example MoorDyn::moordynf) - -Please, note that now you are linking against MoorDyn::moordynf. The usage -is also very similar to the C one: - -.. code-block:: fortran - - program main - use, intrinsic :: iso_c_binding, only: c_ptr - use moordyn - - character(len=28) :: infile - type(c_ptr) :: system - integer :: err - - infile = 'Mooring/lines.txt' - system = MD_Create(infile) - err = MD_Close(system) - - end program main - -Matlab -^^^^^^ - -Using MoorDyn in Matlab is so far similar to using it in Python. However, in -Matlab you must manually add the folder where the wrapper an MoorDyn libraries -are located to the path. -To this end, in Matlab go to the HOME menu, section ENVIRONMENT, and click on -"Set Path". -In the window appearing click on "Add Folder...", and set the folder where you -installed the MoorDyn library, which by default is: - -* C:\Program Files (x86)\MoorDyn\bin in Windows -* /usr/lib in Linux and MacOS - -After that you are free to go! - -.. code-block:: matlab - - system = MoorDynM_Create("Mooring/lines.txt") - MoorDynM_Close(system) - diff --git a/docs/structure.rst b/docs/structure.rst index fe33b214..d04bbb32 100644 --- a/docs/structure.rst +++ b/docs/structure.rst @@ -1,325 +1,409 @@ -.. _structure: - Model Structure =============== +.. _structure: + +MoorDyn v2 models the dynamics of mooring structures in an object-oriented approach. There are four +main object types: Lines, Points, Rods, and Bodies. MoorDyn v1 only contained Lines and Points. +Lines are the fundamental discretized lumped-mass modeling component. Points and Rods provide a +means of connecting lines with additional 3- and 6-DOF properties (respectively), and Bodies +provide a way to create more complex 6-DOF rigid-body assemblies. These objects have predefined +ways or interacting. Kinematics are passed from the top down in and are used to calculate the +forces which are passed up back to the outside program or to output channels. This hierarchy is +shown below: +.. figure:: structure_moordyn.png + :alt: MoorDyn object hierarchy -MoorDyn Objects ---------------- -MoorDyn models the dynamics of mooring structures in an object-oriented programming (OOP) approach. -The overall simulation is managed by the MoorDyn2 class. This class reads inputs, allows models to -be loaded and saved, contains various environmental parameters (e.g. time-steps sizes and filepaths) -and most importantly contains pointers to all the Objects representing physical parts of the model -(Lines, Bodies, Rods, Points). +Each object type and its key parameters are detailed in the following sections. +Note: The variables described below are for MoorDyn-C. MoorDyn-F has the same general structure as +MoorDyn-C, with similar variables. The biggest difference between the codes underlying modeling is +that in MoorDyn-C quaternions are used to describe the position and orientation of 6DOF objects, +while in MoorDyn-F traditional Euler angles are used. To read more about quaternions and their +implementation, refer to the :ref:`theory section `. Lines -^^^^^ +----- +.. _lines: MoorDyn uses a lumped-mass approach to discretize the dynamics over the length of the mooring line. -A line is broken up into N evenly-sized line segments connecting N+1 node points. The indexing starts at the anchor (or lower end), -with the anchor node given a value of zero, and the cable segment between nodes 0 and 1 given an index of 1/2. +A line is broken up into N evenly sized line segments connecting N+1 node points. The indexing +starts at the anchor (or lower end), with the anchor node given a value of zero, and the cable +segment between nodes 0 and 1 given an index of 1/2. -The model uses a right-handed inertial reference frame with the z axis being measured positive up from the water plane, -consistent with NREL’s FAST simulator. Each node’s position is defined by a vector r. Each segment of the cable has -identical properties of unstretched length, diameter, density, and Young's modulus. Different cables can have different -sets of properties, and cables can be connected together at the ends, enabling mooring systems with interconnected lines. +The model uses a right-handed inertial reference frame with the z axis being measured positive up +from the water plane, consistent with NREL’s FAST simulator. Each node’s position is defined by a +vector r. Each segment of the cable has identical properties of unstretched length, diameter, +density, and Young's modulus. Different cables can have different sets of properties, and cables +can be connected together at the ends, enabling mooring systems with interconnected lines. -Hydrodynamic loads are calculated directly at the node points rather than at the segment centers. This ensures damping of -transverse cable vibrations having a wavelength of twice the cable segment length. To approximate the cable direction at -the node points, the cable tangent at each node is assumed to be the average of the tangent directions of the two -adjacent cable elements. Aside from this detail, the formulation of the mooring model is fairly standard. -Further technical details and some validation results are available in :ref:`some papers `. +Hydrodynamic loads are calculated directly at the node points rather than at the segment centers. +This ensures damping of transverse cable vibrations having a wavelength of twice the cable segment +length. To approximate the cable direction at the node points, the cable tangent at each node is +assumed to be the average of the tangent directions of the two adjacent cable elements. Aside from +this detail, the formulation of the mooring model is fairly standard. Further technical details and +validation results are available in the :ref:`theory section `. -Bending stiffness is a recent capability addition in MoorDyn v2 (it is not yet implemented in MoorDyn-F). -In the explanations that follow, the word cable is used to refer to a Line object with nonzero bending stiffness. +Bending stiffness is a recent capability addition in MoorDyn-C (it is not yet implemented in +MoorDyn-F). The word cable is used to refer to a Line object with nonzero bending stiffness. -MoorDyn keeps a dictionary of line types to describe the cross-sectional -(or per-meter) properties of the mooring lines. Each line type has an alphanumeric name -to identify it, and contains all the properties aside from length and discretization that -are needed to describe a mooring line in MoorDyn. +MoorDyn reads a user defined table of line types from the input file to describe the +cross-sectional (or per-meter) properties of the mooring lines. Each line type has an alphanumeric +name to identify it and contains all the properties aside from length and discretization that are +needed to describe a mooring line in MoorDyn. -Line objects maintain the following Data Members: +Line objects have the following variables: General: -- env: a pointer to the global environment object -- waves: a pointer to the global object storing information about waves/currents -- t: the simulation time, as a real +* *env*: a pointer to the global environment object +* *waves*: a pointer to the global object storing information about waves/currents +* *t*: the simulation time, as a real +* *seafloor*: a pointer to the global object storing the 3d seafloor information + Specific to each Line: -- N: int indicating the number of line segments in N -- UnstrLen: real indicating the unstretched length of the line -- d: real describing the line diameter -- rho: real describing the linear density of the line -- E: Young's modulus of the line (Pa) -- EI: real Bending stiffness (Nm^2) -- c: real damping coefficient (Ns). This can be the literal damping coefficient, or a negative value representing -fraction of critical damping -- Can: real normal added mass coefficient -- Cat: real axial added mass coefficient -- Cdn: real normal drag coefficient w/r/t frontal area -- Cdt: real axial drag coefficient w/r/t surface area -- BAin: real axial-internal damping -- A: real cross sectional area -- nEApoints: number of values in stress-strain lookup table -- stiffXs: x-array for stress-strain lookup table -- stiffYs: y-array of reals for stress-strain lookup table -- nEIpoints: number of values in bent-stiffness lookup table -- bstiffXs: x-array for bent-stiffness lookup table -- bstiffYs: y-array of reals for bent-stiffness lookup table +- *N*: int indicating the number of line segments in N +- *UnstrLen*: real indicating the unstretched length of the line +- *d*: real describing the line diameter +- *rho*: real describing the linear density of the line +- *E*: Young's modulus of the line (Pa) +- *EI*: real Bending stiffness (Nm^2) +- *c*: real damping coefficient (Ns). This can be the literal damping coefficient, or a negative + value representing fraction of critical damping +- *Can*: real normal added mass coefficient +- *Cat*: real axial added mass coefficient +- *Cdn*: real normal drag coefficient w/r/t frontal area +- *Cdt*: real axial drag coefficient w/r/t surface area +- *BAin*: real axial-internal damping +- *A*: real cross sectional area +- *nEApoints*: number of values in stress-strain lookup table +- *stiffXs*: x-array for stress-strain lookup table +- *stiffYs*: y-array of reals for stress-strain lookup table +- *nEIpoints*: number of values in bent-stiffness lookup table +- *bstiffXs*: x-array for bent-stiffness lookup table +- *bstiffYs*: y-array of reals for bent-stiffness lookup table +- *nCpoints*: number of values in stress-strain rate lookup table (0 for constant c) +- *dampXs*: x array for stress-strain rate lookup table +- *dampYs*: y array for stress-strain rate lookup table State: -- r: a vector of 3D node positions for the nodes representing the line. -- rd: a vector of 3D velocities for each of the nodes representing the line -- q: a vector of 3D tangent vectors for each node -- qs: a vector of 3D tangent vectors for each segment -- l: a vector of unstretched line segment lengths (as reals) -- lstr: a vector of stretched segment lengths (as reals) -- ldstr: a vector of reals describing the rate of stretch for each segment -- Kurv: a vector of reals describing the curvature at node points -- M: a vector of 3x3 matrices describing the mass+added mass of each node in the line -- V: a vector of line-segment volumes as reals - -Forces are computed at every node in the line. Hence, all line forces are represented as std::vectors of 3D force vectors: - -- T: a vector of 3D vectors describing segment tensions -- Td: a vector of 3D vectors describing segment Damping forces -- Bs: a vector of 3D vectors describing bending stiffness forces -- W: a vector of 3D vectors describing weight (gravity) forces -- Dp: a vector of 3D vectors describing node drag (transversal) -- Dq: a vector of 3D vectors describing node drag (axial) -- Ap: a vector of 3D vectors describing added-mass forcing (Transversal) -- Aq: a vector of 3D vectors describing mass-forcing (axial) -- B: a vector of 3D vectors describing node bottom contact force -- Fnet: a vector of 3D vectors describing total force on each node in the line - -Waves: - -- F: a vector of reals indicating volume of each segment submerged (1 = fully submerged, 0 = out of water) -- zeta: vector of reals describing free-surface elevations -- PDyn: vecctor of reals describing dynamic pressures -- U: vector of 3D vectors describing wave velocities -- Ud: vector of 3D vectors describing wave accelerations - -Misc. - -- endTypeA, endTypeB: indicates whether ends are pinned or cantilevered to rod -- endMomentA, endMomentB: 3D moment vectors at ends, to be applied to attached Rod/Body -- outfile: pointer to outfile to write to -- channels: which channels to write to the outfile +- *r*: a vector of 3D node positions for the nodes representing the line. +- *rd*: a vector of 3D velocities for each of the nodes representing the line + +Dynamics: + +- *q*: a vector of 3D tangent vectors for each node +- *qs*: a vector of 3D tangent vectors for each segment +- *l*: a vector of unstretched line segment lengths (as reals) +- *lstr*: a vector of stretched segment lengths (as reals) +- *ldstr*: a vector of reals describing the rate of stretch for each segment +- *Kurv*: a vector of reals describing the curvature at node points +- *M*: a vector of 3x3 matrices describing the mass+added mass of each node in the line +- *V*: a vector of line-segment volumes as reals +- *F*: a vector of reals indicating volume of each segment submerged (1 = fully submerged, 0 = out + of water) + +Forces are computed at every node in the line. Hence, all line forces are represented as vectors of +3D force vectors: + +- *T*: a vector of 3D vectors describing segment tensions +- *Td*: a vector of 3D vectors describing segment Damping forces +- *Bs*: a vector of 3D vectors describing bending stiffness forces +- *W*: a vector of 3D vectors describing weight (gravity) forces +- *Dp*: a vector of 3D vectors describing node drag (transversal) +- *Dq*: a vector of 3D vectors describing node drag (axial) +- *Ap*: a vector of 3D vectors describing added-mass forcing (Transversal) +- *Aq*: a vector of 3D vectors describing mass-forcing (axial) +- *B*: a vector of 3D vectors describing node bottom contact force +- *Fnet*: a vector of 3D vectors describing total force on each node in the line + +.. Waves: +.. +.. - *zeta*: vector of reals describing free-surface elevations +.. - *PDyn*: vector of reals describing dynamic pressures +.. - *U*: vector of 3D vectors describing wave velocities +.. - *Ud*: vector of 3D vectors describing wave accelerations +.. + +Misc: + +- *endTypeA, endTypeB*: indicates whether ends are pinned or cantilevered to rod +- *endMomentA, endMomentB*: 3D moment vectors at ends, to be applied to attached Rod/Body +- *outfile*: pointer to outfile to write to +- *channels*: which channels to write to the outfile Points -^^^^^^ +------ .. _points: Point objects attach to the ends of Lines and can be used to connect Lines to other things -or to each other. (In MAP and older versions of MoorDyn, these objects were called Points). -A Point has three degrees of freedom and can have any number of Lines attached to it. -There are three types of Points: +or to each other. (In MAP and older versions of MoorDyn, these objects were called Connections or +Nodes). A Point has three degrees of freedom and can have any number of Lines attached to it. There +are three types of Points: -- **Fixed**: their location is fixed to ground (stationary) or a Body object. - They can be used as anchor points or as a way to attach mooring Lines to a Body. -- **Coupled**: they move under the control of the calling program/script. +- **Fixed/Anchor/Body**: their location is fixed to an XYZ coordinate (stationary) or a Body object. + They can be used as anchor points or to attach mooring Lines to a Body. +- **Coupled/Fairlead/Vessel**: they move under the control of the driver program/script. They can be used as fairlead points when the platform is modeled externally. See :ref:`the coupling documentation `. -- **Free**: they are free to move according to the forces acting on them, which includes - the tensions of attached lines as well as their own self weight and buoyancy, if applicable. +- **Free/Point/Connect**: they are free to move according to the forces acting on them, which + includes the tensions of attached lines as well as their own self weight and buoyancy, if + applicable. Free Points facilitate more advanced mooring systems. They can be used to connect two or more mooring lines together, to create multi-segmented lines or junctions such as in a bridle mooring configuration. If a free Point is given nonzero volume or mass properties, it can also represent a clump weight or float. -In the C++ API, "Points" are represented as Point objects (as their principle purpose -is to connect different lines/bodies/rods together). Currently, every line must have 2 -Points at each endpoint. Point objects expose a public member, Point::attachment, -that contains 1. a pointer to the Line object attached to the point and 2. a field indicating -which "end" (A or B) of the line is attached to the point. +In MoorDyn-C, "Points" are represented as Point objects. +Currently, every line must have 2 +points at each endpoint (Rod ends serve as points). Point objects expose a public member, +Point::attachment, that contains 1) a pointer to the Line object attached to the point and 2) a +field indicating which "end" (A or B) of the line is attached to the point. -Points Objects have the following data members: +Points Objects have the following variables: General: -- env: a pointer to a global struct holding environmental settings -- waves: a pointer to a global object representing Waves in the system +- *env*: a pointer to a global struct holding environmental settings +- *waves*: a pointer to a global object representing Waves in the system +- *t*: the simulation time, as a real +- *seafloor*: a pointer to the global object storing the 3d seafloor information Specific to each Point: -- attached: a vector of attachments, describing all lines attached to the Point -- conM: the mass of the point as a real -- conV: the volume of the point as a real -- conF: a 3D vector of forces on the point -- conCdA: Drag coefficient of the point -- conCa: Added mass coefficient of the point +- *attached*: a vector of attachments, describing all lines attached to the point +- *pointM*: the mass of the point as a real +- *pointV*: the volume of the point as a real +- *pointF*: a 3D vector of forces on the point +- *pointCdA*: prag coefficient of the point +- *pointCa*: pdded mass coefficient of the point State: -- r: 3D node position -- rd: 3D node velocity -- FNet: 3D force vector on node -- M: 3x3 mass + added mass matrix +- *r*: 3D node position +- *rd*: 3D node velocity + +Dynamics: -Waves: +- *r_ves*: 3D fairlead position for coupled points +- *rd_ves*: 3D fairlead velocity for coupled points +- *FNet*: 3D force vector on node +- *M*: 3x3 mass + added mass matrix +- *Acc*: 3D node acceleration vector -- zeta: real representing free-surface elevation -- PDyn: dynamic pressure -- U: Wave velocities -- Ud: Wave accelerations +.. Waves: +.. +.. - *zeta*: real representing free-surface elevation +.. - *PDyn*: dynamic pressure +.. - *U*: Wave velocities +.. - *Ud*: Wave accelerations +.. - *WaterKin*: Flag indicating whether wave/current kinematics will be considered +.. Misc: -- number: point ID (unique int) -- type: Point type, one of moordyn::Point::types -- WaterKin: Flag indicating whether wave/current kinematics will be considered: +- *number*: point ID (unique int) +- *type*: point type, one of moordyn::Point::types Rods -^^^^ +---- +.. _rods: -Rod objects provide an option for rigid cylindrical elements within a mooring system. They have similar modeling details as -Lines except for their rigidity, which reduces their degrees of freedom to six. Like Lines, they are divided into a number -of nodes at which weight, buoyancy, seabed contact, -and Morison-based hydrodynamic forces are calculated. Unlike Lines, their internal forces are not calculated. -The end nodes of a rod are available for attachment of lines (specified like "R2A" for end A of Rod 2). +Rod objects provide an option for rigid cylindrical elements within a mooring system. They have +similar modeling details as Lines except for their rigidity, which gives them six degrees of +freedom. Like Lines, they are divided into nodes at which weight, buoyancy, seabed contact, and +Morison-based hydrodynamic forces are calculated. Unlike Lines, their internal forces are not +calculated. Generally, more nodes in a rod increase the accuracy of rod dynamics calculations. The +end nodes of a rod are available for attachment of lines (specified as "R2A" for end A of Rod 2) +and can be set up in the :ref:`input file `. Rods can have 6, 3, or 0 DOF. -- **Fixed**: Rods are full constrained, and their movement is defined by that of a body, the ground, or a coupling point. -- **Pinned**: Rods are attached at end A to something else, whether that is a body, the ground, or a coupling point. - This type of Rod only has three rotational degrees of freedom, about end A. -- **Coupled**: They move under the control of the calling program/script. +- **Fixed**: Rods are full constrained, and their movement is defined by that of a body, the ground, + or a coupling point (0 DOF). +- **Pinned**: Rods are attached at end A to something else, whether that is a body, the ground, or + a coupling point (3 DOF, all rotational). This type of Rod only has three rotational degrees of + freedom, about end A. +- **Coupled**: They move under the control of the calling program/script (constrained in all 6 DOF). See :ref:`the coupling documentation `. - **Free**: Rods are unconstrained to move in all 6 DOF. Pinned or Fixed Rods attached to a body (e.g. body 1) are labelled "Body1Pinned" or "Body1". Pinned or fixed rods that serve as a coupling point are labelled "CoupledPinned" or "Coupled" -As it happens with other entities, rods are computed considering a simplified -Hydrodynamic model. Thus there are situations which are not properly handled, -like surfaced rods with the free surface oriented along the main axis. -In such case it is strongly recommended to set the rod "coupled" and apply an -external solver. +A special case exists if a Rod is specified with zero elements: in that case it is given zero +length, and its end B coordinates in the input file are instead interpreted as vector components to +describe its direction vector. This case is meant for making cantilever points of a line with +bending stiffness. A fixed zero-length rod can be used to make a cantilever point of a power cable +to the ground, a body, or a coupling point. A free zero-length rod can be used to join two +different types of power cable segments, and it will pass moments between the cable segments +without adding any mass or other characteristics. -A special case exists if a Rod is specified with zero elements: in that case it is given zero length, and -its end B input coordinates are instead interpreted as vector components to describe its direction vector. -This case is meant for convenience when making cantilever points of a line with bending stiffness. -A fixed zero-length rod can be used to make a cantilever point of a power cable to the ground, a body, or a coupling point. -A free zero-length rod can be used to join two different types of power cable segments, and it will pass moments -between the cable segments without adding any mass or other characteristics. +Rod objects have the following variables: + +General: + +- *env*: a pointer to a global struct holding environmental settings +- *waves*: a pointer to a global object representing Waves in the system +- *t*: the simulation time, as a real +- *seafloor*: a pointer to the global object storing the 3d seafloor information + +Attachments: + +- *attachedA*: A vectors of lines attached to the end point A of the rod +- *attachedB*: A vector of lines attached to the end point B of the rod + +Specific to each rod: + +- *N*: The number of rod segments +- *UnstrLen*: The constrained length of the rod +- *q0*: The original rod orientation vector +- *d*: Rod diameter +- *rho*: Rod linear density +- *Can*: Normal added mass coefficient +- *Cat*: Axial added mass coefficient +- *Cdn*: Normal drag coefficient (unused) +- *Cdt*: Axial drag coefficient (unused) +- *CdEnd*: Rod end drag coefficient +- *CaEnd*: Rod end added mass coefficient + +State: + +- *r7*: A quaternion describing the rods position +- *v6*: Rod 6dof velocity[vx,vy,vz,wx,wy,wz] (end A velocity and rotational velocities about + unrotated axes) +- *vel7*: A quaternion describing the rods velocity that when integrated gives r7. It is equivalent + to v6. + +Dynamics: + +- *acc6*: Final 6 DOF rod acceleration used for outputs. When integrated gives v6. +- *r*: 3D vector of node positions +- *rd*: 3D vector of node velocities +- *q*: Unit tangent vector for the rod +- *l*: Rod segment lengths +- *M*: 3x3 node mass and added mass matrix +- *V*: Segment volumes +- *r_ves*: 6D vector of fairlead position for coupled rods +- *rd_ves*: 6D vector of fairlead velocity for coupled rods + +Forces: + +- *FextA*: A vector of external forces from attached lines on/about end A +- *FextB*: A vector of external forces from attached lines on/about end B +- *Mext*: A vector of external moments (from attached cables or waterplane hydrostatic moment) +- *F6net*: Total force and moment about end A (excluding inertial loads) that Rod may exert on + whatever it's attached to +- *M6net*: total 6x6 mass matrix about end A of Rod and any attached Points +- *W*: A vector of node dry weights +- *Bo*: A vector of node buoyancy +- *Pd*: A vector of the Froud-Krylov force +- *Dp*: A vector of node drag forces (axial) +- *Dq*: A vector of node drag forces (transversal) +- *Ap*: A vector of node added mass (transversal) +- *Aq*: A vector of the long wave diffraction force +- *B*: A vector of node bottom contact force +- *Fnet*: A vector of total force on node (depreciated) + +Wave stuff: + +- *VOF*: VOF submergence scalar for each node (1 = fully submerged, 0 = out of water) +- *h0*: instantaneous axial submerged length + +Misc: + +- *outfile*: pointer to the main outfile for the rod +- *channels*: which channels to write to the outfile Bodies -^^^^^^ - -Body objects provide a generic 6 DOF rigid-body representation based on a lumped-parameter model of translational -and rotational properties (e.g. hydrodynamic drag and added mass coefficients). -Rod elements can be added to bodies and mooring lines can be attached at any location, -allowing a wide variety of submerged structures to be integrated into the mooring system. -Aside from contributions which might come from incorporated Rod objects or attached Point -and Line objects, the core Body object properties are as follows: - -- mass, and center of mass -- volumetric displacement (assumed to be at reference point) -- mass moment of inertia about each axis -- hydrodynamic drag coefficient in each direction -- rotational hydrodynamic drag coefficient about each axis -- added mass coefficient in each direction -- added mass moment of inertia coefficient about each axis - -In the C++ API, Bodies are represented as a standalone class. This class can have different behaviors -depending on it's "type" (in the intuitive sense, not in the C++ sense) - there are three possible types +------ +.. _bodies: + +Body objects provide a generic 6 DOF rigid-body representation based on a lumped-parameter model of +translational and rotational properties (e.g. hydrodynamic drag and added mass coefficients). Rod +elements can be added to bodies and mooring lines can be attached at any location, allowing a wide +variety of submerged structures to be integrated into the mooring system. The body itself does not +have a defined geometry (the volume is only used in buoyancy calculations), rather its geometry is +defined by the rods attached to it. Therefore, for simplicity, any hydrodynamic loads associated +with a body on its own (with no attached objects) are always calculated as though the body is fully +submerged. Partial submergence is handled in any attached objects. Aside from contributions which +might come from incorporated Rod objects or attached Point and Line objects, the core Body object +properties are as follows: + +- *mass, and center of mass* +- *volumetric displacement (assumed to be at reference point)* +- *mass moment of inertia about each axis* +- *hydrodynamic drag coefficient in each direction* +- *rotational hydrodynamic drag coefficient about each axis* +- *added mass coefficient in each direction* +- *added mass moment of inertia coefficient about each axis* + +There are three possible types for bodies: +- **Coupled**: the body kinematics are controlled by the calling program. +- **Free**: the body kinematics are computed by MoorDyn based on the applied loads and inertia - **Fixed**: the body is fixed, either to a particular location or to a connected, moving entity. -- **Coupled**: the body position is controlled by the calling program. - See :ref:`the coupling documentation `. -- **Free**: the body position is free to move, controlled by the hydrodynamic forces implemented in MoorDyn -Body objects have the following data members: +Body objects have the following variables: General: -- env: a pointer to a global struct holding environmental settings -- waves: a pointer to a global object representing Waves in the system - -Unique to Body: +- *env*: a pointer to a global struct holding environmental settings +- *waves*: a pointer to a global object representing Waves in the system Attachments: -- attachedP: a vector of pointers to Point objects, indicating all the points attached to the body -- attachedR: a vector of pointers to Rod objects attached to the body. -- rConnectRel: a vector of 3d vectors describing the attachment points locations for Points -- r6RodRel: a vector of 6D vectors describing the attachment points and orientation of eac rod. +- *attachedP*: a vector of pointers to point objects, indicating all the points attached to the + body +- *attachedR*: a vector of pointers to Rod objects attached to the body. +- *rPointRel*: a vector of 3d vectors describing the attachment points locations for Points +- *r6RodRel*: a vector of 6D vectors describing the attachment points and orientation of + each rod. -Body Properties (set upon call to Body::setup()). Note that these are all set to zero for all Body types +Body Properties. Note that these are all set to zero for all Body types other than FREE, as they are not relevant to COUPLED or FIXED scenarios: -- body_r6: 6D reference point for the body. -- body_rCG: 3D location of body center-of-gravity -- bodyM: real number describing the body's mass -- bodyV: real number describing the body's volume -- bodyI: 3d Vector describing the inertia diagonal components of the body -- bodyCdA: 6D vector describing the body's drag coefficients -- bodyCa: 6D vector describing added-mass coefficients - -Values describing the body's state: - -- r6: 6D vector describing body's position -- v6: 6D vector describing body's velocity -- r_ves: 6D vector describing fairlead position if a coupled body (may be different than overall r6) -- rd_ves: 6D vector describing fairlead velocity if a coupled body (may be different than overall v6) -- F6net: 6D vector describing total force/moment vector on node -- M: 6x6 matrix representing total body mass + added mass -- m0: 6x6 matrix representing 'starting mass' matrix of body, not taking into accound rod elements. -- OrMat: 3x3 matrix representing orientation of the body -- U: 3D vector of wave velocity at reference point -- Ud: 3D vector of wave acceleration at reference point -- outfile: pointer to the main output file for the body +- *body_r6*: 6D reference point for the body. +- *body_rCG*: 3D location of body center-of-gravity +- *bodyM*: real number describing the body's mass +- *bodyV*: real number describing the body's displaced volume +- *bodyI*: 3d Vector describing the inertia diagonal components of the body +- *bodyCdA*: 6D vector describing the body's drag coefficients +- *bodyCa*: 6D vector describing added-mass coefficients + +State: +- *r7*: quaternion describing body's position +- *v6*: 6D vector describing body's velocity +- *dPos*: quaternion describing the body’s velocity that when integrated gives r7. It is equivalent + to v6. + +Dynamics and Forces: + +- *a6*: 6D vector of body acceleration that when integrated gives v6. +- *r_ves*: 6D vector describing fairlead position if a coupled body (may be different than + overall r6) +- *rd_ves*: 6D vector describing fairlead velocity if a coupled body (may be different than + overall v6) +- *F6net*: 6D vector describing total force/moment vector on node +- *M*: 6x6 matrix representing total body mass + added mass +- *M0*: 6x6 matrix representing 'starting mass' matrix of body, not taking into account rod + elements. +- *OrMat*: 3x3 matrix representing orientation of the body + +.. Waves: +.. +.. - *U*: 3D vector of wave velocity at reference point +.. - *Ud*: 3D vector of wave acceleration at reference point +.. + Misc: -- number: a unique int id identifying the body -- type: FREE, COUPLED, or FIXED, describing the "type" of body to be modeled - -Angles criteria ---------------- - -In the following figure the angles criteria is schematically depicted: - -.. figure:: angles.svg - :alt: Angles criteria schematic view - -Indeed, the roll and heading angles, :math:`\phi` and :math:`\psi`, follow the -right hand criteria, while the pitch angle, :math:`\theta`, follows the left -hand criteria. -This way the classic rotation matrices can be considered, - -.. math:: - \begin{alignat}{1} - R_x(\phi) &= \begin{bmatrix} - 1 & 0 & 0 \\ - 0 & \cos \phi & -\sin \phi \\[3pt] - 0 & \sin \phi & \cos \phi \\[3pt] - \end{bmatrix} \\[6pt] - R_y(\theta) &= \begin{bmatrix} - \cos \theta & 0 & \sin \theta \\[3pt] - 0 & 1 & 0 \\[3pt] - -\sin \theta & 0 & \cos \theta \\ - \end{bmatrix} \\[6pt] - R_z(\psi) &= \begin{bmatrix} - \cos \psi & -\sin \psi & 0 \\[3pt] - \sin \psi & \cos \psi & 0 \\[3pt] - 0 & 0 & 1 \\ - \end{bmatrix} - \end{alignat} - -which allows to compute moments just by simple cross products, -:math:`\boldsymbol{M} = \boldsymbol{r} \times \boldsymbol{F}`. - -Please, notice that in MoorDyn the z axis is considered the upwards direction, -i.e. the gravity points towards -z direction. -Thus, the North-East-Down (NED) angles criteria widely applied in naval -architecture does not match the MoorDyn one. -More specifically, the pitch and heading angles shall be inverted whereas roll -angle remains the same. +- *number*: a unique int id identifying the body +- *type*: FREE, COUPLED, or FIXED, describing the "type" of body to be modeled +- *outfile*: pointer to the main output file for the body diff --git a/docs/structure_moordyn.png b/docs/structure_moordyn.png new file mode 100644 index 00000000..02c957dc Binary files /dev/null and b/docs/structure_moordyn.png differ diff --git a/docs/theory.rst b/docs/theory.rst index 8cd20e50..1d3af3c5 100644 --- a/docs/theory.rst +++ b/docs/theory.rst @@ -1,21 +1,85 @@ +Features and References +======================= .. _theory: -Theory and References -===================== - -The theory behind MoorDyn is available in a collection of papers, listed below along with which modeling aspects they focus on. - -The original lumped-mass formulation of MoorDyn as well as its validation against experiments: +Most of MoorDyn’s theory is described in the following publications. This page +gives a very high-level overview, highlights specific theory aspects that may +be important to users, and lists the papers where more detail can be found. + +Features +-------- + +Version 1 +^^^^^^^^^ +MoorDyn is based on a lumped-mass discretization of a mooring line’s dynamics, and adds point-mass and rigid-body objects to enable simulation of a wide +variety of mooring and cabling arrangements. Hydrodynamics are included using a version of the Morison equation. + +Version 2 +^^^^^^^^^ +MoorDyn v2 contains all the features of v1 with the following additional features: + - Simulation of 6 degree of freedom objects + - Non-linear tension + - Wave kinematics + - Bending stiffness + - Bathymetry + - Seabed friction + +The main difference between MoorDyn-C and MoorDyn-F is that MoorDyn-C uses quaternions to describe the orientation of 6DOF objects, while F uses traditional Euler angles to handle 6DOF object rotations. + +Orientation of 6 DOF objects: +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Euler angles – MoorDyn-F +"""""""""""""""""""""""" + +In the following figure the 6DOF object orientation angles convention is depicted: + +.. figure:: angles.svg + :alt: Angles criteria schematic view + +The roll and yaw angles, :math:`\phi` and :math:`\psi`, follow the +right hand criteria, while the pitch angle, :math:`\theta`, follows the left +hand criteria. +This way the classic rotation matrices can be considered, + +.. math:: + \begin{alignat}{1} + R_x(\phi) &= \begin{bmatrix} + 1 & 0 & 0 \\ + 0 & \cos \phi & -\sin \phi \\[3pt] + 0 & \sin \phi & \cos \phi \\[3pt] + \end{bmatrix} \\[6pt] + R_y(\theta) &= \begin{bmatrix} + \cos \theta & 0 & \sin \theta \\[3pt] + 0 & 1 & 0 \\[3pt] + -\sin \theta & 0 & \cos \theta \\ + \end{bmatrix} \\[6pt] + R_z(\psi) &= \begin{bmatrix} + \cos \psi & -\sin \psi & 0 \\[3pt] + \sin \psi & \cos \psi & 0 \\[3pt] + 0 & 0 & 1 \\ + \end{bmatrix} + \end{alignat} + + +Quaternions – MoorDyn-C +""""""""""""""""""""""" + +The latest MoorDyn-C internally uses quaternions to describe the location and orientation of 6 DOF objects. Externally MoorDyn-C behaves the same as MoorDyn-F, using Euler angles for both inputs and outputs. Quaternions are a common alternative to Euler angles for describing orientations of 3D objects. +Further description of quaternions can be found in PR #90 in the MoorDyn repository, put together by Alex Kinley of Kelson Marine: https://github.com/FloatingArrayDesign/MoorDyn/pull/90#issue-1777700494 + +References +---------- + +The theory behind MoorDyn is available in a collection of papers, listed below by which version they were implemented in. + +Version 1 +^^^^^^^^^ +The v1 lumped-mass formulation of MoorDyn as well as its validation against experiments: `M. Hall and A. Goupee, “Validation of a lumped-mass mooring line model with DeepCwind semisubmersible model test data,” Ocean Engineering, vol. 104, pp. 590–603, Aug. 2015.' `_ - -Early work on seabed friction and independent fairlead points: - - `M. Hall, “Efficient Modelling of Seabed Friction and Multi-Floater Mooring Systems in MoorDyn,” - in Proceedings of the 12th European Wave and Tidal Energy Conference, Cork, Ireland, 2017. `_ - Coupling with WEC-Sim or any Simulink code for wave energy converter simulation: `S. Sirnivas, Y.-H. Yu, M. Hall, and B. Bosma, “Coupled Mooring Analysis for the WEC-Sim Wave Energy Converter Design Tool,” @@ -25,6 +89,16 @@ Coupling with WEC-Sim or any Simulink code for wave energy converter simulation: `G. Vissio, B. Passione, and M. Hall, “Expanding ISWEC Modelling with a Lumped-Mass Mooring Line Model,” presented at the European Wave and Tidal Energy Conference, Nantes, France, 2015. `_ +Version 2 +^^^^^^^^^ + +Version 2 builds upon the capabilities of Version 1. The theory behind the new features is described in the following references. + +Early work on seabed friction and independent fairlead points: + + `M. Hall, “Efficient Modelling of Seabed Friction and Multi-Floater Mooring Systems in MoorDyn,” + in Proceedings of the 12th European Wave and Tidal Energy Conference, Cork, Ireland, 2017. `_ + Preliminary comparison of seabed friction formulations: `K. Devries, M. Hall, “Comparison of Seabed Friction Formulations in a LumpedMass Mooring Model”. in Proceedings of the ASME @@ -37,3 +111,23 @@ Overview of MoorDyn v2: Implementation of bending stiffness modeling for power cables: https://www.nrel.gov/docs/fy21osti/76968.pdf + +The Fortran version of MoorDyn is available as a module inside of OpenFAST: + + https://openfast.readthedocs.io/en/main/ + +Dynamics of 6DOF objects follows a similar approach to Hydrodyn: + + https://www.nrel.gov/wind/nwtc/assets/downloads/HydroDyn/HydroDyn_Manual.pdf + +Quaternion references: + +1. Fossen, Thor I. Handbook of marine craft hydrodynamics and motion control. + Page 25 John Wiley & Sons, 2011. +2. https://en.wikipedia.org/wiki/Gimbal_lock +3. https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/ +4. https://en.wikipedia.org/wiki/Quaternion#Hamilton_product + +MoorDyn-C Packages used: + Eigen: https://eigen.tuxfamily.org + Catch2: https://github.com/catchorg/Catch2 diff --git a/docs/troubleshooting.rst b/docs/troubleshooting.rst index cb6677d1..9b3c212a 100644 --- a/docs/troubleshooting.rst +++ b/docs/troubleshooting.rst @@ -1,46 +1,124 @@ -.. _troubleshooting: - Troubleshooting =============== +.. _troubleshooting: -The Python wrapper does not work --------------------------------- +Here are some general points of advice for using MoorDyn. Another good resource is the +`closed issues page `_ on the +MoorDyn-C repository . + +Model Stability and Segment Damping +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -ModuleNotFoundError: No module named 'moordyn' -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Two of the trickier input parameters are the internal damping (BA) for each line type, +and the mooring simulation time step (dtM). Both relate to the discretization of the +lines. The highest axial vibration mode of the lumped-mass cable representation would +be when adjacent nodes oscillate out of phase with each other, as depicted below. + +In this mode, the midpoint of each segment would not move. The motion of each node can +then be characterized by mass-spring-damper values of -If you type in a Python console +.. math:: -.. code-block:: python + m = w \frac{L}{N}, \\ c = 4 B A \frac{N}{L}, \\ k = 4 E A \frac{N}{L}. - import moordyn +The natural frequency of this mode is then + +.. math:: + + \omega_n = \sqrt{\frac{k}{m}} = \frac{2}{l} \sqrt{\frac{E A}{w}}=2 \frac{N}{L} \sqrt{\frac{E A}{w}} + +and the damping ratio, ζ, is related to the internal damping coefficient, BA, by + +.. math:: + + \zeta =\frac{c}{c_{crit}} = \frac{B}{l} \sqrt{\frac{A}{E w}} = B A \frac{N}{L} \sqrt{\frac{1}{E A w}}, \\ B A= \zeta \frac{L}{N} \sqrt{E A w}. + +The line dynamics frequencies of interest should be lower than ω_n in order to be +resolved by the model. Accordingly, line dynamics at ω_n, which are likely to be +dominated by the artificial resonance created by the discretization, can be damped out +without necessarily impacting the line dynamics of interest. This is advisable because +the resonances at ω_n can have a large impact on the results. To damp out the segment +vibrations, a damping ratio approaching the critical value (ζ=1) is recommended. Care +should be taken to ensure that the line dynamics of interest are not affected. + +To simplify things, a desired line segment damping ratio can be specified in the input +file. This is done by entering the negative of the desired damping ratio in the BA/-zeta +field of the Line Types section. A negative value here signals MoorDyn to interpret it as +a desired damping ratio and then calculate the damping coefficient (BA) for each mooring +line that will give every line segment that damping ratio (accounting for possible +differences in segment length between lines). -and you receive the error above, then the Python wrapper is not properly -installed. First, if you compiled MoorDyn by yourself check that -PYTHON_WRAPPER option was ON while configuring with CMake. +Note that the damping ratio is with respect to the critical damping of each segment along +a mooring line, not with respect to the line as a whole or the floating platform as a +whole. It is just a way of letting MoorDyn calculate the damping coefficient automatically +from the perspective of damping non-physical segment resonances. If the model is set up +right, this damping can have a negligible contribution to the overall damping provided by +the moorings on the floating platform. However, if the damping contribution of the mooring +lines on the floating platform is supposed to be significant, it is best to (1) set the BA +value directly to ensure that the expected damping is provided and then (2) adjust the number +of segments per line to whatever provides adequate numerical stability. + +Finally, to ensure stability the time step should be significantly smaller than +the natural period, + +.. math:: + + \Delta t < \frac{2 \pi}{\omega_n}. + +However, in contrast to the damping, which can be selected line by line, the +time step is a constant of the whole system, and thus should be selected +considering the minimum natural period of all lines. + +Python errors +------------- + +ModuleNotFoundError: No module named 'moordyn' +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +If you try to import MoorDyn into your Python file or shell and you receive the error +above, then the Python wrapper is not properly installed. First, if you compiled MoorDyn +by yourself check that PYTHON_WRAPPER option was ON while configuring with CMake. Another possible source for the error is that MoorDyn was installed for a different version of Python. That would happened if either CMake considered the -wrong version or you upgraded your Python installation. Either way, it is -recommended to install the MoorDyn Python wrapper again. +wrong version or you upgraded your Python installation. Either way, installing +the MoorDyn Python wrapper again should fix the problem. + +ImportError +^^^^^^^^^^^ +The import error can show up in a number of ways when importing the MoorDyn module into +Python: + +1. ImportError: dlopen(Python/3.9/lib/python/site-packages/cmoordyn.cpython-39-darwin.so, 0x0002): Library not loaded: @rpath/libmoordyn.2.dylib + Reason: tried: '/usr/local/lib/libmoordyn.2.dylib' (no such file), '/usr/lib/libmoordyn.2.dylib' (no such file, not in dyld cache). -ImportError: libmoordyn.so.2: cannot open shared object file: No such file or directory -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2. ImportError: libmoordyn.so.2: cannot open shared object file: No such file or directory. -If you type in a Python console +If you try to import MoorDyn into your Python file or shell: .. code-block:: python import moordyn moordyn.Create() -receiving the error above, then the Python wrapper has been correctly installed, +and you receive the error above, then the Python wrapper has been correctly installed, but the actual MoorDyn library cannot be found. This is generally caused by an -installation of MoorDyn in a custom path. You must locate where you have -installed the MoorDyn library and add that folder to the following environment -variables: +installation of MoorDyn in a custom path or when installing MoorDyn without admin +privileges. To resolve this error, add the path to the directory where the MoorDyn +library was installed to the following environment variables: -* LD_LIBRARY_PATH in Linux and MAC +* LD_LIBRARY_PATH in Linux and MAC (export LD_LIBRARY_PATH=) * PATH in Windows -Note that the error can be slightly different in Linux, Windows and MAC. +Another solution is to change the -DCMAKE_INSTALL_PREFIX flag for the +:ref:`CMake compile method ` to be the path until the lib folder where +python is searching for the library. For example, to resolve error 1 (installing without +admin privileges on MacOS), you would set -DCMAKE_INSTALL_PREFIX=/usr/local/ which would +copy the libraries in the correct place. The total CMake configure command would be: + +.. code-block:: none + + cmake -DCMAKE_INSTALL_PREFIX="/usr/local/" -DCMAKE_BUILD_TYPE=Release + DPYTHON_WRAPPER_USERINSTALL=ON ../ + +Note that this error can be slightly different in Linux, Windows, and MAC. diff --git a/docs/usage.rst b/docs/usage.rst deleted file mode 100644 index ebcf4cfc..00000000 --- a/docs/usage.rst +++ /dev/null @@ -1,643 +0,0 @@ -.. _usage: - -MoorDyn Usage -===================================================== - -.. - customize code highlight color through "hll" span css - -.. raw:: html - - - - - -.. role:: fast -.. role:: stnd - - -The v1 Input File ------------------ - -MoorDyn v1 uses a plain-text input file for its description of the mooring system as well as simulation settings. -This file is divided into sections identified by header lines. - -Most of the sections are set up to contain a table of input information. The FORTRAN/OpenFAST form of MoorDyn v1 -requires these section to start with a declaration of how many data rows will be in the table (e.g. "3 nLines"). -The C/standalone form of MoorDyn skips this. Lines that should only be the in the Fortran/OpenFAST for are -:fast:`shown in blue`. -Next, the table of each section begins with two preset lines that contain the column names and the corresponding units. -These lines are followed by any number of lines containing the entries in that section's -table of inputs. - - -Front matter -^^^^^^^^^^^^ - -The first 1-n lines of the input file are reserved for free-form user input, for labeling the input file, -writing notes, etc. - -.. code-block:: none - :emphasize-lines: 2 - - MoorDyn input file... - MoorDyn-F v2 sample input file - True Echo echo the input file data (flag) - -Line Types -^^^^^^^^^^ - -The Line Types section of the file contains one or more definitions of physical line properties and -four hydrodynamic coefficients. - -.. code-block:: none - :emphasize-lines: 2 - - ------------------------- LINE TYPES -------------------------------------------------- - 1 NTypes - the number of line types - LineType Diam MassDen EA BA/-zeta Can Cat Cdn Cdt - (-) (m) (kg/m) (N) (Pa-s/-) (-) (-) (-) (-) - nylon 0.124 13.76 2515288.0 -0.8 1.0 0.0 1.6 0.05 - -The columns in order are as follows: - - - Name – an identifier word for the line type - - 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) - - 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 – see Section 4.1 for more information) - - Can – transverse added mass coefficient (with respect to line displacement) - - Cat – tangential added mass coefficient (with respect to line displacement) - - Cdn – transverse drag coefficient (with respect to frontal area, d*l) - - Cdt – tangential drag coefficient (with respect to surface area, π*d*l) - - -Point Properties -^^^^^^^^^^^^^^^^^^^^^ - -The Point Properties section defines the point node points which mooring lines can be connected to. - -.. code-block:: none - :emphasize-lines: 2 - - ----------------------- POINT PROPERTIES ---------------------------------------------- - 3 NPoints - the number of points - Node Type X Y Z M V FX FY FZ CdA CA - (-) (-) (m) (m) (m) (kg) (m^3) (kN) (kN) (kN) (m^2) (-) - 1 Vessel 0.0 0 -10.00 0 0 0 0 0 0 0 - 2 Fixed 267.0 0 -70.00 0 0 0 0 0 0 0 - 3 Connect 0.0 0 -10.00 0 0 0 0 0 0 0 - -The columns are as follows: - - - Node – the ID number of the point (must be sequential starting with 1) - - Type – one of “Fixed”, “Vessel”, or “Connect”, as described :ref:`here ` - - X, Y, Z – Coordinates of the point (relative to inertial reference frame if “fixed” or “point”, - relative to platform reference frame if “vessel”). In the case of “point” nodes, it is simply an - initial guess for position before MoorDyn calculates the equilibrium initial position. (m) - - M – node mass in the case of clump weights (kg) - - V – node displacement in the case of floats (m^3) - - FX, FY, FZ – any steady external forces applied to the node (N) - - CdA – product of drag coefficient and projected area (assumed constant in all directions) to calculate a drag force for the node (m^2) - - Ca – added mass coefficient used along with V to calculate added mass on node - - -Lines list -^^^^^^^^^^ - -The Line Properties section defines each uniform-property section of mooring line to be simulated. - -.. code-block:: none - :emphasize-lines: 2 - - -------------------------- LINE PROPERTIES ------------------------------------------------- - 3 NLines - the number of lines - Line LineType UnstrLen NumSegs NodeA NodeB Flags/Outputs - (-) (-) (m) (-) (-) (-) (-) - 1 nylon 300.0 50 2 1 p - 2 nylon 300.0 50 4 3 p - 3 nylon 300.0 50 6 5 p - -The columns are as follows: - - - Line - the ID number of the line (must be sequential starting with 1) - - LineType - a string matching a Line Dictionary entry, specifying which physical properties it uses - - 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) - - NodeA - the ID number of the point that the first (anchor) end of the line is attached to - - NodeB - the ID number of the point that the final (fairlead) end of the line is attached to - - flags/outputs - 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 activating a given output property. -A placeholder character such as “-” should be used if no outputs are wanted. Eight output properties are currently possible: - - - p – node positions - - v – node velocities - - U – wave velocities at each node - - D – hydrodynamic drag force at each node - - t – tension force at each segment - - c – internal damping force at each segment - - s – strain of each segment - - d – rate of strain of each segment - -For example, outputting node positions and segment tensions could be achieved by writing “pt” for this last column. These outputs will go to a dedicated output file for each line only. For sending values to the global output file, use the Outputs section instead. - - - -Options -^^^^^^^ - -The Solver Options section can contain any number of optional settings for the overall model, including seabed properties, -initial condition (IC) generation settings, and the time step size. - -.. code-block:: none - - -------------------------- SOLVER OPTIONS--------------------------------------------------- - 0.001 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 - 0.001 ICthresh - threshold for IC convergence - 0 ICTmax - threshold for IC convergence (set to zero for debugging) - -Any of these lines can be omitted, in which case default values will be used. As such, they are all optional settings, -although some of them (such as time step size) often need to be set by the user for proper operation. -The list of possible options is: - - - dtM – desired mooring model time step (s) - - g – gravitational constant (m/s^2)* - - rhoW – water density (kg/m^3)* - - WtrDpth – water depth (m)* - - SeafloorFile – Relative path of a 3D Seafloor file - - kBot – bottom stiffness constant (Pa/m) - - cBot – bottom damping constant (Pa-s/m) - - dtIC – period for analyzing convergence of dynamic relaxation IC generation (s) - - TmaxIC – maximum simulation time to allow for IC generation without convergence (s) - - CdScaleIC – factor by which to scale drag coefficients to accelerate convergence of IC generation (-) - - ThreshIC – convergence threshold for IC generation, acceptable relative difference between three successive fairlead tension measurements (-) - -:fast:`In MoorDyn-F, the default values for g, rhoW, and WtrDpth are the values provided by FAST, so it is recommended to not use -custom values for the sake of consistency.` - -The bottom contact parameters, kBot and cBot, result in a pressure which is then applied to the cross-sectional area (d*l) -of each contacting line segment to give a resulting vertical contact force for each segment. - -Seafloor File -^^^^^^^^^^^^^ - -If you need the seafloor have different depths at different locations, it is possible to create and use a 3D Seafloor file. -This file allows you to define a square grid of points and define depths at each of these points. - -code-block:: none - num_x_points num_y_points - x_1 x_2 ... x_num_x_points - y_1 y_2 ... y_num_y_points - x_pos y_pos depth - x_pos y_pos depth - x_pos y_pos depth - etc, etc - -The two values on the first line define the number of points in each axis of the grid. -The second line defines the actual locations along the x axis for the x grid points. -The third line defines the locations along the y axis for the y grid points. -The remaining lines are (x, y, z) coordinates for the seafloor on grid points. -The order of these points is not important. -It is also important that the x_pos be a value found in line 2 and y_pos be a value found in line 3. -What happens if one of these points does not fall on the grid is not defined and may overwrite other depth values. - -If some part of the simulation fall outside of the defined grid area, it will use the depth of the nearest grid edge. - - -Outputs -^^^^^^^ - -The Outputs section is used to specify general outputs, which are written to the main MoorDyn output file -:fast:`and also sent to the driver program for inclusion in the global output file.` - -.. code-block:: none - :emphasize-lines: 8 - - ---------------------- OUTPUTS ----------------------------------------- - FairTen1 - FairTen2 - AnchTen1 - Con2px - Con2py - Con2Fz - END - ------------------------- need this line ------------------------------------- - - -Each output channel name should have its own line. There are intuitive keywords for fairlead and anchor tensions -of a given line: fairten# and anchten#, where # is the line number. -There is also a flexible naming system for outputting other quantities. -There are currently five supported types of output quantities: - - - pX, pY , pZ – x/y/z coordinate (m) - - vX, vY, vZ – velocity (m/s) - - aX, aY, aZ – acceleration (m/s^2) - - T or Ten – tension (N) - - fX, fY, fZ – net force in x/y/z direction (N) - -These can be produced at a point object, denoted by the prefix Con#, where # is the point number. -Or, they can be produced at a node along a line, denoted by the prefix L#N@, where # is the line number -and @ is the number of the node along that line. For example, - - - Con3vY outputs the point 3 y velocity, - - L2N4pX outputs the line 2, node 4 x position. - - - - -The v2 Input File ------------------ - -MoorDyn v2 uses a standardized plain-text input file for its description of the -mooring system and simulation settings that has some important additions and -changes from v1. - -Most helpfully, this new format is identical between C++ and FORTRAN versions of -MoorDyn, and it is designed to be support future capability enhancements without -requiring changes. - -This file is divided into sections, some of which are optional. Each section is -identified (and detected) by a header line consisting of a key phrase (e.g. Line -Types) surrounded by dashes. While a couple sections are optional, the order of -the sections should never be changed. - -Most of the sections are set up to contain a table of input information. These -tables begin with two preset lines that contain the column names and the -corresponding units. These lines are followed by any number of lines containing -the entries in that section's table of inputs. - -Front matter -^^^^^^^^^^^^ - -The first lines of the input file are reserved for free-form user input, for -labeling the input file, writing notes, etc. -There is not a limit on the number of lines you can write here. - -.. code-block:: none - - --------------------- MoorDyn Input File ------------------------------------ - MoorDyn-F v2 sample input file - - -Line Types -^^^^^^^^^^ - -This section (required if there are any mooring lines) describes the list of mooring line property sets -that will be used in the simulation - -.. code-block:: none - - ---------------------- LINE TYPES ----------------------------------- - TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx - (name) (m) (kg/m) (N) (N-s/-) (N-m^2) (-) (-) (-) (-) - Chain 0.1 150.0 1e8 -1 0 2.3 1 1.0 0.5 - -The columns in order are as follows: - - - Name – an identifier word for the line type - - 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) - - 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 – see Section 4.1 for more information) - - EI – the line bent stiffness, product of elasticity modulus and inertia of the cross-sectional area (N) - - Cd – transverse drag coefficient (with respect to frontal area, d*l) - - Ca – transverse added mass coefficient (with respect to line displacement) - - CdAx – tangential drag coefficient (with respect to surface area, π*d*l) - - CaAx – tangential added mass coefficient (with respect to line displacement) - -Non-linear values for the stiffness (EA), internal damping (BA/-zeta) and bent -stiffness (EI) are accepted. -To this end, a file can be provided (to be located in the same folder than the -main MoorDyn input file) instead of a number. -Such file is simply a tabulated file with 2 columns, separated by a blank space. -The columns to be provided for each non-linear magnitude are the followings: - - - Stiffness: Strain rate - EA/Stretching rate (N) - - Internal damping: Curvature - EI/Curvature (N-m^2) - - Bent stiffness: Stretching rate - Damping coefficient/Stretching rate (N-s^2/s) - - -Rod Types -^^^^^^^^^ - -This section (required if there are any rod objects) describes the list of rod property sets -that will be used in the simulation - -.. code-block:: none - - ---------------------- ROD TYPES ------------------------------------ - TypeName Diam Mass/m Cd Ca CdEnd CaEnd - (name) (m) (kg/m) (-) (-) (-) (-) - Buoy 10 1.0e3 0.6 1.0 1.2 1.0 - - -Bodies list -^^^^^^^^^^^ - -This section (optional) describes the 6DOF body objects to be simulated. - -.. code-block:: none - - ---------------------- BODIES --------------------------------------- - ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca* - (#) (word) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) - 1 coupled 0 0 0 0 0 0 0 0 0 0 0 0 - - -Rods list -^^^^^^^^^ - -This section (optional) describes the rigid Rod objects - -.. code-block:: none - - ---------------------- RODS ---------------------------------------- - ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs - (#) (name) (word/ID) (m) (m) (m) (m) (m) (m) (-) (-) - 1 Can Body1 0 0 2 0 0 15 8 p - 2 Can Body1Pinned 2 0 2 5 0 15 8 p - - -Points list -^^^^^^^^^^^ - -This section (optional) describes the Point objects - -.. code-block:: none - - ---------------------- POINTS --------------------------------------- - ID Attachment X Y Z Mass Volume CdA Ca - (#) (word/ID) (m) (m) (m) (kg) (mˆ3) (m^2) (-) - 1 Fixed -500 0 -150 0 0 0 0 - 4 Coupled 0 0 -9 0 0 0 0 - 11 Body2 0 0 1.0 0 0 0 0 - - -Lines list -^^^^^^^^^^ - -This section (optional) describes the Line objects, typically used for mooring lines or dynamic power cables - -.. code-block:: none - - ---------------------- LINES ---------------------------------------- - ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs - (#) (name) (ID) (ID) (m) (-) (-) - 1 Chain 1 2 300 20 p - - -Options -^^^^^^^ - -This section (required) describes the simulation options - -.. code-block:: none - - ---------------------- OPTIONS ----------------------------------------- - 0.002 dtM time step to use in mooring integration (s) - 3000000 kbot bottom stiffness (Pa/m) - 300000 cbot bottom damping (Pa-s/m) - 0.5 dtIC time interval for analyzing convergence during IC gen (s) - 10 TmaxIC max time for ic gen (s) - 0.001 threshIC threshold for IC convergence (-) - -Any of these lines can be omitted, in which case default values will be used. -As such, they are all optional settings, although some of them (such as time -step size) often need to be set by the user for proper operation. -The list of possible options is: - - - writeLog (0): If >0 a log file is written recording information. The bigger the number the more verbose. Please, be mindful that big values would critically reduce the performance! - - DT (0.001): The time step (s) - - tScheme (RK2): The time integrator. It should be one of Euler, Heun, RK2, RK4, AB2, AB3, AB4, BEuler2, BEuler3, BEuler4, BEuler5, Midpoint2, Midpoint3, Midpoint4, Midpoint5. RK stands for Runge-Kutta while AB stands for Adams-Bashforth - - g (9.81): The gravity acceleration (m/s^2) - - rho (1025): The water density (kg/m^3) - - WtrDpth (0.0): The water depth (m) - - kBot (3.0e6): The bottom stiffness (Pa/m) - - cBot (3.0e5): The bottom damping (Pa-s/m) - - dtIC (1.0): The time lapse between convergency checks during the initial condition computation (s) - - TmaxIC (120.0): The maximum simulation time to run in order to find a stationary initial condition (s) - - CdScaleIC (5.0): The damping scale factor during the initial condition computation - - threshIC (0.001): The lines tension maximum relative error to consider that the initial condition have converged - - WaveKin (0): The waves model to use. 0 = none, 1 = waves externally driven, 2 = FFT in a regular grid, 3 = kinematics in a regular grid, 4 = WIP, 5 = WIP, 7 = Wave Component Summing - - dtWave (0.25): The time step to evaluate the waves, only for wave grid (WaveKin = 3) (s) - - Currents (0): The currents model to use. 0 = none, 1 = steady in a regular grid, 2 = dynamic in a regular grid, 3 = WIP, 4 = WIP, 5 = 4D Current Grid - - UnifyCurrentGrid (1): When both waves and currents are defined using a grid method, you may want to pre-combine those grids into a single grid that stores the summed wave and current kinematics. When this option is 1 the wave grid points get the interpolated current grid values added to them. When this option is 0 the wave grid and current grid are kept separate. - - WriteUnits (1): 0 to do not write the units header on the output files, 1 otherwise - - FrictionCoefficient (0.0): The seabed friction coefficient - - FricDamp (200.0): The seabed friction damping, to scale from no friction at null velocity to full friction when the velocity is large - - StatDynFricScale (1.0): Rate between Static and Dynamic friction coefficients - - dtOut (0.0): Time lapse between the ouput files printing (s) - -Outputs -^^^^^^^ - -This section (optional) lists any specific output channels to be written in the main output file. The section -needs to end with another header-style line (as shown below) for the program to know when to end. :: - - ---------------------- OUTPUTS ----------------------------------------- - Body1Px - Body1Py - Body1Pz - Body1Roll - Body1Pitch - FairTen1 - FairTen2 - FairTen3 - AnchTen1 - AnchTen2 - AnchTen3 - END - ------------------------- need this line ------------------------------------- - -General output suffixes - -============== ======================== ======= ===== ===== ===== ===== -Suffix Description Units Node Point Rod Body -============== ======================== ======= ===== ===== ===== ===== -PX/PY/PZ Position coordinates [m] X X X X -VX/VY/VZ Velocity components [m/s] X X X X -Ax/Ay/AZ Acceleration components [m/s^2] X X X X -T Tension or net force [N] X X X X -Fx/Fy/Fz Force components [N] X X X X -Roll/Pitch/Yaw Orientation angles [deg] X X -Sub Fraction of submergence [0-1] X -============== ======================== ======= ===== ===== ===== ===== - -The v2 snapshot file --------------------- - -In MoorDyn v2 two new functions have been added: - -.. doxygenfunction:: MoorDyn_Save -.. doxygenfunction:: MoorDyn_Load - -With the former a snapshot of the simulation can be saved, in such a way it can -be resumed in a different session using the latter function. -It is anyway required to create the system using the same input file in both -sessions. -But the initial condition computation could be skip in the second session -calling - -.. doxygenfunction:: MoorDyn_Init_NoIC - - - - - -MoorDyn with FAST.Farm ----------------------- - -In FAST.Farm, a new ability to use MoorDyn at the array level to simulate shared mooring systems has been develop. -Until the main branch of OpenFAST, the FAST.Farm capability, and the MoorDyn v2 capability are merged, -the shared moorings capability in FAST.Farm uses the MoorDyn-F v1 input file format, with a -small adjustment to reference attachments to multiple turbines. - -https://github.com/mattEhall/openfast/tree/f/fast-farm - -General Organization -^^^^^^^^^^^^^^^^^^^^ - -The regular ability for each OpenFAST instance to have its own MoorDyn simulation is unchanged in FAST.Farm. This -ability can be used for any non-shared mooring lines in all cases. To enable simulation of shared mooring lines, -which are coupled with multiple turbines, an additional farm-level MoorDyn instance has been added. This MoorDyn -instance is not associated with any turbine but instead is called at a higher level by FAST.Farm. Attachments -to different turbines within this farm-level MoorDyn instance are handled by specifying "TurbineN" as the type -for any points that are attached to a turbine, where "N" is the specific turbine number as listed in the -FAST.Farm input file. - - -MoorDyn Input File -^^^^^^^^^^^^^^^^^^ - -The following input file excerpt shows how points can be specified as attached to specific turbines (turbines -3 and 4 in this example). When a point has "TurbineN" as its type, it acts similarly to a "Vessel" type, where -the X/Y/Z inputs specify the relative location of the fairlead on the platform. In the farm-level MoorDyn input -file, "Vessel" point types cannot be used because it is ambiguous which turbine they attach to. - -.. code-block:: none - :emphasize-lines: 5,6,12 - - ----------------------- POINTS ---------------------------------------------- - Node Type X Y Z M V CdA CA - (-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) - 1 Turbine3 10.0 0 -10.00 0 0 0 0 - 3 Turbine4 -10.0 0 -10.00 0 0 0 0 - 2 Fixed 267.0 80 -70.00 0 0 0 0 - -------------------------- LINE PROPERTIES ------------------------------------------------- - 2 NLines - the number of lines - Line LineType UnstrLen NumSegs NodeA NodeB Flags/Outputs - (-) (-) (m) (-) (-) (-) (-) - 1 sharedchain 300.0 20 1 2 p - 2 anchorchain 300.0 20 1 3 p - -In this example, Line 1 is a shared mooring line and Line 2 is an anchored mooring line that has a fairlead point -in common with the shared line. Individual mooring systems can be modeled in the farm-level MoorDyn instance as well. - - - -FAST.Farm Input File -^^^^^^^^^^^^^^^^^^^^ - -In the branch of FAST.Farm the supports shared mooring capabilities, several additional lines have been added to the -FAST.Farm primary input file. These are highlighted in the example input file excerpt below - - -.. code-block:: none - :emphasize-lines: 9,10,13,14,15 - - FAST.Farm v1.10.* INPUT FILE - Sample FAST.Farm input file - --- SIMULATION CONTROL --- - False Echo Echo input data to .ech? (flag) - FATAL AbortLevel Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} - 2000.0 TMax Total run time (s) [>=0.0] - False UseSC Use a super controller? (flag) - 1 Mod_AmbWind Ambient wind model (-) (switch) {1: high-fidelity precursor in VTK format, 2: one InflowWind module, 3: multiple instances of InflowWind module} - 2 Mod_WaveField Wave field handling (-) (switch) {1: use individual HydroDyn inputs without adjustment, 2: adjust wave phases based on turbine offsets from farm origin} - 3 Mod_SharedMooring Shared mooring system model (-) (switch) {0: None, 3: MoorDyn} - --- SUPER CONTROLLER --- [used only for UseSC=True] - "SC_DLL.dll" SC_FileName Name/location of the dynamic library {.dll [Windows] or .so [Linux]} containing the Super Controller algorithms (quoated string) - --- SHARED MOORING SYSTEM --- [used only for Mod_SharedMooring > 0] - "FarmMoorDyn.dat" FarmMoorDynFile Name of file containing shared mooring system input parameters (quoted string) [used only when Mod_SharedMooring > 0] - 0.01 DT_Mooring Time step for farm-level mooring coupling with each turbine (s) [used only when Mod_SharedMooring > 0] - --- AMBIENT WIND: PRECURSOR IN VTK FORMAT --- [used only for Mod_AmbWind=1] - 2.0 DT_Low-VTK Time step for low -resolution wind data input files ; will be used as the global FAST.Farm time step (s) [>0.0] - 0.3333333 DT_High-VTK Time step for high-resolution wind data input files (s) [>0.0] - "Y:\Wind\Public\Projects\Projects F\FAST.Farm\AmbWind\steady" WindFilePath Path name to VTK wind data files from precursor (string) - False ChkWndFiles Check all the ambient wind files for data consistency? (flag) - --- AMBIENT WIND: INFLOWWIND MODULE --- [used only for Mod_AmbWind=2 or 3] - 2.0 DT_Low Time step for low -resolution wind data interpolation; will be used as the global FAST.Farm time step (s) [>0.0] - - - - - - -Advice and Frequent Problems ----------------------------- - - -Model Stability and Segment Damping -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -Two of the trickier input parameters are the internal damping (BA) for each line type, and the mooring simulation time step (dtM). -Both relate to the discretization of the lines. -The highest axial vibration mode of the lumped-mass cable representation would be when adjacent nodes -oscillate out of phase with each other, as depicted below. - -In this mode, the midpoint of each segment would not move. The motion of each node can then be -characterized by mass-spring-damper values of - -.. math:: - - m = w \frac{L}{N}, \\ c = 4 B A \frac{N}{L}, \\ k = 4 E A \frac{N}{L}. - -The natural frequency of this mode is then - -.. math:: - - \omega_n = \sqrt{\frac{k}{m}} = \frac{2}{l} \sqrt{\frac{E A}{w}}=2 \frac{N}{L} \sqrt{\frac{E A}{w}} - -and the damping ratio, ζ, is related to the internal damping coefficient, BA, by - -.. math:: - - \zeta =\frac{c}{c_{crit}} = \frac{B}{l} \sqrt{\frac{A}{E w}} = B A \frac{N}{L} \sqrt{\frac{1}{E A w}}, \\ B A= \zeta \frac{L}{N} \sqrt{E A w}. - -The line dynamics frequencies of interest should be lower than ω_n in order to be resolved by the model. -Accordingly, line dynamics at ω_n, which are likely to be dominated by the artificial resonance created -by the discretization, can be damped out without necessarily impacting the line dynamics of interest. -This is advisable because the resonances at ω_n can have a large impact on the results. -To damp out the segment vibrations, a damping ratio approaching the critical value (ζ=1) is recommended. -Care should be taken to ensure that the line dynamics of interest are not affected. - -To simplify things, a desired line segment damping ratio can be specified in the input file. This is done -by entering the negative of the desired damping ratio in the BA/-zeta field of the Line Types section. -A negative value here signals MoorDyn to interpret it as a desired damping ratio and then calculate the -damping coefficient (BA) for each mooring line that will give every line segment that damping ratio -(accounting for possible differences in segment length between lines). - -Note that the damping ratio is with respect to the critical damping of each segment along a mooring -line, not with respect to the line as a whole or the floating platform as a whole. It is just a way -of letting MoorDyn calculate the damping coefficient automatically from the perspective of damping -non-physical segment resonances. If the model is set up right, this damping can have a negligible -contribution to the overall damping provided by the moorings on the floating platform. However, if -the damping contribution of the mooring lines on the floating platform is supposed to be significant, -it is best to (1) set the BA value directly to ensure that the expected damping is provided and then -(2) adjust the number of segments per line to whatever provides adequate numerical stability. - -Finally, to ensure stability the time step should be significantly smaller than -the natural period, - -.. math:: - - \Delta t < \frac{2 \pi}{\omega_n}. - -However, in contrast to the damping, which can be selected line by line, the -time step is a constant of the whole system, and thus should be selected -considering the minimum natural period of all lines. diff --git a/docs/version2.rst b/docs/version2.rst deleted file mode 100644 index 4c7955c0..00000000 --- a/docs/version2.rst +++ /dev/null @@ -1,16 +0,0 @@ -.. _version-2: - -Changes for Version 2 -===================================================== - -Features of MoorDyn v2 include - -- rigid bodies -- rigid cylindrical Rod objects, with surface-piercing capabilities -- wave kinematics -- bending stiffness for power cable simulation -- pinned (3 DOF) and rigid (6 DOF) coupling options - -Some more information is in https://www.nrel.gov/docs/fy20osti/76555.pdf - -This page will be expanded and updated as version 2 progresses. diff --git a/docs/waterkinematics.rst b/docs/waterkinematics.rst index 92c309a5..d8a5174e 100644 --- a/docs/waterkinematics.rst +++ b/docs/waterkinematics.rst @@ -1,22 +1,20 @@ -.. _waterkinematics: - -Water Kinematics In MoorDyn +Water Kinematics in MoorDyn =========================== - +.. _waterkinematics: MoorDyn has support for specifying water currents as well as waves in a variety of ways. - -Wave Kinematics Options ------------------------ +Wave Kinematics (MoorDyn-C) +--------------------------- +Below are the possible values for the WaveKin option in the MoorDyn-C input file along with +descriptions and instructions for use. WaveKin = 0 (None) ^^^^^^^^^^^^^^^^^^ Assumes there are no waves. -The water surface is still at z=0.0 - +The water surface is still and at z=0.0. WaveKin = 1 (Externally Driven Waves) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -30,8 +28,8 @@ and set the wave kinematics as frequently as you want. .. doxygenfunction:: MoorDyn_ExternalWaveKinGetCoordinates .. doxygenfunction:: MoorDyn_ExternalWaveKinSet -A standard usage of external wave kinematics would be in some situations where you have your own code or an external program -computing the fluid dynamics and you want MoorDyn to use those values. +A standard usage of external wave kinematics would be in some situations where you have your own +code or an external program computing the fluid dynamics and you want MoorDyn to use those values. Below is an example program demonstrating basic usage of external wave kinematics. @@ -45,12 +43,12 @@ Below is an example program demonstrating basic usage of external wave kinematic { // this function could call an external program, do its own computation, // lookup a precalculated value, etc - u[0] = 1.0; // x velocity - u[1] = 0.0; // y velocity - u[2] = 0.0; // z velocity - du[0] = 0.0; // x acceleration - du[1] = 0.0; // y acceleration - du[2] = 0.0; // z acceleration + u[0] = 1.0; // x velocity + u[1] = 0.0; // y velocity + u[2] = 0.0; // z velocity + du[0] = 0.0; // x acceleration + du[1] = 0.0; // y acceleration + du[2] = 0.0; // z acceleration } void main() { @@ -140,20 +138,25 @@ Below is an example program demonstrating basic usage of external wave kinematic **NOTES:** -- Previous versions of MoorDyn did acceleration based velocity interpolation and allowed for defining wave kinematics at times in the future to be interpolated to. The current version of MoorDyn does not have this capability. -- When you set the wave kinematics for the nodes, those values are used for every calculation until you set them again. -- You should set the external wave kinematics frequently enough to keep any error introduced by that to acceptable levels. -- External Waves do no have the capability of defining a variable surface height. If this is needed you must use one of the other wave options. -- The external wave option can also be used for currents, but can also be combined with currents set using one of the current options. - +- Previous versions of MoorDyn did acceleration based velocity interpolation and allowed for + defining wave kinematics at times in the future to be interpolated to. The current version of + MoorDyn does not have this capability. +- When you set the wave kinematics for the nodes, those values are used for every calculation until + you set them again. +- You should set the external wave kinematics frequently enough to keep any error introduced by + that to acceptable levels. +- External Waves do not have the capability of defining a variable surface height. If this is + needed, you must use one of the other wave options. +- The external wave option can also be used for currents but can also be combined with currents set + using one of the current options. WaveKin = 2 (Wave FFT Grid) ^^^^^^^^^^^^^^^^^^^^^^^^^^^ **NOTE:** -This method currently cannot be counted on to always provide the expected water kinematics especially for low resolution spectra. -See below for a description of the problems to determine if they would affect your use case. - +This method currently cannot be counted on to always provide the expected water kinematics +especially for low resolution spectra. See below for a description of the problems to determine +if they would affect your use case. The grid methods are based around precomputing a 4 dimensional (x, y, z, t) grid of wave kinematics information that can be linearly interpolated within @@ -184,7 +187,7 @@ frequency with spacing equal to the smallest difference between subsequent frequencies in the input file. The angular direction can be different between different frequency components, but you cannot have components with the same frequency but different directions. In most cases this is most useful to set -all of the waves going in a single direction. If an angular direction is not +all the waves going in a single direction. If an angular direction is not provided for a line, MoorDyn uses the default value of 0.0. Very similar to WaveGrid except that instead of a wave_elevation.txt file, it @@ -193,9 +196,11 @@ components at some set of angular velocities (rad/s). Then after that it is the same as Wave Grid, in that is precalculates along a grid defined in water_grid.txt. - **The Problems with Wave FFT Grid** -The way that inverse FFT's work means that they expect sinc interpolation between points but currently the interpolation between samples is linear. A example of this is shown below, a graph of the surface elevation at x = 0, y = 0 is shown for a wave_frequencies.txt file of + +The way that inverse FFT's work means that they expect sine interpolation between points but +currently the interpolation between samples is linear. An example of this is shown below, a graph +of the surface elevation at x = 0, y = 0 is shown for a wave_frequencies.txt file of .. code-block:: @@ -207,7 +212,8 @@ The way that inverse FFT's work means that they expect sinc interpolation betwee .. figure:: waves_fft_problem.png :alt: A graph comparing MoorDyn surface elevation and the correct surface elevation - Linear interpolation between points can skip peaks, and interpolation at the end of the period is incorrect. + Linear interpolation between points can skip peaks, and interpolation at the end of the period + is incorrect. The general solution to this is to provide more frequencies, specifically higher frequencies. Due to the nature of IFFTs the resulting time between the @@ -217,7 +223,7 @@ frequencies in the linearly interpolated input spectrum. The value nt is 2 * (N interpolation). This means to decrease the time between the resulting samples, you want to have more samples with the same distance between their frequencies, so higher frequencies. This comes at the cost of memory usage -for the wave grid, so if you end up wanting a high resolution wave grid, you +for the wave grid, so if you end up wanting a high-resolution wave grid, you may want to consider switching to the new component summing wave mode. The FFT wave mode also is susceptible to generating incorrect data when the @@ -249,37 +255,33 @@ odd number of samples after down sampling). Internally, this mode performs an FFT to get the spectrum data, and then uses that data as an input to the FFT Grid mode. -This means that the problem of that mode (linear interpolation and loss of accuracy when doing large time steps) -also affect Wave Grid. -To avoid these issues you should try and use a relatively small value of ``dtWave`` as well as -manually verify the wave kinematics. +This means that the problem of that mode (linear interpolation and loss of accuracy when doing +large time steps) also affect Wave Grid. To avoid these issues you should try and use a relatively +small value of ``dtWave`` as well as manually verify the wave kinematics. -To see examples of the inputs files for Wave Grid you can look in the ``tests/Mooring/wavekin_2/`` +To see examples of the inputs files for Wave Grid you can look in the ``tests/Mooring/wavekin_2/`` folder to see examples of the wave elevation file and wave grid file. WaveKin = 4 (Wave FFT Node) ^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Not implemented. - +Not yet implemented. -This options would allow for defining a wave frequency spectrum +This option would allow for defining a wave frequency spectrum that would be used to precalculate wave properties at line nodes. -Makes the assumption that the line nodes do not move substantially over time. - +It makes the assumption that the line nodes do not move substantially over time. WaveKin = 5 (Wave Node) ^^^^^^^^^^^^^^^^^^^^^^^ -Not implemented. - +Not yet implemented. WaveKin = 6 (Wave Kin) ^^^^^^^^^^^^^^^^^^^^^^ -Not implemented. +Not yet implemented. -This options would allow for defining a 4d grid (x, y, z, t) for water +This option would allow for defining a 4d grid (x, y, z, t) for water velocities, accelerations, and wave elevations. WaveKin = 7 (Summing Component Waves) @@ -291,42 +293,42 @@ calculates wave kinematics at the location of every structural node. The summing component waves option looks for a ``wave_frequencies.txt`` file with the same format as is specified in the Wave FFT Grid section. -Unlike Wave FFT Grid, this option does no sort of interpolation or modification to the input data. +Unlike Wave FFT Grid, this option does no interpolation or modification to the input data. This means that you can define a spectrum with irregularly spaced, or duplicated frequencies. This allows you to define a multiple spectrum with different directions in a single input file. -Then, at whatever frequencies is set for updating wave kinematics, the effect of each spectrum component -on every structural node will be calculated and summed to calculate the surface height, water velocity, -and water acceleration at that point at that time. +Then, at whatever frequencies that are set for updating wave kinematics, the effect of each +spectrum component on every structural node will be calculated and summed to calculate the surface +height, water velocity, and water acceleration at that point at that time. -The major advantage of this mode is that when wave kinematics are calculated, they are fully accurate -for the time when they are calculated, and there are no potential issues with interpolation or -loss of accuracy from large spectrum spacing like with the FFT Grid option. -The downside is that compared to a precalculated wave grid, it is more computationally expensive to +The major advantage of this mode is that when wave kinematics are calculated, they are highly +accurate for the time when they are calculated, and there are no potential issues with +interpolation or loss of accuracy from large spectrum spacing like with the FFT Grid option. The +downside is that compared to a precalculated wave grid, it is more computationally expensive to calculate the wave kinematics at a given point. - -Current Modes and Options -------------------------- +Currents (MoorDyn-C) +-------------------- +Below are the possible values for the Currents option in the MoorDyn-C input file along with +descriptions and instructions for use. Currents = 0 (No Currents) ^^^^^^^^^^^^^^^^^^^^^^^^^^ This is the default option and specifies no currents (there still could be waves). - Currents = 1 (Steady Currents Grid) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -This option allows you to specify a constant depth-dependent fluid velocity. -You can specify a constant fluid velocity in the x, y, and z direction for some set of depths. -The fluid velocity at some point will be determined by interpolating between the nearest z-plane above and below that point. -If the point is beyond the range of z values it will use the closest value. +This option allows you to specify a constant depth-dependent fluid velocity. You can specify a +constant fluid velocity in the x, y, and z direction for some set of depths. The fluid velocity at +some point will be determined by linearly interpolating between the nearest z-plane above and below +that point. If the point is beyond the range of z values, it will use the closest value. The current profile is read in from a ``current_profile.txt`` in the same folder as the model file. -The first three lines are ignored and the remaining lines should have the four space separated numbers. -Each line is parsed as: +The first three lines are ignored, and the remaining lines should have the four space separated +numbers. Each line is parsed as: .. code-block:: @@ -334,11 +336,11 @@ Each line is parsed as: **Example current_profile.txt file** -This example defines a current that increases with depth, with the water surface having no current, all the points below z = -10 has a current of 1.25m/s in the x direction. The points between z = 0 and z = -10 are calculated by interpolating between the neighbooring values. - -Ex: +This example defines a current that increases with depth, with the water surface having no current, +all the points below z = -10 has a current of 1.25m/s in the x direction. The points between z = 0 +and z = -10 are calculated by interpolating between the neighboring values. -The current at point ``(10, -6, -5.5)`` would be ``(0.65, 0.0, 0.0)`` +For example, the current at point ``(10, -6, -5.5)`` would be ``(0.65, 0.0, 0.0)`` .. code-block:: @@ -360,15 +362,19 @@ The current at point ``(10, -6, -5.5)`` would be ``(0.65, 0.0, 0.0)`` Currents = 2 (Dynamic Currents Grid) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -The dynamic currents grid allows for specifying a depth-dependent water velocity that changes over time. +The dynamic currents grid allows for specifying a depth-dependent water velocity that changes over +time. -The first 4 lines of the file are ignored, then it expects a line of space separated depth values that defines the depth values where current velocities will be defined. -Then line 6 of the file is ignored, and the remaining lines are used to define the currents at the defined depths for a series of times. -Those data lines start with the time they are defining currents for, and then have velocity components for each of the depths at that time. -The velocities can be defined along just the x axis, the x and y axis, or the x, y, and z axis. -When defining the velocity along multiple axis you first list all the x components by depth, and then all the y components by depth, and then all the z components by depth. +The first 4 lines of the file are ignored, then it expects a line of space separated depth values +that defines the depth values where current velocities will be defined. Then line 6 of the file is +ignored, and the remaining lines are used to define the currents at the defined depths for a series +of times. Those data lines start with the time they are defining currents for, and then have +velocity components for each of the depths at that time. The velocities can be defined along just +the x axis, the x and y axis, or the x, y, and z axis. When defining the velocity along multiple +axis you first list all the x components by depth, and then all the y components by depth, and then +all the z components by depth. -For example if you are defining currents at 5 depths, then a data line could look like +For example, if you are defining currents at 5 depths, then a data line could look like