diff --git a/README.md b/README.md index e609410f..cc883c90 100644 --- a/README.md +++ b/README.md @@ -7,6 +7,7 @@ MoorDyn is a lumped-mass model for simulating the dynamics of mooring systems co license. Read the docs here: [moordyn.readthedocs.io](https://moordyn.readthedocs.io/en/latest/) +Example uses and instructions here: [Examples](https://github.com/FloatingArrayDesign/MoorDyn/tree/dev/example) 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 and bodies. @@ -21,7 +22,7 @@ MoorDyn-C. The dev branch contains new features currently in development. The v1 [National Renewable Energy Laboratory (NREL)](https://www.nrel.gov/): - - [Matt Hall](http://matt-hall.ca/moordyn.html) + - Matt Hall - Ryan Davies - Andy Platt - Stein Housner diff --git a/docs/compiling.rst b/docs/compiling.rst index 043cfe7e..bd5e7298 100644 --- a/docs/compiling.rst +++ b/docs/compiling.rst @@ -5,8 +5,8 @@ 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 +version of MoorDyn v1. You can read more on the :ref:`home page `. It includes the +capability to simulate rigid bodies, nonlinear tension, wave kinematics, bending stiffness, and more. Further details can be found in the :ref:`theory section ` and :ref:`structure section `. @@ -70,7 +70,7 @@ This can be done by executing the following command: Linux ^^^^^ -Some GNU/Linux distributions have already packages deployed for their package +Some GNU/Linux distributions already have packages deployed for their package managers, which would make your life way easier. Otherwise, a self-extracting package is also provided. @@ -96,7 +96,7 @@ However, it is strongly recommended to compile it yourself with To use the self-extracting package head your browser to the `releases page `_, select/expand the latest release, download the file named -"Moordyn-X.Y.Z-Linux.sh" (with X.Y.Z the specific version you chosen) and +"Moordyn-X.Y.Z-Linux.sh" (with X.Y.Z being the specific version you choose) and execute it. NOTE: The self-extracting file you have downloaded cannot be executed until you diff --git a/docs/drivers.rst b/docs/drivers.rst index 1e360119..c5115593 100644 --- a/docs/drivers.rst +++ b/docs/drivers.rst @@ -8,6 +8,10 @@ MoorDyn-F contains a driver script that has a :ref:`separate input file ` and :ref:`inputs ` sections for instructions on how to use the MoorDyn-F driver. +Additionally, MoorDyn-F has a c-bindings interface, which allows it (along with the rest +of OpenFAST) to be coupled with other languages. The MoorDyn-F C interface is set up using +the MoorDyn V1 approach (single 6 DOF coupling), thus it requires a single coupled body to +be used in the MoorDyn input file. 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 @@ -80,6 +84,8 @@ MoorDyn-C can be compiled as a dynamically linked library with C bindings or a m sophisticated API functions and wrappers, making it accessible from a wide range of programming languages. +Further examples of MoorDyn-C drivers with input files can be found in the `examples folder `_. + Python ^^^^^^ .. _python_wrapper: @@ -127,11 +133,9 @@ control: for node_id in range(n_segs+1): print(" node {}:".format(node_id)) pos = moordyn.GetLineNodePos(line, node_id) - printf(" pos = {}".format(pos)) + print(" pos = {}".format(pos)) ten = moordyn.GetLineNodeTen(line, node_id) - printf(" ten = {}".format(ten)) - } - } + print(" ten = {}".format(ten)) # Alright, time to finish! moordyn.Close(system) @@ -811,3 +815,15 @@ 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. +OpenFOAM +^^^^^^^^ + +MoorDyn-C has been coupled with OpenFOAM through the `foamMooring `_ project. + +Bladed +^^^^^^ + +MoorDyn V1 has been coupled with DNV's Bladed software. See the following links for details: + +- `MoorDyn-Bladed Coupling Documentation `_ +- `MoorDyn-Bladed Coupling Theory `_ \ No newline at end of file diff --git a/docs/index.rst b/docs/index.rst index 625623fc..b3270a3c 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -87,9 +87,13 @@ for the use of the MoorDyn-F driver can be found :ref:`here `. 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 +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 `. +scripts are available :ref:`here `. + +Additionally, an example directory contains instructions for common couplings +and basic input file set ups. A recording of the presentation that walks through +the directory is also available `here `_. Table of Contents: ------------------ diff --git a/docs/inputs.rst b/docs/inputs.rst index 2721d319..4ac84b86 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -247,10 +247,10 @@ 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. # is the general comment chacater. If you are adding notes +the entries in that section's table of inputs. # is the general comment character. If you are adding notes to self after any of the lines, # will prevent MoorDyn from reading them. -Examples of input files for MoorDyn-C can be found in the `test directory `_ (note that these do not include outputs becasue they are for tests). +Examples of input files for MoorDyn-C can be found in the `test directory `_ (note that these do not include outputs because they are for tests). Examples for MoorDyn-F can be found in the `OpenFAST tests `_. @@ -301,9 +301,9 @@ The columns in order are as follows: for end nodes (and thus end half-segments), so if simulating VIV users should ensure to include a higher number of segments. Also note that VIV has only been tested with explicit time schemes (specifically rk2 and rk4). There may be unexpected behavior if used with an implicit time scheme. - - dF - OPTIONAL - the cF +- range of non-dimensional frequnecies for the CF VIV synchronization model. If it is not + - dF - OPTIONAL - the cF +- range of non-dimensional frequencies for the CF VIV synchronization model. If it is not provided and VIV is enabled (Cl > 0) then it is default to 0.08 to align with the the theory found :ref:`here ` - - cF - OPTIONAL - the center of the range of non-dimensional frequnecies for the CF VIV synchronization model. If it is not + - cF - OPTIONAL - the center of the range of non-dimensional frequencies for the CF VIV synchronization model. If it is not provided and VIV is enabled (Cl > 0) then it is default to 0.18 to align with the the theory found :ref:`here ` Note: Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file @@ -320,10 +320,10 @@ tabulated file with 3 header lines and then a strain column and a tension column ... ... Note: MoorDyn has the ability to model the viscoelastic properties of synthetic lines in two ways. The first method, from work linked in the -:ref:`theory section `, allows a user to specify a bar-seperated constant dynamic and static stiffness. The second method allows the user +:ref:`theory section `, allows a user to specify a bar-separated constant dynamic and static stiffness. The second method allows the user to provide a constant static stiffness and two terms to determine the dynamic stiffness as a linear function of mean load. The equation is: `EA_d = EA_Dc + EA_D_Lm * mean_load` where `EA_D_Lm` is the slope of the load-stiffness curve. Both of these methods allow users to provide static -and dynamic damping coefficients as values seperated by |. While the static damping can be described as a fraction of cricial, the dyanamic damping +and dynamic damping coefficients as values separated by |. While the static damping can be described as a fraction of critical, the dynamic damping needs to be input as a value. Example inputs are below: .. code-block:: none @@ -822,7 +822,7 @@ Footnotes: - 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. -- The output list is not case sensistive, however all MoorDyn-F outputs will be printed to the output +- The output list is not case sensitive, however all MoorDyn-F outputs will be printed to the output file in all caps. When searching OpenFAST output channels, users will need to search for MoorDyn channels in all caps. Example: the channel fairten1 would appear in the output file as FAIRTEN1. @@ -886,11 +886,11 @@ follows the order of the state vector: Body degrees of freedom, rod degrees of f degrees of freedom. For coupled pinned bodies and rods the full 6DOF need to be provided, however the rotational values will be ignored by by the MoorDyn-F driver (they can be set to zero). -When using the MoorDyn driver in OpenFAST mode, the inital positions represents the offsets to the +When using the MoorDyn driver in OpenFAST mode, the initial positions represents the offsets to the global frame. When using OpenFAST mode with the positions set to 0's, then MoorDyn objects will be simulated based on the positions defined in the MoorDyn input file. If a non-zero value is provided, -it will be incorporated into the inital positions of coupled objects. For example, if the following -inital positions are given: +it will be incorporated into the initial positions of coupled objects. For example, if the following +initial positions are given: .. code-block:: none @@ -1004,8 +1004,8 @@ data. 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 + 1500 0.2 0.0 + 5000 0.15 0.0 --------------------- need this line ------------------ MoorDyn-F with FAST.Farm - Inputs diff --git a/docs/integration_moordyn.png b/docs/integration_moordyn.png index d21c3bdf..9cb55049 100644 Binary files a/docs/integration_moordyn.png and b/docs/integration_moordyn.png differ diff --git a/docs/references.rst b/docs/references.rst index 24cb6c47..a6e24059 100644 --- a/docs/references.rst +++ b/docs/references.rst @@ -97,15 +97,30 @@ Non-linear line stiffness: `Lozon, Ericka, Matthew Hall, Paul McEvoy, Seojin Kim, and Bradley Ling, “Design and Analysis of a Floating-Wind Shallow-Water Mooring System Featuring Polymer Springs.” American Society of Mechanical Engineers Digital Collection, 2022. `_ +Bladed-MoorDyn Coupling: + + `Alexandre, Armando, Francesc Fabregas Flavia, Jingyi Yu, Ali Bakhshandehrostami, and Steven Parkinson. "Coupling Bladed With External Finite-Element Mooring Libraries." + American Society of Mechanical Engineers Digital Collection, 2023. `_ + Viscoelastic approach for non-linear rope behavior: `Hall, Matthew, Brian Duong, and Ericka Lozon, “Streamlined Loads Analysis of Floating Wind Turbines With Fiber Rope Mooring Lines.” In ASME 2023 5th International Offshore Wind Technical Conference, V001T01A029. Exeter, UK: American Society of Mechanical Engineers, 2023. `_ Updated MoorDyn-OpenFOAM Coupling: + `Haifei Chen, Tanausú Almeida Medina, and Jose Luis Cercos-Pita, "CFD simulation of multiple moored floating structures using OpenFOAM: An open-access mooring restraints library." Ocean Engineering, vol. 303, Jul. 2024. `_ +Reef3D-MoorDyn Coupling: + + `Soydan, Ahmet, Widar Weizhi Wang, and Hans Bihs. "An Improved Direct Forcing Immersed Boundary Method With Integrated Mooring Algorithm for Floating Offshore Wind + Turbines." American Society of Mechanical Engineers Digital Collection, 2024. `_ + +Modeling of Bi-stable Nonlinear Energy Sinks in MoorDyn (most recent description of MoorDyn theory): + + `Anargyros Michaloliakos, Wei-Ying Wong, Ryan Davies, Malakonda Reddy Lekkala, Matthew Hall, Lei Zuo, Alexander F. Vakakis, "Stabilizing dynamic subsea power cables using + Bi-stable nonlinear energy sinks", Ocean Engineering, vol. 334, August 2025. `_ The Fortran version of MoorDyn is available as a module inside of OpenFAST: diff --git a/docs/structure.rst b/docs/structure.rst index c4c71d53..06535e3f 100644 --- a/docs/structure.rst +++ b/docs/structure.rst @@ -7,8 +7,8 @@ main object types: Lines, Points, Rods, and Bodies. MoorDyn v1 only contained Li 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 +ways of interacting. Kinematics are passed from the top down and are used to calculate the +forces which are passed back up to the outside program or to output channels. This hierarchy is shown below: .. figure:: structure_moordyn.png diff --git a/docs/troubleshooting.rst b/docs/troubleshooting.rst index 33dc5160..e6ef0a5a 100644 --- a/docs/troubleshooting.rst +++ b/docs/troubleshooting.rst @@ -52,7 +52,7 @@ Note that the damping ratio is with respect to the critical damping of each segm 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 +correctly, 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 @@ -69,6 +69,26 @@ 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. +Catenary Solve Unsuccessful +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +One of the most common issues encountered when using MoorDyn is the failure of the +catenary solver to converge. The catenary solver is the first step in solving the +initial conditions of the system. This approach tries to use the properties and geometry +of the mooring lines to solve for a catenary shape. + +If this routine fails, you will see a "Catenary solve unsuccessful" message in the +the console and the log file. This means that MoorDyn will initialize the lines +as linear between the two defined end locations. After this, the ICgen process begins, +which runs a simulation with no external forcing, allowing the lines to 'fall' into +place. If the lines initialize as linear, then the initialization process will just take +longer, requiring a larger `TmaxIC` value. Explanations about the different initial +condition generating methods can be found in the :ref:`initialization section `. + +The "Catenary Solve Unsuccessful" message does not impact the performance of MoorDyn or +the results it produces, provided the initialization process converges before the simulation +begins. + Python errors ^^^^^^^^^^^^^ diff --git a/docs/waterkinematics.rst b/docs/waterkinematics.rst index 88bb3f5f..7708652a 100644 --- a/docs/waterkinematics.rst +++ b/docs/waterkinematics.rst @@ -500,20 +500,20 @@ Water Kinematics (MoorDyn-F) MoorDyn-F has three options for simulating wave and current loads on the MoorDyn system: the Old Method, the Hybrid Method, and the SeaState Method. Both the hybrid method and the SeaState method use a coupling -with the `OpenFAST SeaState module _` +with the `OpenFAST SeaState module `_ to calculate the wave kinematics. The Old Method is a legacy method that is not coupled to SeaState. The three methods can be described as: -- **Old Method**: MoorDyn takes wave elevation time series and current speeds with depths as inputs generates it's +- **Old Method**: MoorDyn takes wave elevation time series and current speeds with depths as inputs and generates its own water kinematics using the equivalent of WaveGrid = 3 and Currents = 1 in MoorDyn-C. - **Hybrid Method**: SeaState sets up wave elevation frequencies and current speeds and then MoorDyn interpolates this information to user provided wave grid and current depth discretization. This allows users to set the - WaterKinematics for the whole OpenFAST or FAST.Farm system while still maintaining a courser grid for the MoorDyn + WaterKinematics for the whole OpenFAST or FAST.Farm system while still maintaining a coarser grid for the MoorDyn water kinematics, enabling computational efficiency. This method is compatible with FAST.Farm. - **SeaState Method**: SeaState does all the work, MoorDyn just accesses the SeaState grid data at any given timestep and location. This requires the SeaState grid to encompass the whole MoorDyn system for the most - accurate results. If a point is quried outside the SeaState gird, it will recive the water kinematics of - the nearest grid point. This method is not compataible with FAST.Farm. + accurate results. If a point is queried outside the SeaState grid, it will receive the water kinematics of + the nearest grid point. This method is not compatible with FAST.Farm. The table below summarizes these three options. diff --git a/example/MoorDyn_standalone_demo.ipynb b/example/MoorDyn_standalone_demo.ipynb index fbb32c48..4dac90f4 100644 --- a/example/MoorDyn_standalone_demo.ipynb +++ b/example/MoorDyn_standalone_demo.ipynb @@ -7,6 +7,8 @@ "collapsed": false }, "source": [ + "This Jupyter Notebook was presented during Software Demo Days. A link to that presentation can be found here: https://www.youtube.com/watch?v=FqW7Xpl_VNk\n", + "\n", "# Starting Out\n", "\n", "Some reminder notes about MoorDyn:\n", @@ -22,7 +24,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": null, "id": "627cec", "metadata": { "collapsed": false @@ -115,7 +117,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": null, "id": "d42146", "metadata": { "collapsed": false @@ -237,12 +239,9 @@ "system = moordyn.Create(\"lines.txt\")\n", "\n", "# Set the initial positions in this driver code to what was defined in the input file\n", - "x = np.array([ 5.2, 0.0, -70.0, -2.6, 4.5, -70.0, -2.6, -4.5, -70.0])\n", - "# Formerly:\n", - " # x = []\n", - " # x += [ 5.2, 0.0, -70.0]\n", - " # x += [-2.6, 4.5, -70.0]\n", - " # x += [-2.6, -4.5, -70.0]\n", + "x = np.array([ 5.2, 0.0, -70.0, # point 4\n", + " -2.6, 4.5, -70.0, # point 5\n", + " -2.6, -4.5, -70.0]) # point 6\n", "\n", "# Set the velocities to zero. 3 coupled points x 3 DoF per point = 9 DoF\n", "xd = np.zeros(9)\n", @@ -463,7 +462,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": null, "id": "e3b168", "metadata": { "collapsed": false @@ -594,9 +593,6 @@ "\n", "x = np.array(state[0]) # x, y, z, roll, pitch, yaw \n", "xd = np.array(state[1]) # xdot, ydot, zdot, roll_dot, pitch_dot, yaw_dot \n", - "# Formerly:\n", - " # x = list(state[0]) # x, y, z, roll, pitch, yaw\n", - " # xd = list(state[1]) # xdot, ydot, zdot, roll_dot, pitch_dot, yaw_dot\n", "\n", "# Setup the initial condition\n", "moordyn.Init(system, x, xd)" diff --git a/example/README.md b/example/README.md index dc705539..9e3e0c54 100644 --- a/example/README.md +++ b/example/README.md @@ -1,11 +1,13 @@ This example directory contains instructions for common uses of MoorDyn, including OpenFAST, WEC-Sim, and running standalone. -Before working with these examples, please look at the [MoorDyn documentation](https://moordyn.readthedocs.io/en/latest/drivers.html#python) for an explaination of the code and the different versions (MoorDyn-C and MoorDyn-F). After that, start out with working through the jupyter notebook (`MoorDyn_standalone_demo.ipynb`). This will walk through basic examples for running MoorDyn and visualzing outputs. Visualization is done with MoorPy, however Paraview can also be used as well as the tool [PyDatView](https://github.com/ebranlard/pyDatView). +Before working with these examples, please look at the [MoorDyn documentation](https://moordyn.readthedocs.io/en/latest/drivers.html#python) for an explanation of the code and the different versions (MoorDyn-C and MoorDyn-F). After that, start out with working through the jupyter notebook (`MoorDyn_standalone_demo.ipynb`). This will walk through basic examples for running MoorDyn and visualizing outputs. Visualization is done with MoorPy, however Paraview can also be used as well as the tool [PyDatView](https://github.com/ebranlard/pyDatView). + +Much of this directory was presented during Software Demo Days. A link to that presentation can be found here: https://www.youtube.com/watch?v=FqW7Xpl_VNk Further examples are the following: - `MHK_RM1_Floating`: This directory shows how to run MoorDyn-F with OpenFAST. - `MoorDynF_example`: This directory shows how to use the MoorDyn-F driver from OpenFAST. -- `simpledemo.py`: This is the simplement example of how to run MoorDyn-C with a python script. -- `Running MoorDyn-F (OpenFAST).pdf`: This is a step-by-step list of iunstructions for running MoorDyn-F with OpenFAST. -- `Running WECSim with MoorDyn.pdf`: This is a step-by-step list of instructions for running MoorDyn-C with WECSim. \ No newline at end of file +- `simpledemo.py`: This is the simplest example of how to run MoorDyn-C with a python script. +- `Running MoorDyn-F (OpenFAST).pdf`: This is a step-by-step list of instructions for running MoorDyn-F with OpenFAST. +- `Running WECSim with MoorDyn.pdf`: This is a step-by-step list of instructions for running MoorDyn-C with WECSim. \ No newline at end of file diff --git a/example/Running MoorDyn-F (OpenFAST).md b/example/Running MoorDyn-F (OpenFAST).md new file mode 100644 index 00000000..59ef928e --- /dev/null +++ b/example/Running MoorDyn-F (OpenFAST).md @@ -0,0 +1,50 @@ + + +# OpenFAST and MoorDyn-F + +MoorDyn-F is the core mooring dynamics module in OpenFAST. It is structured to seamlessly fit into the OpenFAST code structure, and thus is less suitable for external couplings than MoorDyn-C. The steps for running MoorDyn with OpenFAST and FAST.Farm are very similar to running any of the other OpenFAST modules. First, enable the module in the main input file, then provide the path to the module input file, and then configure the module input file for your simulation. Finally, run your simulation. + +## Running OpenFAST with MoorDyn-F + +See the instructions in the `Running OpenFAST.pdf` from the OpenFAST co-calc demonstration for details on setting up OpenFAST more broadly. Additional OpenFAST information can be found in the [OpenFAST documentation](https://openfast.readthedocs.io/en/main/). The general steps for running OpenFAST with MoorDyn-F are as follows: + +- Obtain the OpenFAST executables + - Compile from source code + - Download executables from [GitHub releases](https://github.com/OpenFAST/openfast/releases) +- Configure the OpenFAST input files for your system + - Set `CompMooring = 3` in the main OpenFAST `.fst` input file + - Set the `MooringFile` variable in the main OpenFAST `.fst` input file to the MoorDyn input file path +- Configure the MoorDyn input file for your system + - Note that coupled MoorDyn objects (bodies, rods, and points) are rigidly attached to the ElastoDyn object instance +- Execute `openfast .fst` + +## Running MoorDyn-F with the MoorDyn Driver + +The MoorDyn driver allows for MoorDyn-F to be run as a stand-alone module, enabling debugging of OpenFAST simulations and MoorDyn-only simulations. To run the driver, an additional input file is required that fills in the information normally provided to MoorDyn by the OpenFAST input file. Information on this file can be found in the [MoorDyn documentation](https://moordyn.readthedocs.io/en/latest/inputs.html#moordyn-f-driver-input-file). The general steps for running MoorDyn-F with the MoorDyn driver are as follows: + +- Obtain the driver executable + - Compile from source code + - Download executable from [GitHub releases](https://github.com/OpenFAST/openfast/releases) +- Configure the MoorDyn driver input file `.dvr` following the formatting described in the [MoorDyn documentation](https://moordyn.readthedocs.io/en/latest/inputs.html#moordyn-f-driver-input-file). + - A time series input file is needed for providing motion to coupled MoorDyn objects. The path to this input file is set as the `InputsFile` variable in the MoorDyn driver input file (note that if `InputsMode = 0` all coupled objects positions will be fixed at 0 and the time series file will be ignored) +- Configure the MoorDyn input file + - Coupled objects will be driven by a time series file provided in the driver input file +- Execute `moordyn_driver .dvr` + +## Running FAST.Farm with MoorDyn-F + +FAST.Farm, the wind farm simulation tool built on OpenFAST, can also be run with MoorDyn. More information on FAST.Farm can be found in the [OpenFAST documentation](https://openfast.readthedocs.io/en/main/source/user/fast.farm/index.html#fast-farm-user-s-guide-and-theory-manual). FAST.Farm runs an OpenFAST instance for each turbine in the farm and thus can have a MoorDyn instance for each turbine. Additionally, there can be a farm level MoorDyn instance, which allows for the simulation of shared mooring lines. Instructions for using MoorDyn with FAST.Farm can be found in the [MoorDyn documentation](https://moordyn.readthedocs.io/en/latest/inputs.html#moordyn-f-with-fast-farm-inputs). The general steps for running FAST.Farm with MoorDyn-F are as follows: + +- Obtain the FAST.Farm executables + - Compile from source code + - Download executable from [GitHub releases](https://github.com/OpenFAST/openfast/releases) +- Configure the FAST.Farm input files for your system + - `Mod_SharedMooring = 3` in the main FAST.Farm `.fstf` input file + - Set the `SharedMoorFile` variable in the main FAST.Farm `.fstf` input file to the MoorDyn input file path +- For each turbine in your system, configure the OpenFAST input files for your system + - If using MoorDyn at the turbine scale as well, set `CompMooring = 3` in the main OpenFAST `.fst` input file for each turbine. Otherwise set `CompMooring = 0` + - Set the `MooringFile` variable in the main OpenFAST `.fst` input file to the MoorDyn input file path if using the turbine level MoorDyn instance +- Configure the MoorDyn input files + - At the turbine level, coupled MoorDyn objects (bodies, rods, and points) are rigidly attached to the ElastoDyn object instance + - At the farm level MoorDyn instance, the object attachment `Turbine#` is rigidly coupled to the ElastoDyn instance of the given turbine. Coupled objects are not allowed in the farm level MoorDyn input file. +- Execute `fast.farm .fstf` diff --git a/example/Running MoorDyn-F (OpenFAST).pdf b/example/Running MoorDyn-F (OpenFAST).pdf deleted file mode 100644 index cc0ed975..00000000 Binary files a/example/Running MoorDyn-F (OpenFAST).pdf and /dev/null differ diff --git a/example/Running WECSim with MoorDyn.md b/example/Running WECSim with MoorDyn.md new file mode 100644 index 00000000..544b3f2f --- /dev/null +++ b/example/Running WECSim with MoorDyn.md @@ -0,0 +1,21 @@ + + +# Running WEC-Sim with MoorDyn + +Instructions for running WEC-Sim with MoorDyn can be found in the README for the [WEC-Sim/MoorDyn repository](https://github.com/WEC-Sim/MoorDyn/blob/main/README.md). A short summary of those steps is detailed here: + +1. Obtain the MoorDyn libraries, header files, and the MoorDyn caller + - Download from the [WEC-Sim/MoorDyn repository](https://github.com/WEC-Sim/MoorDyn/blob/main/README.md) + - Compile MoorDyn-C from source following the [instructions in the documentation](https://moordyn.readthedocs.io/en/latest/compiling.html) + - This is only needed if libraries from the [WEC-Sim/MoorDyn repository](https://github.com/WEC-Sim/MoorDyn/blob/main/README.md) do not work +2. Move the MoorDyn libraries, `.h` header files, and MoorDyn caller (all the files in the [WEC-Sim/MoorDyn repository](https://github.com/WEC-Sim/MoorDyn/blob/main/README.md)) from step 1 to the `WEC-Sim/source/functions/moorDyn` directory. + - To test the WEC-Sim MoorDyn setup, run the [WEC-Sim_Application/Mooring/MoorDyn example case](https://github.com/WEC-Sim/WEC-Sim_Applications/tree/main/Mooring/MoorDyn). +3. Configure the MoorDyn input file for your system. + - Note that WEC-Sim requires a rigid 6 DOF body coupling for each mooring connection (a coupled MoorDyn body). Multiple bodies can be coupled to the WEC-Sim system, allowing the simulation of shared moorings for hydrokinetic devices. +4. Configure the WEC-Sim Simulink model + - For each MoorDyn connection (a connection can consist of multiple lines and nodes but is between two distinct objects such as a floating body and the seafloor), there should be a MoorDyn Connection block in the Simulink model defining the relative motion between the objects. + - When using MoorDyn, there should always be exactly one MoorDyn Caller block in the Simulink model. See [WEC-Sim MoorDyn docs](https://wec-sim.github.io/WEC-Sim/dev/user/advanced_features.html#moordyn) for more details. +5. Configure the WEC-Sim input file + - For each MoorDyn block in your system, you need to have a corresponding `mooring(i)` object, where `i` is the ID number of the body in the MoorDyn input file. Instructions for how to set up the mooring object are in the [WEC-Sim MoorDyn docs](https://wec-sim.github.io/WEC-Sim/dev/user/advanced_features.html#moordyn). + - The MoorDyn input file needs to be defined as `mooring(1).moorDynInputFile`, as WEC-Sim uses the file path defined in the first Mooring block to load the MoorDyn input file. +6. Run the simulation by executing `wecSim` from the command window. diff --git a/example/Running WECSim with MoorDyn.pdf b/example/Running WECSim with MoorDyn.pdf deleted file mode 100644 index 8410cc41..00000000 Binary files a/example/Running WECSim with MoorDyn.pdf and /dev/null differ diff --git a/example/simpledemo.py b/example/simpledemo.py index d61fe2c3..ffaef8ee 100644 --- a/example/simpledemo.py +++ b/example/simpledemo.py @@ -1,31 +1,130 @@ import moordyn import numpy as np +### OPTIONAL ### +# import matplotlib.pyplot as plt +# import moorpy + ''' This is a very simple example of how to use the MoorDyn Python interface. Users need to provide a moordyn input file before running. +This code is ready to run if a user provides an input file with a single coupled body. A more thorough explanation of how to drive +MoorDyn can be found in `MoorDyn_standalone_demo.ipynb`. + +The framework here is set up for a single coupled body. For other configurations, the state (x) and state derivatives (xd) need to be +changed accordingly. ''' -# Create the MoorDyn system from the input file +def sin (period = 150, A = 10, axis = 0, dof = 6, x_initial = np.array([0, 0, 0, 0, 0, 0]), vector_size = 6, time = np.array([0])): + ''' + A function that provides time series of states and state variables for simulating sinusoidal motion of a 6 DOF body in one of + the DOFs. + + Inputs + ------ + `period` : `float` + The period of the sinusoidal motion. + `A` : `float` + The amplitude of the sinusoidal motion. + `axis` : `int` + The axis along which the motion occurs (0 -> x, 1 -> y, 2 -> z, 3 -> roll, 4 -> pitch, 5 -> yaw). + `dof` : `int` + The degrees of freedom of the system. + `x_initial` : `np.array` + The initial state of the system. + `vector_size` : `int` + The size of the state vector. This should be equal to `DOF * the number of objects`. For example, 3 coupled points would have `DOF = 3` and `vector_size = 9`. + `time` : `np.array` + The time array for the simulation. + + Outputs + ------- + `xp` : `np.array` + The position time series of the system. + `xdp` : `np.array` + The velocity time series of the system. + ''' + + # axis 0 -> x, 1 -> y, 2 -> z, 3 -> roll, 4 -> pitch, 5 -> yaw + xp = np.zeros((len(time),6)) + + # Time info + dt = time[1] - time[0] + + # Wave properties + T = period / dt + omega = (2*np.pi)/T + + for i in range(len(time)): + xp[i,axis] = A * np.sin(i*omega) + + xdp = np.zeros((len(time),6)) + xold = np.zeros(6) + # calculate velocities using finite difference + for i in range(len(time)): + xdp [i] = (xp[i] - xold)/dt + xold = xp[i] + for i in range(len(time)): + if i == 0: + x[i,:] = x_initial + else: + j = 0 + while j < vector_size: + x[i,j:j+dof] = x[i-1,j:j+dof] + xdp[i, 0:dof] * dt + xd[i,j:j+dof] = xdp[i, 0:dof] + j += dof + + return x, xd + +# Create time array +tMax = 0.5 # max time for running time series +dt = 0.001 # coupling timestep +time = np.arange(0, tMax, dt) # time series + +# Build arrays of state and state derivatives +size = (len(time), 6) +x = np.zeros(size) +xd = np.zeros(size) + +# Create the MoorDyn system from the input file. +# NOTE TO USERS: +# Change this to your own input file. +# It must have one coupled body and no other coupled objects. system = moordyn.Create("") # You can get the initial positions and velocities from the system itself using the MoorDyn-C API body = moordyn.GetBody(system, 1) state = moordyn.GetBodyState(body) # tuple with (x, xd) -x = np.array(state[0]) # x, y, z, roll, pitch, yaw -xd = np.array(state[1]) # xdot, ydot, zdot, roll_dot, pitch_dot, yaw_dot +# Set the first time step of the state and state derivatives to the initial values from MoorDyn +x[0,:] = np.array(state[0]) # x, y, z, roll, pitch, yaw +xd[0,:] = np.array(state[1]) # xdot, ydot, zdot, roll_dot, pitch_dot, yaw_dot # Setup the initial condition -moordyn.Init(system, x, xd) +moordyn.Init(system, x[0,:], xd[0,:]) -# Set the simulation time -t, dt = 0.0, 0.5 +# Get the state and state derivative time series +x_t, xd_t = sin(period = 5, A = 1, axis = 0, dof = 6, x_initial = x[0,:], vector_size = 6, time = time) # Run the simulation for five timesteps -for i in range(5): - f = moordyn.Step(system, x, xd, t, dt) - t += dt - x += xd * dt # update the position +for i in range(1, len(time)): + # call the MoorDyn step function + f = moordyn.Step(system, x_t[i,:], xd_t[i,:], time[i], dt) # force value on coupled DOF returned here in array # Alright, time to finish! -moordyn.Close(system) \ No newline at end of file +moordyn.Close(system) + + +### Optional ### + +# # Plot and animate the results using MoorPy + +# # Create a MoorPy system (this loads the moordyn outputs found in /_#.out, where is either Line or Rod and # is the corresponding number) +# ms = moorpy.System(file=, dirname=, rootname=, qs = 0, Fortran = False) # qs tells MoorPy it is loading a MoorDyn system, Fortran = False tells it to use the MoorDyn-C output format + +# # Plot the results at t = 0 in red +# ms.plot(color="red", time = 0) + +# # animate the results +# animation = ms.animateLines() + +# plt.show() \ No newline at end of file diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 1ed52a75..c0c9898a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1026,6 +1026,25 @@ moordyn::MoorDyn::ReadInFile() } } + if ((i = findStartOfSection(in_txt, { "RODS", "ROD LIST", "ROD PROPERTIES" })) != -1) { + LOGDBG << " Reading rod list:" << endl; + + // parse until the next header or the end of the file + while ((in_txt[i].find("---") == string::npos) && + (i < (int)in_txt.size())) { + Rod* obj = readRod(in_txt[i], i); + + if (obj) { + RodList.push_back(obj); + } else { + delete obj; + return MOORDYN_INVALID_INPUT; + } + + i++; + } + } + if ((i = findStartOfSection(in_txt, { "POINTS", "POINT LIST", @@ -1132,6 +1151,15 @@ moordyn::MoorDyn::ReadInFile() << endl; } + // Check point ID is sequential starting from 1 + if (number != PointList.size() + 1) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Point ID must be sequential starting from 1" << endl; + return MOORDYN_INVALID_INPUT; + } + LOGDBG << "\t'" << number << "'" << " - of type " << Point::TypeName(type) << " with id " << PointList.size() << endl; @@ -1155,20 +1183,6 @@ moordyn::MoorDyn::ReadInFile() } } - if ((i = findStartOfSection( - in_txt, { "RODS", "ROD LIST", "ROD PROPERTIES" })) != -1) { - LOGDBG << " Reading rod list:" << endl; - - // parse until the next header or the end of the file - while ((in_txt[i].find("---") == string::npos) && - (i < (int)in_txt.size())) { - Rod* obj = readRod(in_txt[i], i); - RodList.push_back(obj); - - i++; - } - } - if ((i = findStartOfSection( in_txt, { "LINES", "LINE LIST", "LINE PROPERTIES" })) != -1) { LOGDBG << " Reading line list: " << endl; @@ -1226,6 +1240,15 @@ moordyn::MoorDyn::ReadInFile() } else outfiles.push_back(NULL); + // Check line ID is sequential starting from 1 + if (number != LineList.size() + 1) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Line ID must be sequential starting from 1" << endl; + return MOORDYN_INVALID_INPUT; + } + LOGDBG << "\t'" << number << "'" << " - of class " << type << " (" << TypeNum << ")" << " with id " << LineList.size() << endl; @@ -1423,9 +1446,6 @@ moordyn::MoorDyn::ReadInFile() // figure out what type of output it is and process // accordingly - // TODO: add checks of first char of num1,2, let1,2,3 not - // being NULL to below and handle errors (e.g. invalid line - // number) // fairlead tension case (changed to just be for single // line, not all connected lines) @@ -1434,6 +1454,15 @@ moordyn::MoorDyn::ReadInFile() dummy.QType = Ten; dummy.Units = moordyn::UnitList[Ten]; dummy.ObjID = atoi(num1.c_str()); + // Check if the line ID is valid + if (dummy.ObjID <=0 || dummy.ObjID > LineList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Line ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } dummy.NodeID = LineList[dummy.ObjID - 1]->getN(); } // achor tension case (changed to just be for single line, @@ -1443,6 +1472,15 @@ moordyn::MoorDyn::ReadInFile() dummy.QType = Ten; dummy.Units = moordyn::UnitList[Ten]; dummy.ObjID = atoi(num1.c_str()); + // Check if the line ID is valid + if (dummy.ObjID <=0 || dummy.ObjID > LineList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Line ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } dummy.NodeID = 0; } // more general case @@ -1454,6 +1492,17 @@ moordyn::MoorDyn::ReadInFile() // get object type and node number if applicable // Line case: L?N?xxxx if (str::isOneOf(let1, { "L", "LINE" })) { + + // Check if the line ID is valid + if (dummy.ObjID <=0 || dummy.ObjID > LineList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Line ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } + dummy.OType = 1; if (let3.empty()) { if (let2.substr(0, 2) == "NA") { @@ -1476,14 +1525,48 @@ moordyn::MoorDyn::ReadInFile() } } else dummy.NodeID = atoi(num2.c_str()); + + // Check if NodeID is valid if provided by user (note -1 is returned by atoi(num2.c_str()) if null string). Static cast required because getN returns unsigned int + if ( dummy.NodeID < 0 || dummy.NodeID > static_cast(LineList[dummy.ObjID - 1]->getN()) ) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Line Node ID specifier: " << dummy.NodeID + << endl; + return MOORDYN_INVALID_INPUT; + } } // Point case: P?xxx or Point?xxx else if (str::isOneOf(let1, { "P", "POINT" })) { + + // Check for valid pointID + if (dummy.ObjID <= 0 || dummy.ObjID > PointList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Point ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } + dummy.OType = 2; dummy.NodeID = -1; } // Rod case: R?xxx or Rod?xxx else if (str::isOneOf(let1, { "R", "ROD" })) { + + // Check for valid rodID + cout << "dummy.ObjID: " << dummy.ObjID << endl; + cout << "RodList.size(): " << RodList.size() << endl; + if (dummy.ObjID <= 0 || dummy.ObjID > RodList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Rod ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } + dummy.OType = 3; if (let3.empty()) { if (let2.substr(0, 2) == "NA") { @@ -1496,6 +1579,17 @@ moordyn::MoorDyn::ReadInFile() dummy.NodeID = -1; } else if (!num2.empty()) dummy.NodeID = atoi(num2.c_str()); + + // Check if NodeID is valid if provided by user (note -1 is returned by atoi(num2.c_str()) if null string). Static cast required because getN returns unsigned int + if ( dummy.NodeID < -1 || dummy.NodeID > static_cast(RodList[dummy.ObjID - 1]->getN()) ) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Rod Node ID specifier: " << dummy.NodeID + << endl; + return MOORDYN_INVALID_INPUT; + } + else { LOGWRN << "Warning in " << _filepath << ":" << i + 1 << "..." << endl @@ -1507,6 +1601,17 @@ moordyn::MoorDyn::ReadInFile() } // Body case: B?xxx or Body?xxx else if (str::isOneOf(let1, { "B", "BODY" })) { + + // Check for valid bodyID + if (dummy.ObjID <= 0 || dummy.ObjID > BodyList.size()) { + LOGERR << "Error in " << _filepath << " at line " << i + 1 + << ":" << endl + << "'" << in_txt[i] << "'" << endl + << "Invalid Body ID specifier: " << dummy.ObjID + << endl; + return MOORDYN_INVALID_INPUT; + } + dummy.OType = 4; dummy.NodeID = -1; } @@ -2052,6 +2157,15 @@ moordyn::MoorDyn::readBody(string inputText, int lineNum) return nullptr; } + // Check body ID is sequential starting from 1 + if (number != BodyList.size() + 1) { + LOGERR << "Error in " << _filepath << " at line " << lineNum + 1 + << ":" << endl + << "'" << inputText << "'" << endl + << "Body ID must be sequential starting from 1" << endl; + return nullptr; + } + // id = size + 1 because of ground body, which has an Id of zero Body* obj = new Body(_log, BodyList.size() + 1); LOGDBG << "\t'" << number << "'" @@ -2178,6 +2292,15 @@ moordyn::MoorDyn::readRod(string inputText, int lineNum) << " and type " << Rod::TypeName(type) << " with id " << RodList.size() << endl; + // Check rod ID is sequential starting from 1 + if (number != RodList.size() + 1) { + LOGERR << "Error in " << _filepath << " at line " << lineNum + 1 + << ":" << endl + << "'" << inputText << "'" << endl + << "Rod ID must be sequential starting from 1" << endl; + return nullptr; + } + Rod* obj = new Rod(_log, RodList.size()); obj->setup(number, type, diff --git a/tests/Mooring/RodHanging.txt b/tests/Mooring/RodHanging.txt index 1cfc5818..e9b38bb3 100644 --- a/tests/Mooring/RodHanging.txt +++ b/tests/Mooring/RodHanging.txt @@ -17,7 +17,7 @@ ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs ID Type X Y Z Mass Volume CdA Ca (#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) 1 Fixed -450 0 0 0 0 0 0 -1 Fixed 450 0 0 0 0 0 0 +2 Fixed 450 0 0 0 0 0 0 ---------------------- LINES --------------------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-)