From fd8b5b4e9a94e6dd9bf362f54a075a4b47f2cb78 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 20 Feb 2024 17:47:47 -0700 Subject: [PATCH 001/145] Crossflow VIV attempt 1 --- source/Line.cpp | 37 ++++++++++++++++++++++++++++++++++++- source/Line.hpp | 2 ++ 2 files changed, 38 insertions(+), 1 deletion(-) diff --git a/source/Line.cpp b/source/Line.cpp index 6259e830..f47525c3 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -201,6 +201,7 @@ Line::setup(int number_in, Ap.assign(N + 1, vec::Zero()); // node added mass forcing (transverse) Aq.assign(N + 1, vec::Zero()); // node added mass forcing (axial) B.assign(N + 1, vec::Zero()); // node bottom contact force + Lf.assign(N + 1, vec::Zero()); // viv crossflow lift force Fnet.assign(N + 1, vec::Zero()); // total force on node // wave things @@ -1066,6 +1067,19 @@ Line::getStateDeriv() l[i - 1] * (rho - F[i - 1] * env->rho_w)) * (-env->g); + // line natural frequency + real m_i; // node mass from mass matrix. This can be cleaned up later + if (i == 0) { + m_i = pi / 8. * d * d * l[0] * rho; + } else if (i == N) { + m_i = pi / 8. * d * d * l[N - 1] * rho; + } else { + m_i = pi / 8. * (d * d * rho * (l[i] + l[i - 1])); + } + const moordyn::real omega = (pi/l[i]) * sqrt((T[i].norm()/m_i) + ((pi/l[i]) * (pi/l[i]) * (EI/m_i))); + + // Unit vector of current flow + const vec U_hat = U[i]/U[i].norm(); // relative flow velocity over node const vec vi = U[i] - rd[i]; // tangential relative flow component @@ -1074,6 +1088,11 @@ Line::getStateDeriv() const vec vq = vql * q[i]; // transverse relative flow component const vec vp = vi - vq; + // crossflow relative flow component. Normal to both cable and flow direction + const vec y_dot = vi.dot(q[i].cross(U_hat)) * q[i].cross(U_hat); + // reduced velocity + const moordyn::real Ui_mag = U[i].norm(); + const moordyn::real V_r = Ui_mag/(omega*d); const moordyn::real vq_mag = vq.norm(); const moordyn::real vp_mag = vp.norm(); @@ -1099,6 +1118,22 @@ Line::getStateDeriv() Dq[i] = 0.25 * vq_mag * env->rho_w * Cdt * pi * d * (F[i] * l[i] + F[i - 1] * l[i - 1]) * vq; + // phase of lift force. Assume phi(0) = 0 for now. + const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. + const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; + const moordyn::real phi = phi_dot * t; + // Vortex shedding frequency + // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. + const moordyn::real st = 0.2; + const moordyn::real f_s = st * Ui_mag / d; + // if frequency lock in and crossflow excitation + if ((0.6 < (phi_dot/f_s) < 1.5) && (5.0 < V_r < 7.0)) { + const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. + const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. + const moordyn::real C_l = C_e / cos(phase_diff); + Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot; + } + // tangential component of fluid acceleration // <<<<<<< check sign since I've reversed q const moordyn::real aql = Ud[i].dot(q[i]); @@ -1178,7 +1213,7 @@ Line::getStateDeriv() Fnet[i] = -T[i - 1] - Td[i - 1]; else Fnet[i] = T[i] - T[i - 1] + Td[i] - Td[i - 1]; - Fnet[i] += W[i] + (Dp[i] + Dq[i] + Ap[i] + Aq[i]) + B[i] + Bs[i]; + Fnet[i] += W[i] + (Dp[i] + Dq[i] + Ap[i] + Aq[i]) + B[i] + Bs[i] + Lf[i]; } // if (t > 5) diff --git a/source/Line.hpp b/source/Line.hpp index 93c1e445..bf6e47a7 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -230,6 +230,8 @@ class Line final : public io::IO std::vector Aq; /// node bottom contact force std::vector B; + /// crossflow viv lift force + std::vector Lf; /// total force on node std::vector Fnet; From 8e41671e8cdedfe199f025cf264f7ed0f703a6e1 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 26 Feb 2024 13:16:42 -0700 Subject: [PATCH 002/145] Bug fixes VIV --- source/Line.cpp | 44 ++++++++++++++++++++++++-------------------- 1 file changed, 24 insertions(+), 20 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index f47525c3..2543a4ce 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1078,20 +1078,20 @@ Line::getStateDeriv() } const moordyn::real omega = (pi/l[i]) * sqrt((T[i].norm()/m_i) + ((pi/l[i]) * (pi/l[i]) * (EI/m_i))); + // magnitude of current + const moordyn::real Ui_mag = U[i].norm(); // Unit vector of current flow - const vec U_hat = U[i]/U[i].norm(); + const vec U_hat = U[i]/Ui_mag; // relative flow velocity over node const vec vi = U[i] - rd[i]; // tangential relative flow component - // <<<<<<< check sign since I've reversed q const moordyn::real vql = vi.dot(q[i]); const vec vq = vql * q[i]; // transverse relative flow component const vec vp = vi - vq; // crossflow relative flow component. Normal to both cable and flow direction - const vec y_dot = vi.dot(q[i].cross(U_hat)) * q[i].cross(U_hat); + vec y_dot = vi.dot(q[i].cross(U_hat)) * q[i].cross(U_hat); // reduced velocity - const moordyn::real Ui_mag = U[i].norm(); const moordyn::real V_r = Ui_mag/(omega*d); const moordyn::real vq_mag = vq.norm(); @@ -1117,22 +1117,26 @@ Line::getStateDeriv() else Dq[i] = 0.25 * vq_mag * env->rho_w * Cdt * pi * d * (F[i] * l[i] + F[i - 1] * l[i - 1]) * vq; - - // phase of lift force. Assume phi(0) = 0 for now. - const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. - const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; - const moordyn::real phi = phi_dot * t; - // Vortex shedding frequency - // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. - const moordyn::real st = 0.2; - const moordyn::real f_s = st * Ui_mag / d; - // if frequency lock in and crossflow excitation - if ((0.6 < (phi_dot/f_s) < 1.5) && (5.0 < V_r < 7.0)) { - const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. - const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. - const moordyn::real C_l = C_e / cos(phase_diff); - Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot; - } + if (Ui_mag > 0.0) { // If there is current + // phase of lift force. Assume phi(0) = 0 for now. + const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. + const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; + const moordyn::real phi = phi_dot * t; + // Vortex shedding frequency + // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. + const moordyn::real st = 0.2; + const moordyn::real f_s = st * Ui_mag / d; + // if frequency lock in and crossflow excitation + if ((0.6 < (phi_dot/f_s)) && ((phi_dot/f_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { + if (t == 0.0) { + y_dot = 0.4 * d * phi_dot * (q[i].cross(U_hat)); // Inital crossflow amplitude 40% of diameter + } + const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. + const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. + const moordyn::real C_l = C_e / cos(phase_diff); + Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot; + } + } // tangential component of fluid acceleration // <<<<<<< check sign since I've reversed q From f0fc52eb2ae78e113e236a82c22ec668caaaf61f Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 26 Feb 2024 14:23:42 -0700 Subject: [PATCH 003/145] More viv bug fixes --- source/Line.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 2543a4ce..9c6435ca 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1125,16 +1125,16 @@ Line::getStateDeriv() // Vortex shedding frequency // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. const moordyn::real st = 0.2; - const moordyn::real f_s = st * Ui_mag / d; + const moordyn::real omega_s = 2 * pi * st * Ui_mag / d; // if frequency lock in and crossflow excitation - if ((0.6 < (phi_dot/f_s)) && ((phi_dot/f_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { + if ((0.6 < (phi_dot/omega_s)) && ((phi_dot/omega_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { if (t == 0.0) { y_dot = 0.4 * d * phi_dot * (q[i].cross(U_hat)); // Inital crossflow amplitude 40% of diameter } const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. const moordyn::real C_l = C_e / cos(phase_diff); - Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot; + Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * (y_dot/y_dot.norm()); } } From 09b94c16ba09a257b244c7dd27a0cb23f3030f50 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 4 Mar 2024 15:12:06 -0700 Subject: [PATCH 004/145] Remove VIV IF statement, bug fix for end nodes --- source/Line.cpp | 37 +++++++++++++++++-------------------- 1 file changed, 17 insertions(+), 20 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 9c6435ca..78214c4b 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1067,21 +1067,18 @@ Line::getStateDeriv() l[i - 1] * (rho - F[i - 1] * env->rho_w)) * (-env->g); - // line natural frequency - real m_i; // node mass from mass matrix. This can be cleaned up later - if (i == 0) { - m_i = pi / 8. * d * d * l[0] * rho; - } else if (i == N) { - m_i = pi / 8. * d * d * l[N - 1] * rho; - } else { - m_i = pi / 8. * (d * d * rho * (l[i] + l[i - 1])); - } - const moordyn::real omega = (pi/l[i]) * sqrt((T[i].norm()/m_i) + ((pi/l[i]) * (pi/l[i]) * (EI/m_i))); + // natural frequency + moordyn::real omega; + if (i == 0) + for (int n=1;n<12;n++){ + omega = (n*pi/UnstrLen) * sqrt((T[i].norm()/(rho*A)) + ((n*pi/UnstrLen) * (n*pi/UnstrLen) * (EI/(rho*A)))); + // if (abs(t-1.7) < 0.00001) cout << "Omega_" << n << ": " << omega << endl; + // } // magnitude of current const moordyn::real Ui_mag = U[i].norm(); // Unit vector of current flow - const vec U_hat = U[i]/Ui_mag; + const vec Ui_hat = U[i].normalized(); // relative flow velocity over node const vec vi = U[i] - rd[i]; // tangential relative flow component @@ -1090,10 +1087,9 @@ Line::getStateDeriv() // transverse relative flow component const vec vp = vi - vq; // crossflow relative flow component. Normal to both cable and flow direction - vec y_dot = vi.dot(q[i].cross(U_hat)) * q[i].cross(U_hat); + vec y_dot = vi.dot(q[i].cross(Ui_hat)) * q[i].cross(Ui_hat); // reduced velocity - const moordyn::real V_r = Ui_mag/(omega*d); - + // const moordyn::real V_r = Ui_mag/(omega*d); const moordyn::real vq_mag = vq.norm(); const moordyn::real vp_mag = vp.norm(); @@ -1121,21 +1117,22 @@ Line::getStateDeriv() // phase of lift force. Assume phi(0) = 0 for now. const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; + if ((i==0) && (abs(t-1.7) < 0.00001)) cout << "Phi_dot: " << phi_dot << endl; const moordyn::real phi = phi_dot * t; // Vortex shedding frequency // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. - const moordyn::real st = 0.2; - const moordyn::real omega_s = 2 * pi * st * Ui_mag / d; + // const moordyn::real st = 0.2; + // const moordyn::real omega_s = 2 * pi * st * Ui_mag / d; // if frequency lock in and crossflow excitation - if ((0.6 < (phi_dot/omega_s)) && ((phi_dot/omega_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { + // if ((0.6 < (phi_dot/omega_s)) && ((phi_dot/omega_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { // Disable for now, and run with known VIV cases if (t == 0.0) { - y_dot = 0.4 * d * phi_dot * (q[i].cross(U_hat)); // Inital crossflow amplitude 40% of diameter + y_dot = 0.4 * d * phi_dot * (q[i].cross(Ui_hat)); // Inital crossflow amplitude 40% of diameter } const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. const moordyn::real C_l = C_e / cos(phase_diff); - Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * (y_dot/y_dot.norm()); - } + Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot.normalized(); + // } } // tangential component of fluid acceleration From 011c54cf55c869d779c94b1971e6627c16dda3e5 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 6 Mar 2024 11:31:35 -0700 Subject: [PATCH 005/145] Add VIV force output, frequency bug fix in lift force direction --- source/Line.cpp | 25 +++++++++++++++++++++++-- source/MoorDyn2.cpp | 2 +- 2 files changed, 24 insertions(+), 3 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 78214c4b..b8e5d314 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -289,6 +289,13 @@ Line::initialize() << i << "Dz \t "; } } + // output VIV force + if (channels.find("V") != string::npos) { + for (unsigned int i = 0; i <= N; i++) { + *outfile << "Node" << i << "Vx \t Node" << i << "Vy \t Node" + << i << "Vz \t "; + } + } // output segment tensions if (channels.find("t") != string::npos) { for (unsigned int i = 1; i <= N; i++) { @@ -357,6 +364,11 @@ Line::initialize() for (unsigned int i = 0; i <= 3 * N + 2; i++) *outfile << "(N) \t"; } + // output VIV force + if (channels.find("V") != string::npos) { + for (unsigned int i = 0; i <= 3 * N + 2; i++) + *outfile << "(N) \t"; + } // output segment tensions? if (channels.find("t") != string::npos) { for (unsigned int i = 0; i < N; i++) @@ -1117,7 +1129,7 @@ Line::getStateDeriv() // phase of lift force. Assume phi(0) = 0 for now. const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; - if ((i==0) && (abs(t-1.7) < 0.00001)) cout << "Phi_dot: " << phi_dot << endl; + // if ((i==0) && (abs(t-1.7) < 0.00001)) cout << "Phi_dot: " << phi_dot << endl; const moordyn::real phi = phi_dot * t; // Vortex shedding frequency // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. @@ -1131,7 +1143,7 @@ Line::getStateDeriv() const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. const moordyn::real C_l = C_e / cos(phase_diff); - Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * y_dot.normalized(); + Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * q[i].cross(Ui_hat); // } } @@ -1315,6 +1327,15 @@ Line::Output(real time) << "\t "; } } + + // output VIV force (only CF for now) + if (channels.find("V") != string::npos) { + for (unsigned int i = 0; i <= N; i++) { + for (int J = 0; J < 3; J++) + *outfile << Lf[i][J] + << "\t "; + } + } // output segment tensions? if (channels.find("t") != string::npos) { for (unsigned int i = 0; i < N; i++) { diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index ac36ffa6..f1868db8 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1045,7 +1045,7 @@ moordyn::MoorDyn::ReadInFile() // Make the output file (if queried) if ((outchannels.size() > 0) && - (strcspn(outchannels.c_str(), "pvUDctsd") < + (strcspn(outchannels.c_str(), "pvUDVctsd") < strlen(outchannels.c_str()))) { // if 1+ output flag chars are given and they're valid stringstream oname; From 5409dab03d60b7e1ab6d3d735b53ec38bd8e14e2 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 18 Mar 2024 14:21:32 -0600 Subject: [PATCH 006/145] Removed natural frequency calc --- source/Line.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index b8e5d314..c028daa5 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1079,13 +1079,6 @@ Line::getStateDeriv() l[i - 1] * (rho - F[i - 1] * env->rho_w)) * (-env->g); - // natural frequency - moordyn::real omega; - if (i == 0) - for (int n=1;n<12;n++){ - omega = (n*pi/UnstrLen) * sqrt((T[i].norm()/(rho*A)) + ((n*pi/UnstrLen) * (n*pi/UnstrLen) * (EI/(rho*A)))); - // if (abs(t-1.7) < 0.00001) cout << "Omega_" << n << ": " << omega << endl; - // } // magnitude of current const moordyn::real Ui_mag = U[i].norm(); From 4e8c803ab8212ea78c201d965eb7e90040ba39e8 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 26 Mar 2024 16:16:47 -0600 Subject: [PATCH 007/145] Full CF VIV with hack for state var --- docs/inputs.rst | 8 +- docs/structure.rst | 1 + docs/theory.rst | 22 ++++-- source/Line.cpp | 153 ++++++++++++++++++++++++++------------ source/Line.hpp | 47 ++++++++++-- source/Misc.hpp | 1 + source/MoorDyn2.cpp | 18 ++++- source/State.cpp | 39 ++++++++++ source/State.hpp | 6 ++ source/Time.cpp | 4 +- source/Time.hpp | 10 ++- source/Waves/WaveGrid.cpp | 2 +- 12 files changed, 242 insertions(+), 69 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index ee79eb09..2fb4f51e 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -273,9 +273,9 @@ 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 + TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx Cl + (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 0.8 The columns in order are as follows: @@ -293,6 +293,8 @@ The columns in order are as follows: - 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) + - Cl – the crossflow VIV lift coefficient. If set to 0, then VIV calculations are disabled for the + line. The theory of vortex induced vibrations can be found :ref:`here ` Note: Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file must be located in the same folder as the main MoorDyn input file for MoorDyn-C or for MoorDyn-F diff --git a/docs/structure.rst b/docs/structure.rst index d4c14b3e..0d321a23 100644 --- a/docs/structure.rst +++ b/docs/structure.rst @@ -76,6 +76,7 @@ Specific to each Line: - *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 +- *Cl*: real VIV cross-flow lift coefficient - *BAin*: real axial-internal damping - *A*: real cross sectional area - *nEApoints*: number of values in stress-strain lookup table diff --git a/docs/theory.rst b/docs/theory.rst index e5fef507..e716e782 100644 --- a/docs/theory.rst +++ b/docs/theory.rst @@ -17,6 +17,7 @@ variety of mooring and cabling arrangements. Hydrodynamics are included using a 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 @@ -75,10 +76,12 @@ The theory behind MoorDyn is available in a collection of papers, listed below b Version 1 ^^^^^^^^^ +.. _version1: + 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.' `_ + Ocean Engineering, vol. 104, pp. 590–603, Aug. 2015. `_ Coupling with WEC-Sim or any Simulink code for wave energy converter simulation: @@ -91,6 +94,7 @@ Coupling with WEC-Sim or any Simulink code for wave energy converter simulation: Version 2 ^^^^^^^^^ +.. _version2: Version 2 builds upon the capabilities of Version 1. The theory behind the new features is described in the following references. @@ -120,15 +124,21 @@ Dynamics of 6DOF objects follows a similar approach to Hydrodyn: https://www.nrel.gov/wind/nwtc/assets/downloads/HydroDyn/HydroDyn_Manual.pdf +Voretex Induced Vibration (VIV) calculations are based on the work of Jorgen et. al: + + `M.J. Thorsen, S. Sævik, C.M. Larsen, “Non-linear time domain analysis of cross-flow vortex-induced vibrations,” + Marine Structures, vol. 51, pp. 134-151, Jan. 2017. `_ + 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 + - Fossen, Thor I. Handbook of marine craft hydrodynamics and motion control. + Page 25. John Wiley & Sons, 2011. + - https://en.wikipedia.org/wiki/Gimbal_lock + - https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/ + - https://en.wikipedia.org/wiki/Quaternion#Hamilton_product MoorDyn-C Packages used: + - Eigen: https://eigen.tuxfamily.org - Catch2: https://github.com/catchorg/Catch2 - KISSFFT: https://github.com/mborgerding/kissfft diff --git a/source/Line.cpp b/source/Line.cpp index c028daa5..5766b1dd 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -34,6 +34,7 @@ #include "QSlines.hpp" #include "Util/Interp.hpp" #include +#include #ifdef USE_VTK #include "Util/VTK_Util.hpp" @@ -127,7 +128,8 @@ Line::setup(int number_in, unsigned int NumSegs, EnvCondRef env_in, shared_ptr outfile_pointer, - string channels_in) + string channels_in, + real dtM0) { env = env_in; // set pointer to environment settings object number = number_in; @@ -137,6 +139,8 @@ Line::setup(int number_in, UnstrLend = 0.0; // assign number of nodes to line N = NumSegs; + // save the moordyn internal timestep + dtm = dtM0; // store passed line properties (and convert to numbers) d = props->d; @@ -149,6 +153,7 @@ Line::setup(int number_in, Cat = props->Cat; Cdn = props->Cdn; Cdt = props->Cdt; + Cl = props->Cl; // copy in nonlinear stress-strain data if applicable stiffXs.clear(); @@ -180,7 +185,10 @@ Line::setup(int number_in, // ------------------------- size vectors ------------------------- r.assign(N + 1, vec::Zero()); // node positions [i][x/y/z] - rd.assign(N + 1, vec::Zero()); // node positions [i][x/y/z] + rd.assign(N + 1, vec::Zero()); // node velocities [i][x/y/z] + rdd_old.assign(N + 1, vec::Zero()); // node accelerations previous timestep [i][x/y/z] + VIV.assign(N+1, vec::Zero()); // node viv states [i][phase/amplitude/smoothed amplitude] + VIVd.assign(N+1, vec::Zero()); // node viv state derivatives [i][phase/amplitude/smoothed amplitude] q.assign(N + 1, vec::Zero()); // unit tangent vectors for each node qs.assign(N, vec::Zero()); // unit tangent vectors for each segment l.assign(N, 0.0); // line unstretched segment lengths @@ -208,6 +216,14 @@ Line::setup(int number_in, F.assign(N + 1, 0.0); // VOF scaler for each NODE (mean of two half adjacent // segments) (1 = fully submerged, 0 = out of water) + // Back indexing things for VIV (amplitude disabled, only needed if lift coefficient table is added) + // A_int_old.assign(N + 1, 0.0); // running amplitude total, from previous zero crossing of yd + // Amp.assign(N + 1, 0.0); // VIV Amplitude updated every zero crossing of crossflow velcoity + yd_old.assign(N + 1, 0.0); // node old CF vel + yd_rms_old.assign(N + 1, 0.0); // node old yd_rms + ydd_rms_old.assign(N + 1, 0.0);// node old ydd_rms + dir_old.assign(N + 1, vec::Zero()); // node old CF vel direction + // ensure end moments start at zero endMomentA = vec::Zero(); endMomentB = vec::Zero(); @@ -223,7 +239,7 @@ Line::setup(int number_in, LOGDBG << " Set up Line " << number << ". " << endl; }; -std::pair, std::vector> +std::tuple, std::vector, std::vector> Line::initialize() { LOGMSG << " - Line" << number << ":" << endl @@ -239,6 +255,7 @@ Line::initialize() << " Cat : " << Cat << endl << " Cdn : " << Cdn << endl << " Cdt : " << Cdt << endl + << " Cl : " << Cl << endl << " ww_l: " << ((rho - env->rho_w) * (pi / 4. * d * d)) * 9.81 << endl; @@ -289,7 +306,7 @@ Line::initialize() << i << "Dz \t "; } } - // output VIV force + // output VIV lift force if (channels.find("V") != string::npos) { for (unsigned int i = 0; i <= N; i++) { *outfile << "Node" << i << "Vx \t Node" << i << "Vy \t Node" @@ -521,12 +538,22 @@ Line::initialize() LOGDBG << "Vertical linear initial profile for Line " << number << endl; } - LOGMSG << "Initialized Line " << number << endl; - // also assign the resulting internal node positions to the integrator // initial state vector! (velocities leave at 0) std::vector vel(N - 1, vec::Zero()); - return std::make_pair(vector_slice(r, 1, N - 1), vel); + // inital viv state vector (phase,amplitude,smoothed amplitude) + std::vector viv(N+1, vec::Zero()); + /// give a random distribution between 0 and 2pi for inital phase of lift force to avoid initial transient + if (Cl > 0.0) { + std::vector phase_range(N+1); + for (unsigned int i = 0; i < N+1; i++) phase_range[i] = (i/moordyn::real(N))*2*pi; + shuffle(phase_range.begin(),phase_range.end(),random_device()); + for (unsigned int i = 0; i < N+1; i++) viv[i][0] = phase_range[i]; + } + + LOGMSG << "Initialized Line " << number << endl; + + return std::make_tuple(vector_slice(r, 1, N - 1), vel, viv); }; real @@ -646,17 +673,20 @@ Line::calcSubSeg(unsigned int firstNodeIdx, } void -Line::setState(std::vector pos, std::vector vel) +Line::setState(std::vector pos, std::vector vel, std::vector viv) { - if ((pos.size() != N - 1) || (vel.size() != N - 1)) { + if ((pos.size() != N - 1) || (vel.size() != N - 1) || (viv.size() != N + 1)) { LOGERR << "Invalid input size" << endl; throw moordyn::invalid_value_error("Invalid input size"); } - // set interior node positions and velocities based on state vector - for (unsigned int i = 1; i < N; i++) { - r[i] = pos[i - 1]; - rd[i] = vel[i - 1]; + // set interior node positions and velocities and all VIV based on state vector + for (unsigned int i = 0; i < N+1; i++) { + if ((i != 0) && (i != N)) { + r[i] = pos[i - 1]; + rd[i] = vel[i - 1]; + } + VIV[i] = viv[i]; // VIV[i][0,1,2] correspond to phase, amplitude, smoothed amplitude. } } @@ -749,7 +779,7 @@ Line::getEndSegmentMoment(EndPoints end_point, EndPoints rod_end_point) const return qEnd * EIEnd / dlEnd; } -std::pair, std::vector> +std::tuple, std::vector, std::vector> Line::getStateDeriv() { // NOTE: @@ -1089,13 +1119,9 @@ Line::getStateDeriv() // tangential relative flow component const moordyn::real vql = vi.dot(q[i]); const vec vq = vql * q[i]; + const moordyn::real vq_mag = vq.norm(); // transverse relative flow component const vec vp = vi - vq; - // crossflow relative flow component. Normal to both cable and flow direction - vec y_dot = vi.dot(q[i].cross(Ui_hat)) * q[i].cross(Ui_hat); - // reduced velocity - // const moordyn::real V_r = Ui_mag/(omega*d); - const moordyn::real vq_mag = vq.norm(); const moordyn::real vp_mag = vp.norm(); // transverse drag @@ -1118,26 +1144,64 @@ Line::getStateDeriv() else Dq[i] = 0.25 * vq_mag * env->rho_w * Cdt * pi * d * (F[i] * l[i] + F[i - 1] * l[i - 1]) * vq; - if (Ui_mag > 0.0) { // If there is current - // phase of lift force. Assume phi(0) = 0 for now. - const moordyn::real f_hat = 0.172; // For now assume constant non-dimen frequency at max excitation. - const moordyn::real phi_dot = 2*pi*f_hat*Ui_mag / d; - // if ((i==0) && (abs(t-1.7) < 0.00001)) cout << "Phi_dot: " << phi_dot << endl; - const moordyn::real phi = phi_dot * t; - // Vortex shedding frequency - // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. - // const moordyn::real st = 0.2; - // const moordyn::real omega_s = 2 * pi * st * Ui_mag / d; - // if frequency lock in and crossflow excitation - // if ((0.6 < (phi_dot/omega_s)) && ((phi_dot/omega_s) < 1.5) && (5.0 < V_r) && (V_r < 7.0)) { // Disable for now, and run with known VIV cases - if (t == 0.0) { - y_dot = 0.4 * d * phi_dot * (q[i].cross(Ui_hat)); // Inital crossflow amplitude 40% of diameter - } - const moordyn::real C_e = 0.800; // Excitation coefficient from VIVANA theory manual for f_hat = 0.172. - const moordyn::real phase_diff = 0; // In phase motion from max excitation assumption. - const moordyn::real C_l = C_e / cos(phase_diff); - Lf[i] = 0.5 * env->rho_w * d * vi.norm() * Ui_mag * C_l * cos(phi) * q[i].cross(Ui_hat); + + // Vortex Induced Vibration (VIV) cross-flow lift force + if ((Cl > 0.0) && (!IC_gen)) { // If non-zero lift coefficient and not during IC_gen then VIV to be calculated + // Note: amplitude calculations commented out. Would be needed if a Cl vs A lookup table was implemented + + const moordyn::real phi = VIV[i][0] - (2 * pi * floor(VIV[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi + // const moordyn::real A_int = VIV[i][1]; + // const moordyn::real As = VIV[i][2]; + + // Crossflow velocity + const moordyn::real yd = rd[i].dot(q[i].cross(Ui_hat)); + + // Vortex shedding period + const moordyn::real T_s = d / (Ui_mag * 0.2); // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. + + // phase of y_dot + const moordyn::real T_m = 5 * T_s; // take the sampling time to be 5x the sheddding period + const moordyn::real n_m = int(T_m/dtm)+1; + const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Jorgen + const moordyn::real ydd_old = rdd_old[i].dot(dir_old[i]); + const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd_old*ydd_old))/n_m); + moordyn::real phi_yd; + if ((yd_rms==0.0) || (ydd_rms == 0.0)) phi_yd = atan2(-ydd_old, yd_old[i]); // To avoid divide by zero + else phi_yd = atan2(-ydd_old/ydd_rms, yd_old[i]/yd_rms); + if (phi_yd < 0) phi_yd = 2*pi + phi_yd; // atan2 to 0-2Pi range + + // non-dimensional frequency + const moordyn::real f_hat = 0.18+0.08*sin(phi_yd - phi); // phi to be integrated from state + // frequency of lift force (rad/s) + const moordyn::real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state + + // // Oscillation amplitude + // const moordyn::real A_int_dot = abs(yd); + // // Note: Check if this actually measures zero crossings + // if ((yd * yd_old[i]) < 0) { // if sign changed, i.e. a zero crossing + // Amp[i] = A_int-A_int_old[i]; // amplitude calculation since last zero crossing + // A_int_old[i] = A_int; // stores amplitude of previous zero crossing for finding Amp // } + // // Careful with integrating smoothed amplitude, as 0.1 was a calibarated value based on a very simple integration method + // const moordyn::real As_dot = (0.1/dtm)*(Amp[i]-As); // As to be variable integrated from the state. stands for amplitude smoothed + + // // Lift coefficient from lookup table + // const moordyn::real C_l = cl_lookup(x = As/d); // create function in Line.hpp that uses lookup table + + // Prep for returning VIV state derivatives + VIVd[i][0] = phi_dot; + // VIVd[i][1] = A_int_dot; + // VIVd[i][2] = As_dot; + + Lf[i] = 0.5 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp); + if ((t >= t_old + dtm) || (t == 0.0)) { + // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. + yd_old[i] = yd; // for updating rms back indexing (one moordyn timestep back) + yd_rms_old[i] = yd_rms; // for updating rms back indexing (one moordyn timestep back) + ydd_rms_old[i] = ydd_rms; // for updating rms back indexing (one moordyn timestep back) + dir_old[i] = q[i].cross(Ui_hat); // direction from previous timestep, to make sure ydd_old and yd_old have same direction + } + // FIXME: make sure that in the case of no currents, it runs fine without bugs } // tangential component of fluid acceleration @@ -1222,13 +1286,6 @@ Line::getStateDeriv() Fnet[i] += W[i] + (Dp[i] + Dq[i] + Ap[i] + Aq[i]) + B[i] + Bs[i] + Lf[i]; } - // if (t > 5) - // { - // cout << " in getStateDeriv of line " << number << endl; - // - // B[0][0] = 0.001; // meaningless - // } - // loop through internal nodes and compute the accelerations std::vector u, a; u.reserve(N - 1); @@ -1259,7 +1316,11 @@ Line::getStateDeriv() u.push_back(rd[i]); } - return make_pair(u, a); + if ((t >= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme) + rdd_old = a; // saving acceleration for VIV RMS calculation + t_old = t; // for updating back indexing if statements + } + return make_tuple(u, a, VIVd); }; // write output file for line (accepts time parameter since retained time value diff --git a/source/Line.hpp b/source/Line.hpp index bf6e47a7..cda10050 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -164,6 +164,9 @@ class Line final : public io::IO /// axial drag coefficient [-] /// with respect to surface area, \f$ \pi d l \f$ moordyn::real Cdt; + /// VIV lift coefficient [-] + /// If 0, VIV turned off + moordyn::real Cl; /// line axial internal damping coefficient (before proceessing) [Ns] moordyn::real BAin; @@ -242,6 +245,32 @@ class Line final : public io::IO // time /// simulation time moordyn::real t; + /// MoorDyn internal time step + moordyn::real dtm; + + // VIV stuff + // /// VIV amplitude updated every zero crossing of crossflow velcoity + // std::vector Amp; + /// VIV state (phase,amplitude,smoothed amplitude) + std::vector VIV; + /// derivative of VIV state (phase,amplitude,smoothed amplitude) + std::vector VIVd; + + // back indexing one dtm for VIV + /// old t + moordyn::real t_old = 0.0; + // /// running amplitude total, from previous zero crossing of yd + // std::vector A_int_old; + /// node old cf vel + std::vector yd_old; + /// node old cf vel rms + std::vector yd_rms_old; + /// node old cf accel rms + std::vector ydd_rms_old; + /// node old CF direction + std::vector dir_old; + /// node old accelerations + std::vector rdd_old; // end conditions /** @brief Types of end points @@ -302,6 +331,9 @@ class Line final : public io::IO /// lines size_t lineId; + /// boolean to indicate dynamic relaxation occuring + bool IC_gen = false; + /** @brief Setup a line * @param number Line number * @param props Line properties @@ -310,6 +342,7 @@ class Line final : public io::IO * @param env_in Global struct that holds environmental settings * @param outfile The outfile where information shall be written * @param channels The channels/fields that shall be printed in the file + * @param moordyn internal timestep. Used in VIV */ void setup(int number, LineProps* props, @@ -317,7 +350,8 @@ class Line final : public io::IO unsigned int n, EnvCondRef env_in, shared_ptr outfile, - string channels); + string channels, + real dtM0); /** @brief Set the environmental data * @param waves_in Global Waves object @@ -333,12 +367,12 @@ class Line final : public io::IO /** @brief Compute the stationary Initial Condition (IC) * @return The states, i.e. the positions of the internal nodes - * (first) and the velocities of the internal nodes (second) + * (first) and the velocities of the internal nodes (second) and the viv states (third) * @throws moordyn::output_file_error If an outfile has been provided, but * it cannot be written * @throws invalid_value_error If there is no enough water depth */ - std::pair, std::vector> initialize(); + std::tuple, std::vector, std::vector> initialize(); /** @brief Number of segments * @@ -597,11 +631,12 @@ class Line final : public io::IO /** @brief Set the line state * @param r The moordyn::Line::getN() - 1 positions * @param u The moordyn::Line::getN() - 1 velocities + * @param v The moordyn::Line::getN() + 1 viv properties * @note This method is not affecting the line end points * @see moordyn::Line::setEndState * @throws invalid_value_error If either @p r or @p u have wrong sizes */ - void setState(std::vector r, std::vector u); + void setState(std::vector r, std::vector u, std::vector v); /** @brief Set the position and velocity of an end point * @param r Position @@ -642,10 +677,10 @@ class Line final : public io::IO /** @brief Calculate forces and get the derivative of the line's states * @return The velocties of the internal nodes (first) and the accelerations - * of the internal nodes (second) + * of the internal nodes (second) and the viv derivatives (third) * @throws nan_error If nan values are detected in any node position */ - std::pair, std::vector> getStateDeriv(); + std::tuple, std::vector, std::vector> getStateDeriv(); // void initiateStep(vector &rFairIn, vector &rdFairIn, // double time); diff --git a/source/Misc.hpp b/source/Misc.hpp index 8d725e19..cc0c46c8 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -1058,6 +1058,7 @@ typedef struct _LineProps // (matching Line Dictionary inputs) double Cat; double Cdn; double Cdt; + double Cl; // VIV lift coefficient. If 0, VIV turned off. int nEApoints; // number of values in stress-strain lookup table (0 means // using constant E) double diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index f1868db8..41649b2b 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -308,6 +308,10 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) if (!skip_ic) { LOGMSG << "Finalizing ICs using dynamic relaxation (" << ICDfac << "X normal drag)" << endl; + + for (unsigned int l = 0; l < LineList.size(); l++){ + LineList[l]->IC_gen = true; // turn on IC_gen flag + } } // boost drag coefficients to speed static equilibrium convergence @@ -355,7 +359,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } MOORDYN_CATCHER(err, err_msg); if (err != MOORDYN_SUCCESS) { - LOGERR << "t = " << t << " s" << endl; + LOGERR << "Dynam Relax t = " << t << " s: " << err_msg << endl; return err; } } @@ -421,6 +425,9 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) << " s = " << 100.0 * best_score << "% on line " << best_score_line << endl; } + for (unsigned int l = 0; l < LineList.size(); l++){ + LineList[l]->IC_gen = false; // turn off IC_gen flag + } } // restore drag coefficients to normal values and restart time counter of @@ -1070,7 +1077,8 @@ moordyn::MoorDyn::ReadInFile() NumSegs, env, outfiles.back(), - outchannels); + outchannels, + dtM0); LineList.push_back(obj); LineStateIs.push_back( nX); // assign start index of this Line's states @@ -1608,7 +1616,7 @@ moordyn::MoorDyn::readLineProps(string inputText) { vector entries = moordyn::str::split(inputText, ' '); - if (!checkNumberOfEntriesInLine(entries, 10)) { + if (!checkNumberOfEntriesInLine(entries, 11)) { return nullptr; } @@ -1621,6 +1629,7 @@ moordyn::MoorDyn::readLineProps(string inputText) obj->Can = atof(entries[7].c_str()); obj->Cdt = atof(entries[8].c_str()); obj->Cat = atof(entries[9].c_str()); + obj->Cl = atof(entries[10].c_str()); moordyn::error_id err; err = read_curve(entries[3].c_str(), @@ -1652,7 +1661,8 @@ moordyn::MoorDyn::readLineProps(string inputText) << "\t\tCdn : " << obj->Cdn << endl << "\t\tCan : " << obj->Can << endl << "\t\tCdt : " << obj->Cdt << endl - << "\t\tCat : " << obj->Cat << endl; + << "\t\tCat : " << obj->Cat << endl + << "\t\tCl : " << obj->Cat << endl; return obj; } diff --git a/source/State.cpp b/source/State.cpp index 30ef5b47..6b15b8c9 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -374,6 +374,10 @@ MoorDynState::AsString() const s << "Line " << i << ":" << endl; s << lines[i].AsString(); } + for (unsigned int i = 0; i < viv.size(); i++) { + s << "VIV " << i << ":" << endl; + s << viv[i].AsString(); + } for (unsigned int i = 0; i < points.size(); i++) { s << "Point " << i << ":" << endl; s << points[i].AsString(); @@ -397,6 +401,10 @@ MoorDynState::operator=(const MoorDynState& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.push_back(l); + viv.clear(); + viv.reserve(rhs.viv.size()); + for (auto l : rhs.viv) + viv.push_back(l); points.clear(); points.reserve(rhs.points.size()); for (auto l : rhs.points) @@ -423,6 +431,11 @@ MoorDynState::operator+(const MoorDynState& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] + rhs.lines[i]); + if (viv.size() != rhs.viv.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.viv.reserve(viv.size()); + for (unsigned int i = 0; i < viv.size(); i++) + out.viv.push_back(viv[i] + rhs.viv[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -452,6 +465,11 @@ MoorDynState::operator-(const MoorDynState& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] - rhs.lines[i]); + if (viv.size() != rhs.viv.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.viv.reserve(viv.size()); + for (unsigned int i = 0; i < viv.size(); i++) + out.viv.push_back(viv[i] - rhs.viv[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -479,6 +497,10 @@ DMoorDynStateDt::AsString() const s << "Line " << i << ":" << endl; s << lines[i].AsString(); } + for (unsigned int i = 0; i < viv.size(); i++) { + s << "VIV " << i << ":" << endl; + s << viv[i].AsString(); + } for (unsigned int i = 0; i < points.size(); i++) { s << "Point " << i << ":" << endl; s << points[i].AsString(); @@ -502,6 +524,10 @@ DMoorDynStateDt::operator=(const DMoorDynStateDt& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.push_back(l); + viv.clear(); + viv.reserve(rhs.viv.size()); + for (auto l : rhs.viv) + viv.push_back(l); points.clear(); points.reserve(rhs.points.size()); for (auto l : rhs.points) @@ -526,6 +552,9 @@ DMoorDynStateDt::operator*(const real& dt) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] * dt); + out.viv.reserve(viv.size()); + for (unsigned int i = 0; i < viv.size(); i++) + out.viv.push_back(viv[i] * dt); out.points.reserve(points.size()); for (unsigned int i = 0; i < points.size(); i++) out.points.push_back(points[i] * dt); @@ -549,6 +578,11 @@ DMoorDynStateDt::operator+(const DMoorDynStateDt& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] + rhs.lines[i]); + if (viv.size() != rhs.viv.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.viv.reserve(viv.size()); + for (unsigned int i = 0; i < viv.size(); i++) + out.viv.push_back(viv[i] + rhs.viv[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -578,6 +612,11 @@ DMoorDynStateDt::operator-(const DMoorDynStateDt& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] - rhs.lines[i]); + if (viv.size() != rhs.viv.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.viv.reserve(viv.size()); + for (unsigned int i = 0; i < viv.size(); i++) + out.viv.push_back(viv[i] - rhs.viv[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); diff --git a/source/State.hpp b/source/State.hpp index ab8c28af..2c540f12 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -182,6 +182,9 @@ class MoorDynState /// The states of the lines std::vector lines; + /// The states of VIV (vel is dummy var) + std::vector viv; + /// The states of the points std::vector points; @@ -229,6 +232,9 @@ class DMoorDynStateDt /// The state derivatives of the lines std::vector lines; + /// The state derivatives of VIV (acc is dummy variable) + std::vector viv; + /// The state derivatives of the points std::vector points; diff --git a/source/Time.cpp b/source/Time.cpp index 12aa4094..2f2da0a8 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -84,7 +84,7 @@ TimeSchemeBase::Update(real t_local, unsigned int substep) for (unsigned int i = 0; i < lines.size(); i++) { lines[i]->setTime(this->t); - lines[i]->setState(r[substep].lines[i].pos, r[substep].lines[i].vel); + lines[i]->setState(r[substep].lines[i].pos, r[substep].lines[i].vel, r[substep].viv[i].pos); } } @@ -95,7 +95,7 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) waves->updateWaves(); for (unsigned int i = 0; i < lines.size(); i++) { - std::tie(rd[substep].lines[i].vel, rd[substep].lines[i].acc) = + std::tie(rd[substep].lines[i].vel, rd[substep].lines[i].acc, rd[substep].viv[i].vel) = lines[i]->getStateDeriv(); } diff --git a/source/Time.hpp b/source/Time.hpp index f8f2018e..83f955b0 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -308,16 +308,24 @@ class TimeSchemeBase : public TimeScheme // Build up the states and states derivatives unsigned int n = obj->getN() - 1; LineState state; + LineState vstate; state.pos.assign(n, vec::Zero()); state.vel.assign(n, vec::Zero()); + vstate.pos.assign(n+2, vec::Zero()); + vstate.vel.assign(n+2, vec::Zero()); for (unsigned int i = 0; i < r.size(); i++) { r[i].lines.push_back(state); + r[i].viv.push_back(vstate); } DLineStateDt dstate; + DLineStateDt vdstate; dstate.vel.assign(n, vec::Zero()); dstate.acc.assign(n, vec::Zero()); + vdstate.vel.assign(n+2, vec::Zero()); + vdstate.acc.assign(n+2, vec::Zero()); for (unsigned int i = 0; i < rd.size(); i++) { rd[i].lines.push_back(dstate); + rd[i].viv.push_back(vdstate); } } @@ -515,7 +523,7 @@ class TimeSchemeBase : public TimeScheme } for (unsigned int i = 0; i < lines.size(); i++) { - std::tie(r[0].lines[i].pos, r[0].lines[i].vel) = + std::tie(r[0].lines[i].pos, r[0].lines[i].vel, r[0].viv[i].pos) = lines[i]->initialize(); } } diff --git a/source/Waves/WaveGrid.cpp b/source/Waves/WaveGrid.cpp index 7a241cc4..19eec0b5 100644 --- a/source/Waves/WaveGrid.cpp +++ b/source/Waves/WaveGrid.cpp @@ -545,7 +545,7 @@ constructSteadyCurrentGrid(const std::string& folder, moordyn::Log* _log) { - const string CurrentsFilename = folder + "/current_profile.txt"; + const string CurrentsFilename = folder + "current_profile.txt"; LOGMSG << "Reading currents profile from '" << CurrentsFilename << "'..." << endl; From e8cff616b1b32e76615f436695e4a204ebfa56ab Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 26 Mar 2024 17:10:09 -0600 Subject: [PATCH 008/145] Backwards compatibility with input file change --- docs/inputs.rst | 3 ++- source/MoorDyn2.cpp | 7 +++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 2fb4f51e..0f08dc9c 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -294,7 +294,8 @@ The columns in order are as follows: - CdAx – tangential drag coefficient (with respect to surface area, π*d*l) - CaAx – tangential added mass coefficient (with respect to line displacement) - Cl – the crossflow VIV lift coefficient. If set to 0, then VIV calculations are disabled for the - line. The theory of vortex induced vibrations can be found :ref:`here ` + line. This coefficient has been made backwards compatible. If it is not provided, then it is + assumed to be 0.0. The theory of vortex induced vibrations can be found :ref:`here ` Note: Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file must be located in the same folder as the main MoorDyn input file for MoorDyn-C or for MoorDyn-F diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 41649b2b..c8578eb1 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1616,10 +1616,12 @@ moordyn::MoorDyn::readLineProps(string inputText) { vector entries = moordyn::str::split(inputText, ' '); - if (!checkNumberOfEntriesInLine(entries, 11)) { + if (!checkNumberOfEntriesInLine(entries, 10)) { return nullptr; } + cout << "Entries size: " << entries.size() << endl; + LineProps* obj = new LineProps(); obj->type = entries[0]; @@ -1629,7 +1631,8 @@ moordyn::MoorDyn::readLineProps(string inputText) obj->Can = atof(entries[7].c_str()); obj->Cdt = atof(entries[8].c_str()); obj->Cat = atof(entries[9].c_str()); - obj->Cl = atof(entries[10].c_str()); + if (entries.size() == 10) obj->Cl = 0.0; // If no lift coefficient, disable VIV. For backwards compatability. + else obj->Cl = atof(entries[10].c_str()); moordyn::error_id err; err = read_curve(entries[3].c_str(), From c173eef549248018e680e410d3458afd709e7fb2 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 26 Apr 2024 20:55:11 -0600 Subject: [PATCH 009/145] Add rolling rms sampling time to options list as vivTs --- source/Line.cpp | 13 ++++++++----- source/Line.hpp | 2 ++ source/Misc.hpp | 2 ++ source/MoorDyn2.cpp | 5 +++-- 4 files changed, 15 insertions(+), 7 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 5766b1dd..7ac85c21 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -155,6 +155,9 @@ Line::setup(int number_in, Cdt = props->Cdt; Cl = props->Cl; + // assign number of time steps for RMS back indexing from MD options + n_m = int(env->Ts/dtm)+1; + // copy in nonlinear stress-strain data if applicable stiffXs.clear(); stiffYs.clear(); @@ -1154,14 +1157,14 @@ Line::getStateDeriv() // const moordyn::real As = VIV[i][2]; // Crossflow velocity - const moordyn::real yd = rd[i].dot(q[i].cross(Ui_hat)); + const moordyn::real yd = rd[i].dot(q[i].cross(vp.normalized())); - // Vortex shedding period - const moordyn::real T_s = d / (Ui_mag * 0.2); // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. + // // Vortex shedding period + // const moordyn::real T_s = d / (Ui_mag * 0.2); // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. // phase of y_dot - const moordyn::real T_m = 5 * T_s; // take the sampling time to be 5x the sheddding period - const moordyn::real n_m = int(T_m/dtm)+1; + // const moordyn::real T_m = 5 * T_s; // take the sampling time to be 5x the sheddding period + // const moordyn::real n_m = int(T_m/dtm)+1; const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Jorgen const moordyn::real ydd_old = rdd_old[i].dot(dir_old[i]); const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd_old*ydd_old))/n_m); diff --git a/source/Line.hpp b/source/Line.hpp index cda10050..79a81135 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -255,6 +255,8 @@ class Line final : public io::IO std::vector VIV; /// derivative of VIV state (phase,amplitude,smoothed amplitude) std::vector VIVd; + /// Num timesteps for rolling RMS of crossflow velocity phase + unsigned int n_m; // back indexing one dtm for VIV /// old t diff --git a/source/Misc.hpp b/source/Misc.hpp index cc0c46c8..0dcb8d98 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -1022,6 +1022,8 @@ struct EnvCond double kb; /// bottom damping (Pa/m/s) double cb; + /// VIV RMS sampling time for crossflow velcoity phase (s) + double Ts; /// Bottom modeling mode (0=flat, 1=3d...)<<< moordyn::seafloor_settings SeafloorMode; diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index c8578eb1..6e28d351 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -127,6 +127,7 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) env->rho_w = 1025.; env->kb = 3.0e6; env->cb = 3.0e5; + env->Ts = 3.0; env->waterKinOptions = waves::WaterKinOptions(); env->WriteUnits = 1; // by default, write units line env->writeLog = 0; // by default, don't write out a log file @@ -1620,8 +1621,6 @@ moordyn::MoorDyn::readLineProps(string inputText) return nullptr; } - cout << "Entries size: " << entries.size() << endl; - LineProps* obj = new LineProps(); obj->type = entries[0]; @@ -2045,6 +2044,8 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) ICDfac = atof(entries[0].c_str()); else if ((name == "threshIC") || (name == "ICthresh")) ICthresh = atof(entries[0].c_str()); + else if ((name == "vivTs")) + env->Ts = atof(entries[0].c_str()); else if (name == "WaveKin") { WaveKinTemp = (waves::waves_settings)stoi(entries[0]); if ((WaveKinTemp < waves::WAVES_NONE) || From 58d616cbc39d9c05972fa4e6d807d5063f9660e7 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 13 May 2024 18:21:13 -0600 Subject: [PATCH 010/145] Docs update for failure --- docs/inputs.rst | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 0f08dc9c..43da4de4 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -479,20 +479,26 @@ For example, outputting node positions and segment tensions could be achieved by 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 -^^^^^^^ +Failure (MoorDyn-F only) +^^^^^^^^^^^^^^^^^^^^^^^^ -This section (optional) describes the failure conditions of the system. +This section (optional) describes the failure conditions of the system. Line failures can only be +triggered at an existing point or rod end where a line/lines are attached. Failures can be +triggered by a time or attachment tension threshold, which ever comes first. Users can specify +multiple failures for a given point, but duplicate failure configurations will be ignored. +If two lines attached to a point are listed to fail (failure 1 for example), then after the failure +the lines will remain attached to each other by a free point. In this multi line case, if any line +reaches the tension threshold then the failure will be triggered. The theory behind failures can be +found :ref:`here `. .. 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 - + FailureID Point Line(s) FailTime FailTen + () () (,) (s or 0) (N or 0) + 1 5 1,2,3,4 0 1200e3 + 2 3 1 0 1200e3 + 3 R1a 1,2,3 12 0 Control (MoorDyn-F only) ^^^^^^^^^^^^^^^^^^^^^^^^ From 015dbaa175e86823cc203dff09af7d89ccd12229 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 15 May 2024 11:25:24 -0600 Subject: [PATCH 011/145] Update units for damping in comments and log --- source/Line.cpp | 2 +- source/Line.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 7ac85c21..0b15ca3c 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -464,7 +464,7 @@ Line::initialize() // BAin), then -BAin indicates desired damping ratio) c = -BAin * UnstrLen / N * sqrt(E * rho); // rho = w/A LOGMSG << "Line " << number << " damping set to " << c - << " Ns = " << c * A << " Pa-s, based on input of " << BAin + << " Pa-s = " << c * A << " Ns, based on input of " << BAin << endl; } else { // otherwise it's the regular internal damping coefficient, which should diff --git a/source/Line.hpp b/source/Line.hpp index 79a81135..0c08cb22 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -143,7 +143,7 @@ class Line final : public io::IO moordyn::real E; /// line bending stiffness [Nm^2] moordyn::real EI; - /** line axial internal damping coefficient [Ns] + /** line axial internal damping coefficient [Pa-s] * * The provided value in moordyn::Line::props::c can be either the literal * damping coefficient, or a negative value in which case it represents the From 60855c31fe345a4970a4a8d1de27743fe00e4ab6 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 17 May 2024 12:48:57 -0600 Subject: [PATCH 012/145] Remove RMS sampling window from options, expand line list to include VIV synch model params --- docs/inputs.rst | 14 +++++++++----- source/Line.cpp | 9 +++++---- source/Line.hpp | 8 +++++++- source/Misc.hpp | 4 ++-- source/MoorDyn2.cpp | 18 +++++++++++++----- 5 files changed, 36 insertions(+), 17 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 43da4de4..2f16c8fc 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -272,10 +272,10 @@ that will be used in the simulation .. code-block:: none - ---------------------- LINE TYPES ----------------------------------- - TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx Cl - (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 0.8 + ---------------------- LINE TYPES ---------------------------------------------------------------------- + TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx Cl dF cF + (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 0.8 0.08 0.18 The columns in order are as follows: @@ -293,9 +293,13 @@ The columns in order are as follows: - 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) - - Cl – the crossflow VIV lift coefficient. If set to 0, then VIV calculations are disabled for the + - Cl – OPTIONAL - the crossflow VIV lift coefficient. If set to 0, then VIV calculations are disabled for the line. This coefficient has been made backwards compatible. If it is not provided, then it is assumed to be 0.0. The theory of vortex induced vibrations can be found :ref:`here ` + - dF - OPTIONAL - the cF +- range of non-dimensional frequnecies 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 + provided and VIV is enabled (Cl > 0) then it is default to 0.18 to align with the the theory found :ref:`here ` Note: Non-linear values for the stiffness (EA) are an option in MoorDyn. For this, a file name can be provided instead of a number. This file must be located in the same folder as the main MoorDyn input file for MoorDyn-C or for MoorDyn-F diff --git a/source/Line.cpp b/source/Line.cpp index 0b15ca3c..ba6e4dc9 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -154,9 +154,8 @@ Line::setup(int number_in, Cdn = props->Cdn; Cdt = props->Cdt; Cl = props->Cl; - - // assign number of time steps for RMS back indexing from MD options - n_m = int(env->Ts/dtm)+1; + dF = props->dF; + cF = props->cF; // copy in nonlinear stress-strain data if applicable stiffXs.clear(); @@ -259,6 +258,8 @@ Line::initialize() << " Cdn : " << Cdn << endl << " Cdt : " << Cdt << endl << " Cl : " << Cl << endl + << " dF : " << dF << endl + << " cF : " << cF << endl << " ww_l: " << ((rho - env->rho_w) * (pi / 4. * d * d)) * 9.81 << endl; @@ -1174,7 +1175,7 @@ Line::getStateDeriv() if (phi_yd < 0) phi_yd = 2*pi + phi_yd; // atan2 to 0-2Pi range // non-dimensional frequency - const moordyn::real f_hat = 0.18+0.08*sin(phi_yd - phi); // phi to be integrated from state + const moordyn::real f_hat = cF + dF *sin(phi_yd - phi); // phi to be integrated from state // frequency of lift force (rad/s) const moordyn::real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state diff --git a/source/Line.hpp b/source/Line.hpp index 0c08cb22..8cf6894f 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -167,6 +167,12 @@ class Line final : public io::IO /// VIV lift coefficient [-] /// If 0, VIV turned off moordyn::real Cl; + /// +- range of VIV synchronization [-] + /// in non-dimensional frequency + moordyn::real dF; + /// Center VIV synchronization [-] + /// in non-dimensional frequency + moordyn::real cF; /// line axial internal damping coefficient (before proceessing) [Ns] moordyn::real BAin; @@ -256,7 +262,7 @@ class Line final : public io::IO /// derivative of VIV state (phase,amplitude,smoothed amplitude) std::vector VIVd; /// Num timesteps for rolling RMS of crossflow velocity phase - unsigned int n_m; + const unsigned int n_m = 500; // back indexing one dtm for VIV /// old t diff --git a/source/Misc.hpp b/source/Misc.hpp index 0dcb8d98..43cb0aad 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -1022,8 +1022,6 @@ struct EnvCond double kb; /// bottom damping (Pa/m/s) double cb; - /// VIV RMS sampling time for crossflow velcoity phase (s) - double Ts; /// Bottom modeling mode (0=flat, 1=3d...)<<< moordyn::seafloor_settings SeafloorMode; @@ -1061,6 +1059,8 @@ typedef struct _LineProps // (matching Line Dictionary inputs) double Cdn; double Cdt; double Cl; // VIV lift coefficient. If 0, VIV turned off. + double dF; // +- range around cF for VIV synchronization model + double cF; // center non-dim frequency for VIV synch model int nEApoints; // number of values in stress-strain lookup table (0 means // using constant E) double diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 6e28d351..e1d6edd1 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -127,7 +127,6 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) env->rho_w = 1025.; env->kb = 3.0e6; env->cb = 3.0e5; - env->Ts = 3.0; env->waterKinOptions = waves::WaterKinOptions(); env->WriteUnits = 1; // by default, write units line env->writeLog = 0; // by default, don't write out a log file @@ -1630,8 +1629,19 @@ moordyn::MoorDyn::readLineProps(string inputText) obj->Can = atof(entries[7].c_str()); obj->Cdt = atof(entries[8].c_str()); obj->Cat = atof(entries[9].c_str()); - if (entries.size() == 10) obj->Cl = 0.0; // If no lift coefficient, disable VIV. For backwards compatability. - else obj->Cl = atof(entries[10].c_str()); + if (entries.size() == 10) { + obj->Cl = 0.0; // If no lift coefficient, disable VIV. For backwards compatability. + obj->dF = 0.0; + obj->cF = 0.0; + } else if (entries.size() == 11) { + obj->Cl = atof(entries[10].c_str()); + obj->dF = 0.08; // set to default Thorsen synchronization range if not provided + obj->cF = 0.18; // set to default Thorsen synchronization centering if not provided + } else if (entries.size() == 13) { + obj->Cl = atof(entries[10].c_str()); + obj->dF = atof(entries[11].c_str()); + obj->cF = atof(entries[12].c_str()); + } else return nullptr; moordyn::error_id err; err = read_curve(entries[3].c_str(), @@ -2044,8 +2054,6 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) ICDfac = atof(entries[0].c_str()); else if ((name == "threshIC") || (name == "ICthresh")) ICthresh = atof(entries[0].c_str()); - else if ((name == "vivTs")) - env->Ts = atof(entries[0].c_str()); else if (name == "WaveKin") { WaveKinTemp = (waves::waves_settings)stoi(entries[0]); if ((WaveKinTemp < waves::WAVES_NONE) || From 3568c8a4b79a0c98bb970dcc6ef7d9c7d29326c0 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 3 Jun 2024 18:08:58 -0600 Subject: [PATCH 013/145] linear line initalization tolerance added --- source/Line.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Line.cpp b/source/Line.cpp index ba6e4dc9..cf307bd2 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -483,7 +483,7 @@ Line::initialize() // catenary routine (from FAST v.7) real XF = dir(Eigen::seqN(0, 2)).norm(); // horizontal spread - if (XF > 0.0) { + if (XF > 0.0001) { // tolerance for calculation of XF when points are not along x or y axis real ZF = dir[2]; real LW = ((rho - env->rho_w) * A) * env->g; From 28b2fb1e761d6f1c9899befe4a72b6210fc8f8ae Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 24 Jun 2024 06:37:39 +0200 Subject: [PATCH 014/145] Starting 2.3.4 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4883fb66..bbe2536d 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 3) -set(MOORDYN_PATCH_VERSION 3) +set(MOORDYN_PATCH_VERSION 4) set(MOORDYN_VERSION ${MOORDYN_MAJOR_VERSION}.${MOORDYN_MINOR_VERSION}) project(Moordyn VERSION ${MOORDYN_VERSION}) From 550648b4da77173371b30738adbf1b9d13dbaf61 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 18 Jun 2024 13:15:09 +0200 Subject: [PATCH 015/145] Let's start building and testing MoorDynF --- .github/workflows/mdf_verification.yml | 72 ++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 .github/workflows/mdf_verification.yml diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml new file mode 100644 index 00000000..a6317a92 --- /dev/null +++ b/.github/workflows/mdf_verification.yml @@ -0,0 +1,72 @@ +name: MoorDynF regression tests + +on: + push: + branches: [ $default-branch, master, mdf ] + pull_request: + branches: + - "**" + +permissions: write-all + +env: + # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) + BUILD_TYPE: Release + +jobs: + test: + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-22.04] + + steps: + - uses: actions/checkout@v4 + + - name: Setup Python + uses: actions/setup-python@v5 + id: setup-python + + - name: Install Python dependencies + run: pip install --upgrade pytest Bokeh + + - name: Download OpenFAST + shell: bash + run: | + cd ${{github.workspace}}/ + git clone --recursive https://github.com/OpenFAST/openfast.git + + - name: Compile MoorDynF + shell: bash + run: | + cd ${{github.workspace}}/ + mkdir -p openfast.build + cd openfast.build + cmake openfast -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=${{github.workspace}}/install -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DBUILD_TESTING=ON ../openfast + make moordyn_driver + cd ${{github.workspace}}/ + + - name: Run MoorDynF regression tests + shell: bash + run: | + cd ${{github.workspace}}/openfast.build + ctest -VV -R md_ -LE python + cd ${{github.workspace}}/ + + - name: Create install folder + run: | + mkdir -p ${{github.workspace}}/install + + - name: Configure CMake + 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=ON -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DBUILD_TESTING=ON + + - name: Build + id: build + run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Install + run: cmake --install ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Set env variables for the tests + run: | + echo "LD_LIBRARY_PATH=${{github.workspace}}/build/source/" >> $GITHUB_ENV From bbfe6ae493569b81718e2225d6f53e6abc82166c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 18 Jun 2024 13:23:51 +0200 Subject: [PATCH 016/145] We do not need VTK --- .github/workflows/mdf_verification.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml index a6317a92..863f2597 100644 --- a/.github/workflows/mdf_verification.yml +++ b/.github/workflows/mdf_verification.yml @@ -58,7 +58,7 @@ jobs: mkdir -p ${{github.workspace}}/install - name: Configure CMake - 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=ON -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DBUILD_TESTING=ON + 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=ON -DFORTRAN_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=OFF -DBUILD_TESTING=ON - name: Build id: build From 3e6cd676e79ad186ffe5faf6bc0f7f424ef02197 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 18 Jun 2024 13:33:26 +0200 Subject: [PATCH 017/145] pypa's build pacakge is required --- .github/workflows/mdf_verification.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml index 863f2597..01cc9759 100644 --- a/.github/workflows/mdf_verification.yml +++ b/.github/workflows/mdf_verification.yml @@ -28,7 +28,7 @@ jobs: id: setup-python - name: Install Python dependencies - run: pip install --upgrade pytest Bokeh + run: pip install --upgrade build pytest Bokeh - name: Download OpenFAST shell: bash From 42ae5e476dede793d2025e4a216807c70b67537d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 10:05:54 +0200 Subject: [PATCH 018/145] entries[0] is the failure index --- source/MoorDyn2.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index e554540a..c507a467 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1159,7 +1159,7 @@ moordyn::MoorDyn::ReadInFile() std::string let1, num1, let2, num2, let3; // divided outWord into letters and numbers - str::decomposeString(entries[0], let1, num1, let2, num2, let3); + str::decomposeString(entries[1], let1, num1, let2, num2, let3); if (num1.empty()) { LOGERR << "Error in " << _filepath << ":" << i + 1 << "..." @@ -1209,7 +1209,7 @@ moordyn::MoorDyn::ReadInFile() return MOORDYN_INVALID_INPUT; } - vector lineNums = moordyn::str::split(entries[1], ','); + vector lineNums = moordyn::str::split(entries[2], ','); obj->lines.reserve(lineNums.size()); obj->line_end_points.reserve(lineNums.size()); for (unsigned int il = 0; il < lineNums.size(); il++) { @@ -1225,8 +1225,8 @@ moordyn::MoorDyn::ReadInFile() obj->line_end_points.push_back(ENDPOINT_A); } - obj->time = atof(entries[2].c_str()); - obj->ten = atof(entries[3].c_str()); + obj->time = atof(entries[3].c_str()); + obj->ten = atof(entries[4].c_str()); LOGDBG << "fail time is " << obj->time << " s" << endl; LOGDBG << "fail ten is " << obj->ten << " N" << endl; From c4b82d86da680c92f1257f0b1e8ca9b06922380b Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 10:13:14 +0200 Subject: [PATCH 019/145] kbot and cbot options are accepted by MDF --- source/MoorDyn2.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index c507a467..8e82c3b1 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -2020,9 +2020,9 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) env->rho_w = atof(entries[0].c_str()); else if (name == "WtrDpth") env->WtrDpth = atof(entries[0].c_str()); - else if ((name == "kBot") || (name == "kb")) + else if ((name == "kBot") || (name == "kbot") || (name == "kb")) env->kb = atof(entries[0].c_str()); - else if ((name == "cBot") || (name == "cb")) + else if ((name == "cBot") || (name == "cbot") || (name == "cb")) env->cb = atof(entries[0].c_str()); else if ((name == "dtIC") || (name == "ICdt")) ICdt = atof(entries[0].c_str()); From fc94882f56c63687542437e513d53a854b68b43d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 10:39:09 +0200 Subject: [PATCH 020/145] WIP verification against MDF --- .github/rsc/moordyn.dat | 71 +++++++ .github/rsc/verify.py | 252 +++++++++++++++++++++++++ .github/workflows/mdf_verification.yml | 2 +- 3 files changed, 324 insertions(+), 1 deletion(-) create mode 100644 .github/rsc/moordyn.dat create mode 100644 .github/rsc/verify.py diff --git a/.github/rsc/moordyn.dat b/.github/rsc/moordyn.dat new file mode 100644 index 00000000..3bd25a5c --- /dev/null +++ b/.github/rsc/moordyn.dat @@ -0,0 +1,71 @@ +--------------------- MoorDyn Input File ------------------------------------ +Mooring system for OC4-DeepCwind Semi +----------------------- LINE TYPES ------------------------------------------ +Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx +(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-) +main 0.0766 113.35 7.536E8 -1.0 0 2.0 0.8 0.4 0.25 +---------------------- POINTS -------------------------------- +ID Attachment X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed 418.8 725.383 -200.0 0 0 0 0 +2 Fixed -837.6 0.0 -200.0 0 0 0 0 +3 Fixed 418.8 -725.383 -200.0 0 0 0 0 +4 Vessel 20.434 35.393 -14.0 0 0 0 0 +5 Vessel -40.868 0.0 -14.0 0 0 0 0 +6 Vessel 20.434 -35.393 -14.0 0 0 0 0 +---------------------- LINES -------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs Outputs +(-) (-) (-) (-) (m) (-) (-) +1 main 1 4 835.35 20 - +2 main 2 5 835.35 20 - +3 main 3 6 835.35 20 - +---------------------- SOLVER OPTIONS --------------------------------------- +0.001 dtM - time step to use in mooring integration (s) +3.0e6 kbot - bottom stiffness (Pa/m) +3.0e5 cbot - bottom damping (Pa-s/m) +2.0 dtIC - time interval for analyzing convergence during IC gen (s) +60.0 TmaxIC - max time for ic gen (s) +4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) +0.01 threshIC - threshold for IC convergence (-) +200.0 WtrDpth option set by the driver +1025.0 rho option set by the driver +9.80665 gravity option set by the driver +------------------------ OUTPUTS -------------------------------------------- +FairTen1 +FairTen2 +FairTen3 +AnchTen1 +AnchTen2 +AnchTen3 +L1N10T +L2N10T +L3N10T +P4Fx +P4Fy +P4Fz +P5Fx +P5Fy +P5Fz +P6Fx +P6Fy +P6Fz +L1N19Px +L1N19Py +L1N19Pz +L2N19Px +L2N19Py +L2N19Pz +L3N19Px +L3N19Py +L3N19Pz +P4Px +P4Py +P4Pz +P5Px +P5Py +P5Pz +P6Px +P6Py +P6Pz +END +------------------------- need this line -------------------------------------- diff --git a/.github/rsc/verify.py b/.github/rsc/verify.py new file mode 100644 index 00000000..c5098834 --- /dev/null +++ b/.github/rsc/verify.py @@ -0,0 +1,252 @@ +import argparse +import os +import sys +import moordyn +import numpy as np + +parser = argparse.ArgumentParser( + description='Run the same MDF regression tests and check') +parser.add_argument('root', + help='The root folder with both openfast/ and openfast.build/ subfolders') + + +# Let's start importing some handy tools from MDF +args = parser.parse_args() +sys.path.append(os.path.join(args.root, 'openfast/reg_tests/lib/')) +import pass_fail + +# Now get the list of tests to run +mdf_results_root = os.path.join(args.root, + 'openfast.build/reg_tests/modules/moordyn/') +tests = [f for f in os.listdir(mdf_results_root) if os.path.isdir( + os.path.join(mdf_results_root, f))] + + +def mdopts2dict(lines): + data = {} + for i, line in enumerate(lines): + line = line.strip() + if line == "": + continue + + def to_num(s): + try: + return int(s) + except ValueError: + try: + return float(s) + except ValueError: + return s + + if line.startswith('"'): + # The value is a string + end = line[1:].find('"') + 1 + value = line[1:end] + else: + end = line.find(' ') + value = to_num(line[:end]) + + line = line[end:] + while line.find(" ") != -1: + line = line.replace(" ", " ") + key = line.split(" ")[1] + + data[key] = value + + return data + + +def read_driver(test): + # Read the driver test data + test_root = os.path.join(args.root, + 'openfast/reg_tests/r-test/modules/moordyn/', + test) + with open(os.path.join(test_root, "md_driver.inp"), "r") as f: + lines = f.readlines() + + def get_section(lines, name): + start, end = None, None + for i, line in enumerate(lines): + line = line.strip() + if not line.startswith("---"): + continue + if start is None and name in line: + start = i + 1 + continue + if start is not None and end is None: + end = i + break + assert start is not None + end = end or len(lines) + assert start < end + return lines[start:end] + + env = mdopts2dict(get_section(lines, "ENVIRONMENTAL CONDITIONS")) + md = mdopts2dict(get_section(lines, "MOORDYN")) + for filepaths in ("MDInputFile", "InputsFile", "OutRootName"): + if md[filepaths]: + md[filepaths] = os.path.join(test_root, md[filepaths]) + md["OutRootName"] = md["OutRootName"] + ".MD.out" + return env, md + + +def create_input_file(env, md): + fname = os.path.basename(md["MDInputFile"]) + with open(md["MDInputFile"], "r") as fin, open(fname, "w") as fout: + lines = fin.readlines() + # Find the options section and append the env options (if required) + for i, line in enumerate(lines): + line = line.strip() + if line.startswith('---') and "OPTIONS" in line: + start = i + 1 + break + opts = lines[start:] + end = len(opts) + for i, line in enumerate(opts): + line = line.strip() + if line.startswith('---'): + end = i + break + opts = mdopts2dict(opts[:end]) + for optin, optout in (('Gravity', 'gravity'), + ('rhoW', 'rho'), + ('WtrDpth', 'WtrDpth')): + if optin not in env.keys(): + if optout not in opts.keys(): + print(f"WARNING: Environmental option {optin} not defined") + continue + if optout in opts.keys(): + # Warn about the conflict. We will anyway overwrite the option + if env[optin] != opts[optout]: + print( + f"WARNING: {optin}={env[optin]} in MDF driver vs. " + \ + f"{optout}={opts[optout]} in MoorDyn config file") + lines.insert(start + end, + f"{env[optin]} {optout} option set by the driver\n") + for line in lines: + fout.write(line) + return fname + + +def read_motions(fpath): + data = [] + with open(fpath, "r") as fin: + lines = fin.readlines() + for line in lines: + line = line.strip() + if line.startswith("#") or line == "": + continue + while line.find(" ") != -1: + line = line.replace(" ", " ") + fields = [float(field) for field in line.split()] + if len(data): + assert len(data[-1]) == len(fields) + data.append(fields) + return np.transpose(data) + + +def interpolate_motions(motions, md): + t = np.arange(0, md["TMax"] + md["dtC"], md["dtC"]) + new_motions = [t] + for i in range(1, motions.shape[0]): + new_motions.append(np.interp(t, motions[0, :], motions[i, :])) + return np.asarray(new_motions) + + +def get_state(system): + """ Get all the state variables, as they would be used on moordyn.Init() + and moordyn.Step() + + Parameters + ========== + + system (cmoordyn.MoorDyn): The MoorDyn instance + + Returns + ======= + + state (lst): The list with the sate variables + names (lst): The list of names that each state variable belongs to + """ + state = [] + names = [] + n_bodies = moordyn.GetNumberBodies(system) + for i in range(n_bodies): + body = moordyn.GetBody(system, i + 1) + if moordyn.GetBodyType(body) not in (moordyn.BODY_TYPE_COUPLED,): + continue + body_id = moordyn.GetBodyID(body) + body_state = moordyn.GetBodyState(body) + + state += np.array(body_state).flatten().tolist() + names += [f"body_{body_id}",] * len(body_state) + n_rods = moordyn.GetNumberRods(system) + for i in range(n_rods): + rod = moordyn.GetRod(system, i + 1) + if moordyn.GetRodType(rod) not in (moordyn.ROD_TYPE_COUPLED, + moordyn.ROD_TYPE_CPLDPIN): + continue + rod_id = moordyn.GetRodID(rod) + rod_state = moordyn.GetRodState(rod) + state += np.array(rod_state).flatten().tolist() + names += [f"rod_{rod_id}",] * len(rod_state) + n_points = moordyn.GetNumberPoints(system) + for i in range(n_points): + point = moordyn.GetPoint(system, i + 1) + if moordyn.GetPointType(point) not in (moordyn.POINT_TYPE_COUPLED, ): + continue + point_id = moordyn.GetPointID(point) + point_state = moordyn.GetPointPos(point) + state += point_state + names += [f"point_{point_id}",] * len(point_state) + return state, names + + +def read_outs(fpath, skiplines=2): + data = [] + with open(fpath, "r") as fin: + lines = fin.readlines()[skiplines:] + for line in lines: + line = line.strip().replace("\t", " ") + while line.find(" ") != -1: + line = line.replace(" ", " ") + data.append([float(field) for field in line.split()]) + return np.transpose(data) + + +# Run the tests... +all_good = True +for test in tests: + print(f"Test {test}...") + env, md = read_driver(test) + fname = create_input_file(env, md) + system = moordyn.Create(fname) + # Get the NDoFs and check if the motions are right + ndofs = moordyn.NCoupledDOF(system) + motions = None + if md["InputsMode"]: + motions = interpolate_motions(read_motions(md["InputsFile"]), md) + assert motions.shape[0] - 1 == ndofs + # Run the simulation + r, _ = get_state(system) + u = [0 for i in range(ndofs)] + moordyn.Init(system, r, u) + dt = md["dtC"] + T = md["TMax"] + tlist = np.arange(0, T, dt) + for i, t in enumerate(tlist): + rorg, _ = get_state(system) + rorg = np.asarray(rorg) + rdst = rorg if motions is None else motions[1:, i + 1] + u = (rdst - rorg) / dt + moordyn.Step(system, r, u, t, dt) + moordyn.Close(system) + # Read the ouputs and compare + ref = read_outs(md["OutRootName"], skiplines=8) + new = read_outs(os.path.splitext(fname)[0] + ".out", skiplines=2) + passing = np.all(pass_fail.passing_channels(ref, new, 2.0, 1.9)) + print("Passed!" if passing else "Failed.") + if not passing: + all_good = False + +assert all_good diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml index 01cc9759..348ae33a 100644 --- a/.github/workflows/mdf_verification.yml +++ b/.github/workflows/mdf_verification.yml @@ -28,7 +28,7 @@ jobs: id: setup-python - name: Install Python dependencies - run: pip install --upgrade build pytest Bokeh + run: pip install --upgrade build pytest Bokeh numpy - name: Download OpenFAST shell: bash From 89a20e19982279336a2b0b569e15e821930acc43 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 13:45:17 +0200 Subject: [PATCH 021/145] Verifier Python script --- .github/rsc/verify.py | 55 ++++++++++++++++++++++++++++++++++++------- 1 file changed, 46 insertions(+), 9 deletions(-) diff --git a/.github/rsc/verify.py b/.github/rsc/verify.py index c5098834..86fc5bd9 100644 --- a/.github/rsc/verify.py +++ b/.github/rsc/verify.py @@ -3,11 +3,22 @@ import sys import moordyn import numpy as np +try: + import matplotlib.pyplot as plt + import matplotlib.colors as mcolors +except ImportError: + plt = None parser = argparse.ArgumentParser( description='Run the same MDF regression tests and check') -parser.add_argument('root', +parser.add_argument('root', type=str, help='The root folder with both openfast/ and openfast.build/ subfolders') +parser.add_argument('--rtol', type=float, default=1.5, + help=('Relative tolerance to allow the solution to deviate; expressed as ', + 'order of magnitudes less than baseline')) +parser.add_argument('--atol', type=float, default=1.5, + help=('Absolute tolerance to allow small values to pass; expressed as ', + 'order of magnitudes less than baseline')) # Let's start importing some handy tools from MDF @@ -214,8 +225,21 @@ def read_outs(fpath, skiplines=2): return np.transpose(data) +def plot(ref, data, fpath): + if plt is None: + return + colors = list(mcolors.XKCD_COLORS.values()) + for i in range(1, ref.shape[0]): + plt.plot(ref[0, :], ref[i, :], linestyle='dashed', + color=colors[i - 1]) + plt.plot(data[0, :], data[i, :], linestyle='solid', + color=colors[i - 1], label=f'channel {i}') + plt.legend(loc='best') + plt.savefig(fpath) + + # Run the tests... -all_good = True +summary = {} for test in tests: print(f"Test {test}...") env, md = read_driver(test) @@ -228,7 +252,7 @@ def read_outs(fpath, skiplines=2): motions = interpolate_motions(read_motions(md["InputsFile"]), md) assert motions.shape[0] - 1 == ndofs # Run the simulation - r, _ = get_state(system) + r = get_state(system)[0] if motions is None else motions[1:, 0] u = [0 for i in range(ndofs)] moordyn.Init(system, r, u) dt = md["dtC"] @@ -239,14 +263,27 @@ def read_outs(fpath, skiplines=2): rorg = np.asarray(rorg) rdst = rorg if motions is None else motions[1:, i + 1] u = (rdst - rorg) / dt - moordyn.Step(system, r, u, t, dt) + moordyn.Step(system, rorg, u, t, dt) moordyn.Close(system) # Read the ouputs and compare ref = read_outs(md["OutRootName"], skiplines=8) new = read_outs(os.path.splitext(fname)[0] + ".out", skiplines=2) - passing = np.all(pass_fail.passing_channels(ref, new, 2.0, 1.9)) - print("Passed!" if passing else "Failed.") - if not passing: - all_good = False + # Drop the eventual points at the tail that ight come from precision errors + # on the time + n_samples = min(ref.shape[1], new.shape[1]) + ref = ref[:, :n_samples] + new = new[:, :n_samples] + plot(ref, new, test + ".png") + passing = np.all( + pass_fail.passing_channels(ref, new, args.rtol, args.atol)) + + summary[test] = passing -assert all_good +if np.any(summary.values()): + print("") + print("=" * 80) + print(f"{np.sum(list(summary.values()))} / {len(summary.values())} failed:") + for i, (key, value) in enumerate(summary.items()): + print(f"\t{i + 1}: Test '{key}' " + ("PASSED" if value else "FAILED")) + print("=" * 80) + print("") From e237fd9af17b09b68b1a30f56960cca2bfa52047 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 13:52:10 +0200 Subject: [PATCH 022/145] First try of verifying --- .github/rsc/moordyn.dat | 71 ------------------- .github/workflows/mdf_verification.yml | 3 + .../rsc => tests/.mdf_verification}/verify.py | 34 +++++++++ 3 files changed, 37 insertions(+), 71 deletions(-) delete mode 100644 .github/rsc/moordyn.dat rename {.github/rsc => tests/.mdf_verification}/verify.py (83%) diff --git a/.github/rsc/moordyn.dat b/.github/rsc/moordyn.dat deleted file mode 100644 index 3bd25a5c..00000000 --- a/.github/rsc/moordyn.dat +++ /dev/null @@ -1,71 +0,0 @@ ---------------------- MoorDyn Input File ------------------------------------ -Mooring system for OC4-DeepCwind Semi ------------------------ LINE TYPES ------------------------------------------ -Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx -(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-) -main 0.0766 113.35 7.536E8 -1.0 0 2.0 0.8 0.4 0.25 ----------------------- POINTS -------------------------------- -ID Attachment X Y Z M V CdA CA -(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) -1 Fixed 418.8 725.383 -200.0 0 0 0 0 -2 Fixed -837.6 0.0 -200.0 0 0 0 0 -3 Fixed 418.8 -725.383 -200.0 0 0 0 0 -4 Vessel 20.434 35.393 -14.0 0 0 0 0 -5 Vessel -40.868 0.0 -14.0 0 0 0 0 -6 Vessel 20.434 -35.393 -14.0 0 0 0 0 ----------------------- LINES -------------------------------------- -ID LineType AttachA AttachB UnstrLen NumSegs Outputs -(-) (-) (-) (-) (m) (-) (-) -1 main 1 4 835.35 20 - -2 main 2 5 835.35 20 - -3 main 3 6 835.35 20 - ----------------------- SOLVER OPTIONS --------------------------------------- -0.001 dtM - time step to use in mooring integration (s) -3.0e6 kbot - bottom stiffness (Pa/m) -3.0e5 cbot - bottom damping (Pa-s/m) -2.0 dtIC - time interval for analyzing convergence during IC gen (s) -60.0 TmaxIC - max time for ic gen (s) -4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) -0.01 threshIC - threshold for IC convergence (-) -200.0 WtrDpth option set by the driver -1025.0 rho option set by the driver -9.80665 gravity option set by the driver ------------------------- OUTPUTS -------------------------------------------- -FairTen1 -FairTen2 -FairTen3 -AnchTen1 -AnchTen2 -AnchTen3 -L1N10T -L2N10T -L3N10T -P4Fx -P4Fy -P4Fz -P5Fx -P5Fy -P5Fz -P6Fx -P6Fy -P6Fz -L1N19Px -L1N19Py -L1N19Pz -L2N19Px -L2N19Py -L2N19Pz -L3N19Px -L3N19Py -L3N19Pz -P4Px -P4Py -P4Pz -P5Px -P5Py -P5Pz -P6Px -P6Py -P6Pz -END -------------------------- need this line -------------------------------------- diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml index 348ae33a..68cd38ed 100644 --- a/.github/workflows/mdf_verification.yml +++ b/.github/workflows/mdf_verification.yml @@ -70,3 +70,6 @@ jobs: - name: Set env variables for the tests run: | echo "LD_LIBRARY_PATH=${{github.workspace}}/build/source/" >> $GITHUB_ENV + + - name: Run the tests + run: python ${{github.workspace}}/tests/.mdf_verification/verify.py ${{github.workspace}}/ diff --git a/.github/rsc/verify.py b/tests/.mdf_verification/verify.py similarity index 83% rename from .github/rsc/verify.py rename to tests/.mdf_verification/verify.py index 86fc5bd9..c88e21ed 100644 --- a/.github/rsc/verify.py +++ b/tests/.mdf_verification/verify.py @@ -1,3 +1,37 @@ +############################################################################### +# Copyright (c) 2022 Jose Luis Cercos-Pita +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# 3. Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +############################################################################### + +# This tests are meant to be ran by GitHub actions to compare with the MoorDynF +# implementation, allocated on the OpenFAST repository. +# See .github/workflows/mdf_verification.yml + import argparse import os import sys From 1c4a758ef3449a42f7aeed20f7f8c534f43137a3 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 13:59:13 +0200 Subject: [PATCH 023/145] The summary was wrong --- tests/.mdf_verification/verify.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index c88e21ed..d2ce213d 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -316,7 +316,9 @@ def plot(ref, data, fpath): if np.any(summary.values()): print("") print("=" * 80) - print(f"{np.sum(list(summary.values()))} / {len(summary.values())} failed:") + N = len(summary.values()) + n = N - np.sum(list(summary.values())) + print(f"{n} / {N} failed:") for i, (key, value) in enumerate(summary.items()): print(f"\t{i + 1}: Test '{key}' " + ("PASSED" if value else "FAILED")) print("=" * 80) From 6988737ad5c2fa72789100cefb821996a944a526 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 14:00:45 +0200 Subject: [PATCH 024/145] Drop the automatic trigger on mdf branch --- .github/workflows/mdf_verification.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/mdf_verification.yml b/.github/workflows/mdf_verification.yml index 68cd38ed..a3c38126 100644 --- a/.github/workflows/mdf_verification.yml +++ b/.github/workflows/mdf_verification.yml @@ -2,7 +2,7 @@ name: MoorDynF regression tests on: push: - branches: [ $default-branch, master, mdf ] + branches: [ $default-branch, master ] pull_request: branches: - "**" From 8b860b8ab3857e974f5c75dde02720dee349a682 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 14:06:58 +0200 Subject: [PATCH 025/145] Slightly improved summary --- tests/.mdf_verification/verify.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index d2ce213d..25dd4fb0 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -313,13 +313,15 @@ def plot(ref, data, fpath): summary[test] = passing +print("") +print("=" * 80) +N = len(summary.values()) if np.any(summary.values()): - print("") - print("=" * 80) - N = len(summary.values()) n = N - np.sum(list(summary.values())) - print(f"{n} / {N} failed:") + print(f"{n} / {N} tests failed:") for i, (key, value) in enumerate(summary.items()): print(f"\t{i + 1}: Test '{key}' " + ("PASSED" if value else "FAILED")) - print("=" * 80) - print("") +else: + print(f"{N} / {N} tests passed:") +print("=" * 80) +print("") From 8a85443ddacba9f23657e6737f3b931208f7f08f Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 20 Jun 2024 14:15:06 +0200 Subject: [PATCH 026/145] Send an error to github CI/CD if something fails --- tests/.mdf_verification/verify.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index 25dd4fb0..dc060c8b 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -316,7 +316,7 @@ def plot(ref, data, fpath): print("") print("=" * 80) N = len(summary.values()) -if np.any(summary.values()): +if not np.all(summary.values()): n = N - np.sum(list(summary.values())) print(f"{n} / {N} tests failed:") for i, (key, value) in enumerate(summary.items()): @@ -325,3 +325,5 @@ def plot(ref, data, fpath): print(f"{N} / {N} tests passed:") print("=" * 80) print("") + +assert np.all(summary.values()) From b05dde63e1ea15ec9519f965a7201ac6c91f6cf7 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 24 Jun 2024 06:16:37 +0200 Subject: [PATCH 027/145] Check for MDF '***' outputs --- tests/.mdf_verification/verify.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index dc060c8b..76cd7bb0 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -248,6 +248,11 @@ def get_state(system): def read_outs(fpath, skiplines=2): + def to_num(s): + if '***' in s: + return 0.0 + return float(s) + data = [] with open(fpath, "r") as fin: lines = fin.readlines()[skiplines:] @@ -255,7 +260,7 @@ def read_outs(fpath, skiplines=2): line = line.strip().replace("\t", " ") while line.find(" ") != -1: line = line.replace(" ", " ") - data.append([float(field) for field in line.split()]) + data.append([to_num(field) for field in line.split()]) return np.transpose(data) From 7b2082372ca01e96a6a475a1e73ea72ef722fc3e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 24 Jun 2024 06:46:52 +0200 Subject: [PATCH 028/145] dict_values would be wrongly checked by np.all --- tests/.mdf_verification/verify.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index 76cd7bb0..545804f3 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -320,9 +320,10 @@ def plot(ref, data, fpath): print("") print("=" * 80) -N = len(summary.values()) -if not np.all(summary.values()): - n = N - np.sum(list(summary.values())) +values = list(summary.values()) +N = len(values) +if not np.all(values): + n = N - np.sum(list(values)) print(f"{n} / {N} tests failed:") for i, (key, value) in enumerate(summary.items()): print(f"\t{i + 1}: Test '{key}' " + ("PASSED" if value else "FAILED")) From d1d83beb77423e184a7ff5fc9e4ae17ae91d0794 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 24 Jun 2024 06:50:37 +0200 Subject: [PATCH 029/145] I forgot the assert --- tests/.mdf_verification/verify.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index 545804f3..05844549 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -332,4 +332,4 @@ def plot(ref, data, fpath): print("=" * 80) print("") -assert np.all(summary.values()) +assert np.all(values) From dfb322773d57bd94c6a5e98ec652b52ca5629f9c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 25 Jun 2024 06:35:32 +0200 Subject: [PATCH 030/145] Drop OpenGL functions --- compile/DLL/makefile | 6 ---- compile/DYLIB/makefile | 6 ---- compile/SO/makefile | 6 ---- source/Body.cpp | 10 ------ source/Body.hpp | 4 --- source/Line.cpp | 79 ------------------------------------------ source/Line.hpp | 5 --- source/Misc.hpp | 5 --- source/MoorDyn.cpp | 8 ----- source/MoorDyn.h | 2 -- source/MoorDyn2.cpp | 16 --------- source/MoorDyn2.h | 10 ------ source/Point.cpp | 10 ------ source/Point.hpp | 4 --- source/Rod.cpp | 71 ------------------------------------- source/Rod.hpp | 5 --- tests/c_api.c | 10 ------ 17 files changed, 257 deletions(-) diff --git a/compile/DLL/makefile b/compile/DLL/makefile index ba9dc9ed..70d9fdab 100644 --- a/compile/DLL/makefile +++ b/compile/DLL/makefile @@ -3,7 +3,6 @@ # # Several options can be set: # -# - USEGL: Enables the OpenGL visualization # - COPTS: Compilation options. For good performance and compatibility use: # COPTS='-msse2 -ffast-math -DMOORDYN_SINGLEPRECISSION' # However, for local-only installations a more aggresive instructions @@ -24,11 +23,6 @@ LFLAGS = -shared -static-libgcc -static-libstdc++ -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -g -Wall -Wextra -DMoorDyn_EXPORTS -fPIC -I../../source/ -ifdef USEGL -CFLAGS += -DUSEGL -LFLAGS += -lopengl32 -lglu32 -endif - CFLAGS += $(COPTS) LFLAGS += $(LOPTS) diff --git a/compile/DYLIB/makefile b/compile/DYLIB/makefile index 9634c9bd..da4df230 100644 --- a/compile/DYLIB/makefile +++ b/compile/DYLIB/makefile @@ -3,7 +3,6 @@ # # Several options can be set: # -# - USEGL: Enables the OpenGL visualization # - COPTS: Compilation options. For good performance and compatibility use: # COPTS='-msse2 -ffast-math -DMOORDYN_SINGLEPRECISSION' # However, for local-only installations a more aggresive instructions @@ -29,11 +28,6 @@ LFLAGS = -shared -DOSX -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -static -g -Wall -Wextra -DOSX -DMoorDyn_EXPORTS -fPIC -I../../source/ -ifdef USEGL -CFLAGS += -DUSEGL -LFLAGS += -lopengl32 -lglu32 -endif - CFLAGS += $(COPTS) LFLAGS += $(LOPTS) diff --git a/compile/SO/makefile b/compile/SO/makefile index 68329ad9..d10d0c64 100644 --- a/compile/SO/makefile +++ b/compile/SO/makefile @@ -3,7 +3,6 @@ # # Several options can be set: # -# - USEGL: Enables the OpenGL visualization # - COPTS: Compilation options. For good performance and compatibility use: # COPTS='-msse2 -ffast-math -DMOORDYN_SINGLEPRECISSION' # However, for local-only installations a more aggresive instructions @@ -25,11 +24,6 @@ LFLAGS = -shared -static-libgcc -static-libstdc++ -DLINUX -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -g -Wall -Wextra -DLINUX -DMoorDyn_EXPORTS -fPIC -I../../source/ -ifdef USEGL -CFLAGS += -DUSEGL -LFLAGS += -lopengl32 -lglu32 -endif - CFLAGS += $(COPTS) LFLAGS += $(LOPTS) diff --git a/source/Body.cpp b/source/Body.cpp index 1f17c27f..43cb0879 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -770,16 +770,6 @@ Body::defaultVTK() } #endif -// new function to draw instantaneous line positions in openGL context -#ifdef USEGL -void -Body::drawGL(void) -{ - double radius = pow(BodyV / (4 / 3 * pi), 0.33333); // pointV - Sphere(r[0], r[1], r[2], radius); -}; -#endif - } // ::moordyn // ============================================================================= diff --git a/source/Body.hpp b/source/Body.hpp index d7c5e3a0..9926ff9a 100644 --- a/source/Body.hpp +++ b/source/Body.hpp @@ -439,10 +439,6 @@ class Body final : public io::IO void saveVTK(const char* filename) const; #endif -#ifdef USEGL - void drawGL(void); -#endif - private: #ifdef USE_VTK /// The 3D object that represents the body diff --git a/source/Line.cpp b/source/Line.cpp index 931f0855..7e57793e 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1537,85 +1537,6 @@ Line::saveVTK(const char* filename) const } #endif -// new function to draw instantaneous line positions in openGL context -#ifdef USEGL -void -Line::drawGL(void) -{ - double maxTen = 0.0; - double normTen; - double rgb[3]; - for (int i = 0; i <= N; i++) { - const double newTen = ((i == 0) || (i == N)) ? - getNodeForce(i).norm() : - getNodeTen(i).norm(); - if (newTen > maxTen) - maxTen = newTen; - } - - glColor3f(0.5, 0.5, 1.0); - glBegin(GL_LINE_STRIP); - for (int i = 0; i <= N; i++) { - glVertex3d(r[i][0], r[i][1], r[i][2]); - if (i < N) { - const double normTen = (((i == 0) || (i == N)) ? - getNodeForce(i).norm() : - getNodeTen(i).norm()) / maxTen; - ColorMap(normTen, rgb); - glColor3d(rgb[0], rgb[1], rgb[2]); - } - } - glEnd(); -}; - -void -Line::drawGL2(void) -{ - double maxTen = 0.0; - double normTen; - double rgb[3]; - for (int i = 0; i <= N; i++) { - const double newTen = ((i == 0) || (i == N)) ? - getNodeForce(i).norm() : - (0.5 * (T[i] + T[i - 1])).norm(); - if (newTen > maxTen) - maxTen = newTen; - } - - // line - for (unsigned int i = 0; i < N; i++) { - const double normTen = 0.2 + 0.8 * pow((((i == 0) || (i == N)) ? - getNodeForce(i).norm() : - getNodeTen(i).norm()) / maxTen, 4.0); - ColorMap(normTen, rgb); - glColor3d(rgb[0], rgb[1], rgb[2]); - - Cylinder(r[i][0], - r[i][1], - r[i][2], - r[i + 1][0], - r[i + 1][1], - r[i + 1][2], - 27, - 0.5); - } - // velocity vectors - for (int i = 0; i <= N; i++) { - glColor3d(0.0, 0.2, 0.8); - double vscal = 5.0; - - Arrow(r[i][0], - r[i][1], - r[i][2], - vscal * rd[i][0], - vscal * rd[i][1], - vscal * rd[i][2], - 0.1, - 0.7); - } -}; -#endif - } // ::moordyn // ============================================================================= diff --git a/source/Line.hpp b/source/Line.hpp index 016b88fc..770a97d6 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -905,11 +905,6 @@ class Line final : public io::IO */ void saveVTK(const char* filename) const; #endif - -#ifdef USEGL - void drawGL(void); - void drawGL2(void); -#endif }; } // ::moordyn diff --git a/source/Misc.hpp b/source/Misc.hpp index 759c77a4..3912ad1c 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -49,11 +49,6 @@ #include #include -// #ifdef USEGL -// #include // for openGL drawing option -// #include // used in arrow function -// #endif - #ifdef OSX #include #elif defined WIN32 diff --git a/source/MoorDyn.cpp b/source/MoorDyn.cpp index 0aeba708..224c7610 100644 --- a/source/MoorDyn.cpp +++ b/source/MoorDyn.cpp @@ -281,11 +281,3 @@ GetNodePos(int LineNum, int NodeNum, double pos[3]) auto line = MoorDyn_GetLine(md_singleton, LineNum); return MoorDyn_GetLineNodePos(line, NodeNum, pos); } - -int DECLDIR -DrawWithGL() -{ - if (!md_singleton) - return MOORDYN_MEM_ERROR; - return MoorDyn_DrawWithGL(md_singleton); -} diff --git a/source/MoorDyn.h b/source/MoorDyn.h index ccf0b0e9..02f96c26 100644 --- a/source/MoorDyn.h +++ b/source/MoorDyn.h @@ -142,8 +142,6 @@ extern "C" int DECLDIR GetPointForce(int l, double force[3]); int DECLDIR GetNodePos(int LineNum, int NodeNum, double pos[3]); - int DECLDIR DrawWithGL(void); - int AllOutput(double, double); /** diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 8e82c3b1..61339699 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -2593,22 +2593,6 @@ MoorDyn_Load(MoorDyn system, const char* filepath) return err; } -int DECLDIR -MoorDyn_DrawWithGL(MoorDyn system) -{ - CHECK_SYSTEM(system); - -#ifdef USEGL - // draw the mooring system with OpenGL commands (assuming a GL context has - // been created by the calling program) - for (auto line : ((moordyn::MoorDyn*)system)->GetLines()) - line->drawGL2(); - for (auto point : ((moordyn::MoorDyn*)system)->GetPoints()) - point->drawGL(); -#endif - return MOORDYN_SUCCESS; -} - int DECLDIR MoorDyn_SaveVTK(MoorDyn system, const char* filename) { diff --git a/source/MoorDyn2.h b/source/MoorDyn2.h index a46109ff..c51deaaa 100644 --- a/source/MoorDyn2.h +++ b/source/MoorDyn2.h @@ -470,16 +470,6 @@ extern "C" */ int DECLDIR MoorDyn_Load(MoorDyn system, const char* filepath); - /** @brief Draw the lines and points in the active OpenGL context - * - * The OpenGL context is assumed to be created by the caller before calling - * this function - * @param system The Moordyn system - * @return MOORDYN_SUCESS If the data is correctly set, an error code - * otherwise (see @ref moordyn_errors) - */ - int DECLDIR MoorDyn_DrawWithGL(MoorDyn system); - /** @brief Save the whole system to a VTK (.vtm) file * * In general it is more convenient to handle each object independently, diff --git a/source/Point.cpp b/source/Point.cpp index 62eb26f3..4e97064b 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -471,16 +471,6 @@ Point::saveVTK(const char* filename) const } #endif -// new function to draw instantaneous line positions in openGL context -#ifdef USEGL -void -Point::drawGL(void) -{ - double radius = pow(pointV / (4 / 3 * pi), 0.33333); // pointV - Sphere(r[0], r[1], r[2], radius); -}; -#endif - } // ::moordyn // ============================================================================= diff --git a/source/Point.hpp b/source/Point.hpp index 8882d872..fb7ff43b 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -418,10 +418,6 @@ class Point final : public io::IO */ void saveVTK(const char* filename) const; #endif - -#ifdef USEGL - void drawGL(void); -#endif }; } // ::moordyn diff --git a/source/Rod.cpp b/source/Rod.cpp index 2cafc7b6..6ea1724c 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -1571,77 +1571,6 @@ Rod::saveVTK(const char* filename) const } #endif -// new function to draw instantaneous line positions in openGL context -#ifdef USEGL -void -Rod::drawGL(void) -{ - double maxTen = 0.0; - double normTen; - double rgb[3]; - for (int i = 0; i <= N; i++) { - double newTen = getNodeTen(i); - if (newTen > maxTen) - maxTen = newTen; - } - - glColor3f(0.5, 0.5, 1.0); - glBegin(GL_LINE_STRIP); - for (int i = 0; i <= N; i++) { - glVertex3d(r[i][0], r[i][1], r[i][2]); - if (i < N) { - normTen = getNodeTen(i) / maxTen; - ColorMap(normTen, rgb); - glColor3d(rgb[0], rgb[1], rgb[2]); - } - } - glEnd(); -}; - -void -Rod::drawGL2(void) -{ - double maxTen = 0.0; - double normTen; - double rgb[3]; - for (int i = 0; i <= N; i++) { - double newTen = getNodeTen(i); - if (newTen > maxTen) - maxTen = newTen; - } - - // line - for (int i = 0; i < N; i++) { - normTen = 0.2 + 0.8 * pow(getNodeTen(i) / maxTen, 4.0); - ColorMap(normTen, rgb); - glColor3d(rgb[0], rgb[1], rgb[2]); - - Cylinder(r[i][0], - r[i][1], - r[i][2], - r[i + 1][0], - r[i + 1][1], - r[i + 1][2], - 27, - 0.5); - } - // velocity vectors - for (int i = 0; i <= N; i++) { - glColor3d(0.0, 0.2, 0.8); - double vscal = 5.0; - - Arrow(r[i][0], - r[i][1], - r[i][2], - vscal * rd[i][0], - vscal * rd[i][1], - vscal * rd[i][2], - 0.1, - 0.7); - } -}; -#endif - } // ::moordyn // ============================================================================= diff --git a/source/Rod.hpp b/source/Rod.hpp index 683e6812..af2c277a 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -579,11 +579,6 @@ class Rod final : public io::IO */ void saveVTK(const char* filename) const; #endif - -#ifdef USEGL - void drawGL(void); - void drawGL2(void); -#endif }; } // ::moordyn diff --git a/tests/c_api.c b/tests/c_api.c index c55e4597..1122b3f3 100644 --- a/tests/c_api.c +++ b/tests/c_api.c @@ -88,11 +88,6 @@ main(int narg, char** arg) printf("GetNodePos() test failed..."); return 255; } - ret_code = DrawWithGL(); - if (ret_code != MOORDYN_MEM_ERROR) { - printf("DrawWithGL() test failed..."); - return 255; - } // MoorDyn2.h MoorDyn system = MoorDyn_Create("nofile"); @@ -250,11 +245,6 @@ main(int narg, char** arg) printf("MoorDyn_Load() test failed..."); return 255; } - ret_code = MoorDyn_DrawWithGL(NULL); - if (ret_code != MOORDYN_INVALID_VALUE) { - printf("MoorDyn_DrawWithGL() test failed..."); - return 255; - } ret_code = MoorDyn_SaveVTK(NULL, "nofile"); if (ret_code != MOORDYN_INVALID_VALUE && ret_code != MOORDYN_NON_IMPLEMENTED) { printf("MoorDyn_SaveVTK() test failed..."); From 7d411cf91cfc46f52fc66d05634f260a41b8b7ec Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 25 Jun 2024 06:39:53 +0200 Subject: [PATCH 031/145] Removed a trace (unused) of OpenGL on Rust --- wrappers/rust/bindings.rs | 4 ---- 1 file changed, 4 deletions(-) diff --git a/wrappers/rust/bindings.rs b/wrappers/rust/bindings.rs index 57344470..f26e181e 100644 --- a/wrappers/rust/bindings.rs +++ b/wrappers/rust/bindings.rs @@ -399,7 +399,3 @@ extern "C" { filepath: *const ::std::os::raw::c_char, ) -> ::std::os::raw::c_int; } -extern "C" { - #[doc = " @brief Draw the lines and points in the active OpenGL context\n\n The OpenGL context is assumed to be created by the caller before calling\n this function\n @param system The Moordyn system\n @return MOORDYN_SUCESS If the data is correctly set, an error code\n otherwise (see @ref moordyn_errors)"] - pub fn MoorDyn_DrawWithGL(system: MoorDyn) -> ::std::os::raw::c_int; -} From 71cec5695267474e0c01348de81b2ba4e9b1d760 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 22 Dec 2023 14:47:21 +0100 Subject: [PATCH 032/145] Added CFL base class --- source/CMakeLists.txt | 3 +- source/Util/CFL.hpp | 144 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 146 insertions(+), 1 deletion(-) create mode 100644 source/Util/CFL.hpp diff --git a/source/CMakeLists.txt b/source/CMakeLists.txt index 94d675f8..248a6cbe 100644 --- a/source/CMakeLists.txt +++ b/source/CMakeLists.txt @@ -18,7 +18,7 @@ set(MOORDYN_SRCS Waves/SpectrumKin.cpp Waves/WaveOptions.cpp Waves/WaveGrid.cpp - ) +) set(MOORDYN_HEADERS Body.hpp @@ -48,6 +48,7 @@ set(MOORDYN_HEADERS Waves/WaveOptions.hpp Waves/WaveGrid.hpp Util/Interp.hpp + Util/CFL.hpp ) set(MOORDYN_PUBLIC_DEPS "") diff --git a/source/Util/CFL.hpp b/source/Util/CFL.hpp new file mode 100644 index 00000000..aba664d2 --- /dev/null +++ b/source/Util/CFL.hpp @@ -0,0 +1,144 @@ +/* + * Copyright (c) 2023, Jose Luis Cercos-Pita & Matt Hall + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file CFL.hpp + * Courant–Friedrichs–Lewy condition base classes + */ + +#pragma once + +#include "Misc.hpp" +#include +#include + +using namespace std; + +namespace moordyn { + +/** @class CFL CFL.hpp + * @brief CFL object base class + * + * The base class does nothing but offering a tool which no matters the + * timestep returns a 0 CFL factor, and no matters the CFL returns an infinite + * timestep. + * + * Thus can be used for entitites which does not impose any kind of limitation + * on the timestep + */ +class CFL +{ + public: + /** @brief Constructor + */ + CFL(); + + /** @brief Destructor + */ + ~CFL(); + + /** @brief Get the timestep from a CFL factor + * @param cfl CFL factor + * @return The timestep + */ + virtual inline real cfl2dt(const real cfl) const { return std::numeric_limits::max(); } + + /** @brief Get the CFL factor from a timestep + * @param dt Timestep + * @return CFL factor + */ + virtual inline real dt2cfl(const real dt) const { return 0.0; } +}; + +/** @class NatFreqCFL CFL.hpp + * @brief CFL for objects based on a natural frequency + */ +class NatFreqCFL +{ + public: + /** @brief Constructor + */ + NatFreqCFL(); + + /** @brief Destructor + */ + ~NatFreqCFL(); + + /** @brief Get the timestep from a CFL factor + * @param cfl CFL factor + * @return The timestep + */ + virtual inline real cfl2dt(const real cfl) const { return cfl * period(); } + + /** @brief Get the CFL factor from a timestep + * @param dt Timestep + * @return CFL factor + */ + virtual inline real dt2cfl(const real dt) const { return dt / period(); } + + protected: + /** @brief Set the stiffness of the system + * @param k stiffness + */ + inline void stiffness(real k) { _k = k; } + + /** @brief Get the stiffness of the system + * @return stiffness + */ + inline real stiffness() const { return _k; } + + /** @brief Set the mass of the system + * @param m mass + */ + inline void mass(real m) { _m = m; } + + /** @brief Get the mass of the system + * @return mass + */ + inline real mass() const { return _m; } + + /** @brief Get the natural frequency of the system + * @return natural angular frequency + */ + inline real frequency() const { return sqrt(_k / _m); } + + /** @brief Get the natural period of the system + * @return natural period + */ + inline real period() const { return 2.0 * pi / frequency(); } + + private: + /// Stiffness + real _k; + + /// mass + real _m; +}; + +} // ::moordyn From fad5f96b6c6033e7b50d4d18f7a584d8e50d7f0d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 22 Dec 2023 14:57:43 +0100 Subject: [PATCH 033/145] Added a CFL to the lines --- source/Line.cpp | 5 +++++ source/Line.hpp | 3 ++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/source/Line.cpp b/source/Line.cpp index 7e57793e..11ff3e8c 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -160,6 +160,11 @@ Line::setup(int number_in, stiffYs.push_back(props->stiffYs[I] / A); } + // Use the last entry on the lookup table. see Line::initialize() + const real EA = nEApoints ? stiffYs.back() / stiffXs.back() * A : props->EA; + NatFreqCFL::stiffness(EA * N / UnstrLen); + NatFreqCFL::mass(props->w * UnstrLen / N); + // copy in nonlinear bent stiffness data if applicable bstiffXs.clear(); bstiffYs.clear(); diff --git a/source/Line.hpp b/source/Line.hpp index 770a97d6..519725db 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -37,6 +37,7 @@ #include "Misc.hpp" #include "IO.hpp" #include "Seafloor.hpp" +#include "Util/CFL.hpp" #include #ifdef USE_VTK @@ -68,7 +69,7 @@ typedef std::shared_ptr WavesRef; * The integration time step (moordyn::MoorDyn.dtM0) should be smaller than * this natural period to avoid numerical instabilities */ -class Line final : public io::IO +class Line final : public io::IO, public NatFreqCFL { public: /** @brief Constructor From 4e33a7a6c0f6b31f8613f81677d80c01f4080804 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 22 Dec 2023 15:31:57 +0100 Subject: [PATCH 034/145] Added a CFL option to atumatically set the timestep according to the natural period --- docs/inputs.rst | 10 ++++++++-- source/Body.hpp | 3 ++- source/MoorDyn2.cpp | 26 +++++++++++++++++++++++++- source/MoorDyn2.hpp | 4 +++- source/Point.hpp | 3 ++- source/Rod.hpp | 3 ++- source/Util/CFL.hpp | 10 +++++----- 7 files changed, 47 insertions(+), 12 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 6600bd74..c3038297 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -152,7 +152,7 @@ including seabed properties, initial condition (IC) generation settings, and the .. code-block:: none -------------------------- SOLVER OPTIONS--------------------------------------------------- - 0.001 dtM - time step to use in mooring integration + 0.001 dtM - time step to use in mooring integration 3.0e6 kb - bottom stiffness 3.0e5 cb - bottom damping 70 WtrDpth - water depth @@ -165,7 +165,8 @@ parenthesis). As such, they are all optional settings, although some of them (su 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) + - dtM (3.402823e+38) – desired mooring model maximum time step (s) + - CFL (0.5) – desired mooring model maximum CFL factor - g (9.80665) – gravitational constant (m/s^2) - rhoW (1025.0)– water density (kg/m^3) - WtrDpth (0.0) – water depth (m) @@ -179,6 +180,11 @@ default value provided in parentheses) is: - ThreshIC (0.001) – convergence threshold for IC generation, acceptable relative difference between three successive fairlead tension measurements (-) +The internal time step is first taken from the dtM option, and then adjusted +according to the CFL factor, which is the ratio between the timestep and the +natural period, computed considering the math described on +:ref:`the troubleshooting section `. + 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. diff --git a/source/Body.hpp b/source/Body.hpp index 9926ff9a..07463031 100644 --- a/source/Body.hpp +++ b/source/Body.hpp @@ -41,6 +41,7 @@ #include "Misc.hpp" #include "IO.hpp" +#include "Util/CFL.hpp" #include #include @@ -72,7 +73,7 @@ class Rod; * moordyn::Body extends the io::IO class, allowing it to perform input/output * in a consistent manner. */ -class Body final : public io::IO +class Body final : public io::IO, public CFL { public: /** @brief Costructor diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 61339699..40f24240 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -87,7 +87,8 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) , ICTmax(120.0) , ICthresh(0.001) , WaveKinTemp(waves::WAVES_NONE) - , dtM0(0.001) + , dtM0(std::numeric_limits::max()) + , cfl(0.5) , dtOut(0.0) , _t_integrator(NULL) , env(std::make_shared()) @@ -302,6 +303,27 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) ix += 3; } + // Compute the timestep + for (auto obj : LineList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : PointList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : RodList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : BodyList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + // And get the resulting CFL + cfl = 0.0; + for (auto obj : LineList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : PointList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : RodList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : BodyList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + LOGMSG << "dtM = " << dtM0 << " s (CFL = " << cfl << ")" << endl; + // Initialize the system state _t_integrator->init(); @@ -1998,6 +2020,8 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) // DT is old way, should phase out if ((name == "dtM") || (name == "DT")) dtM0 = atof(entries[0].c_str()); + else if ((name == "CFL") || (name == "cfl")) + cfl = atof(entries[0].c_str()); else if (name == "writeLog") { // This was actually already did, so we do not need to do that again // But we really want to have this if to avoid showing a warning for diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index ff4f249c..90431205 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -435,8 +435,10 @@ class MoorDyn final : public io::IO // temporary wave kinematics flag used to store input value while keeping // env.WaveKin=0 for IC gen moordyn::waves::waves_settings WaveKinTemp; - /// (s) desired mooring line model time step + /// (s) desired mooring line model maximum time step real dtM0; + /// desired mooring line model maximum CFL factor + real cfl; /// (s) desired output interval (the default zero value provides output at /// every call to MoorDyn) real dtOut; diff --git a/source/Point.hpp b/source/Point.hpp index fb7ff43b..0e131a67 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -37,6 +37,7 @@ #include "Misc.hpp" #include "IO.hpp" #include "Seafloor.hpp" +#include "Util/CFL.hpp" #include #ifdef USE_VTK @@ -66,7 +67,7 @@ typedef std::shared_ptr WavesRef; * weight or float via the point's mass and volume parameters * - Coupled: The point position and velocity is externally imposed */ -class Point final : public io::IO +class Point final : public io::IO, public CFL { public: /** @brief Costructor diff --git a/source/Rod.hpp b/source/Rod.hpp index af2c277a..1a800d32 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -37,6 +37,7 @@ #include "Misc.hpp" #include "IO.hpp" #include "Seafloor.hpp" +#include "Util/CFL.hpp" #include #include @@ -62,7 +63,7 @@ class Line; * Each end point of the rod can be fixed or pinned to another object, let free * or control it externally */ -class Rod final : public io::IO +class Rod final : public io::IO, public CFL { public: /** @brief Costructor diff --git a/source/Util/CFL.hpp b/source/Util/CFL.hpp index aba664d2..a4f9e4c6 100644 --- a/source/Util/CFL.hpp +++ b/source/Util/CFL.hpp @@ -57,11 +57,11 @@ class CFL public: /** @brief Constructor */ - CFL(); + CFL() {}; /** @brief Destructor */ - ~CFL(); + virtual ~CFL() {}; /** @brief Get the timestep from a CFL factor * @param cfl CFL factor @@ -84,15 +84,15 @@ class NatFreqCFL public: /** @brief Constructor */ - NatFreqCFL(); + NatFreqCFL() {}; /** @brief Destructor */ - ~NatFreqCFL(); + virtual ~NatFreqCFL() {}; /** @brief Get the timestep from a CFL factor * @param cfl CFL factor - * @return The timestep + * @return The timestUtilep */ virtual inline real cfl2dt(const real cfl) const { return cfl * period(); } From 646672a0bb1c951bed49b181d12a81162d7881a8 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 30 Dec 2023 19:25:34 +0100 Subject: [PATCH 035/145] This is not anymore a problem --- source/QSlines.hpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/source/QSlines.hpp b/source/QSlines.hpp index 783f6604..f7946506 100644 --- a/source/QSlines.hpp +++ b/source/QSlines.hpp @@ -593,12 +593,5 @@ Catenary(T XF, ZF = -ZF; } - // It might happen that the output solution does not respect the - // queried final point. See the pendulum example - if (abs(Z[Nnodes-1] - ZF) > Tol) { - if (longwinded == 1) - cout << "Fairlead and anchor vertical seperation has changed" - << ", aborting catenary solver ..." << endl; - return -1; - } else return 1; + return 1; } From d3952e6b36fe8bc654da0c0b1ff54c356b6d1a1c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 30 Dec 2023 19:28:12 +0100 Subject: [PATCH 036/145] Stationary solution for initializations (and WIP Local-Euler) --- source/Body.cpp | 2 + source/Body.hpp | 2 +- source/Line.cpp | 3 +- source/Misc.hpp | 2 + source/MoorDyn2.cpp | 112 ++++++---------- source/Point.cpp | 2 + source/Point.hpp | 2 +- source/Rod.cpp | 2 + source/Rod.hpp | 2 +- source/State.cpp | 102 +++++++++++++++ source/State.hpp | 55 ++++++++ source/Time.cpp | 176 ++++++++++++++++++++++++++ source/Time.hpp | 168 +++++++++++++++++++++++- source/Util/CFL.hpp | 134 +++++++++++++++++++- tests/Mooring/BeamCantilevered.txt | 11 +- tests/Mooring/BeamSimplySupported.txt | 9 +- tests/Mooring/RodHanging.txt | 5 +- tests/Mooring/WD0050_Chain.txt | 9 +- tests/Mooring/WD0200_Chain.txt | 11 +- tests/Mooring/WD0600_Chain.txt | 9 +- tests/Mooring/pendulum.txt | 9 +- tests/Mooring/rod_tests/AddedMass.txt | 7 +- tests/quasi_static_chain.cpp | 4 + 23 files changed, 711 insertions(+), 127 deletions(-) diff --git a/source/Body.cpp b/source/Body.cpp index 43cb0879..a7019532 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -140,6 +140,7 @@ Body::addPoint(moordyn::Point* point, vec coords) // store Point address attachedP.push_back(point); + SuperCFL::AddChild(point); // store Point relative location rPointRel.push_back(coords); @@ -152,6 +153,7 @@ Body::addRod(Rod* rod, vec6 coords) // store Rod address attachedR.push_back(rod); + SuperCFL::AddChild(rod); // store Rod end A relative position and unit vector from end A to B vec tempUnitVec; diff --git a/source/Body.hpp b/source/Body.hpp index 07463031..d123f1de 100644 --- a/source/Body.hpp +++ b/source/Body.hpp @@ -73,7 +73,7 @@ class Rod; * moordyn::Body extends the io::IO class, allowing it to perform input/output * in a consistent manner. */ -class Body final : public io::IO, public CFL +class Body final : public io::IO, public SuperCFL { public: /** @brief Costructor diff --git a/source/Line.cpp b/source/Line.cpp index 11ff3e8c..23cc40b2 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -162,6 +162,7 @@ Line::setup(int number_in, // Use the last entry on the lookup table. see Line::initialize() const real EA = nEApoints ? stiffYs.back() / stiffXs.back() * A : props->EA; + NatFreqCFL::length(UnstrLen / N); NatFreqCFL::stiffness(EA * N / UnstrLen); NatFreqCFL::mass(props->w * UnstrLen / N); @@ -467,7 +468,7 @@ Line::initialize() real ZF = dir[2]; real LW = ((rho - env->rho_w) * A) * env->g; real CB = 0.; - real Tol = 0.00001; + real Tol = 1e-5; // locations of line nodes along line length - evenly distributed // here diff --git a/source/Misc.hpp b/source/Misc.hpp index 3912ad1c..44c46a46 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -730,7 +730,9 @@ namespace fileIO { */ std::vector fileToLines(const std::filesystem::path& path); + } + /** * @} */ diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 40f24240..fe3d52ea 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -193,14 +193,6 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // <<<<<<<<< need to add bodys - // Allocate past line fairlead tension array, which is used for convergence - // test during IC gen - const unsigned int convergence_iters = 9; // 10 iterations, indexed 0-9 - vector FairTensLast_col(convergence_iters, 0.0); - for (unsigned int i = 0; i < convergence_iters; i++) - FairTensLast_col[i] = 1.0 * i; - vector> FairTensLast(LineList.size(), FairTensLast_col); - // ------------------ do static bodies and lines --------------------------- LOGMSG << "Creating mooring system..." << endl; @@ -325,7 +317,8 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) LOGMSG << "dtM = " << dtM0 << " s (CFL = " << cfl << ")" << endl; // Initialize the system state - _t_integrator->init(); + _t_integrator->SetCFL(cfl); + _t_integrator->Init(); // ------------------ do dynamic relaxation IC gen -------------------- @@ -347,34 +340,45 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // vector to store tensions for analyzing convergence vector FairTens(LineList.size(), 0.0); - unsigned int iic = 1; // To match MDF indexing real t = 0; - bool converged = true; - real max_error = 0.0; - unsigned int max_error_line = 0; + real error_prev = (std::numeric_limits::max)(); + real error0, error; // The function is enclosed in parenthesis to avoid Windows min() and max() // macros break it // See // https://stackoverflow.com/questions/1825904/error-c2589-on-stdnumeric-limitsdoublemin real best_score = (std::numeric_limits::max)(); real best_score_t = 0.0; - unsigned int best_score_line = 0; // //dtIC set to fraction of input so convergence is over dtIC - ICdt = ICdt / (convergence_iters+1); - while (((ICTmax-t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt + StationaryScheme t_integrator(_log, waves); + t_integrator.SetGround(GroundBody); + for (auto obj : BodyList) + t_integrator.AddBody(obj); + for (auto obj : RodList) + t_integrator.AddRod(obj); + for (auto obj : PointList) + t_integrator.AddPoint(obj); + for (auto obj : LineList) + t_integrator.AddLine(obj); + t_integrator.SetCFL(cfl); + t_integrator.Init(); + while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt // Integrate one ICD timestep (ICdt) real t_target = ICdt; real dt; - _t_integrator->Next(); + t_integrator.Next(); while ((dt = t_target) > 0.0) { if (dtM0 < dt) dt = dtM0; moordyn::error_id err = MOORDYN_SUCCESS; string err_msg; try { - _t_integrator->Step(dt); - t = _t_integrator->GetTime(); + t_integrator.Step(dt); + error = t_integrator.Error(); + if (!t) + error0 = error; + t = t_integrator.GetTime(); t_target -= dt; } MOORDYN_CATCHER(err, err_msg); @@ -384,72 +388,32 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } } - // Roll previous fairlead tensions for comparison - for (unsigned int lf = 0; lf < LineList.size(); lf++) { - for (int pt = convergence_iters - 1; pt > 0; pt--) - FairTensLast[lf][pt] = FairTensLast[lf][pt - 1]; - FairTensLast[lf][0] = FairTens[lf]; + if (error < best_score) { + best_score = error; + best_score_t = t; } - // go through points to get fairlead forces - for (unsigned int lf = 0; lf < LineList.size(); lf++) - FairTens[lf] = - LineList[lf]->getNodeTen(LineList[lf]->getN()).norm(); - - // check for convergence (compare current tension at each fairlead with - // previous convergence_iters-1 values) - if (iic > convergence_iters) { - // check for any non-convergence, and continue to the next time step - // if any occurs - converged = true; - max_error = 0.0; - for (unsigned int lf = 0; lf < LineList.size(); lf++) { - for (unsigned int pt = 0; pt < convergence_iters; pt++) { - const real error = - abs(FairTens[lf] / FairTensLast[lf][pt] - 1.0); - if (error > max_error) { - max_error = error; - max_error_line = LineList[lf]->number; - } - } - } - if (max_error < best_score) { - best_score = max_error; - best_score_t = t; - best_score_line = max_error_line; - } - if (max_error > ICthresh) { - converged = false; - LOGDBG << "Dynamic relaxation t = " << t << "s (time step " - << iic << "), error = " << 100.0 * max_error - << "% on line " << max_error_line << " \r"; - } - - if (converged) - break; - } + const real error_rel = error / error0; + const real error_deriv = std::abs(error_prev - error) / error_prev; + if (!error || (error_rel < ICthresh) || (error_deriv < ICthresh)) + break; + error_prev = error; - iic++; + LOGDBG << "Stationary solution t = " << t << "s, error change = " + << 100.0 * error_deriv << "% \r"; } if (!skip_ic) { - if (converged) { - LOGMSG << "Fairlead tensions converged" << endl; - } else { - LOGWRN << "Fairlead tensions did not converge" << endl; - } - LOGMSG << "Remaining error after " << t << " s = " << 100.0 * max_error - << "% on line " << max_error_line << endl; - if (!converged) { - LOGMSG << "Best score at " << best_score_t - << " s = " << 100.0 * best_score << "% on line " - << best_score_line << endl; - } + LOGMSG << "Remaining error after " << t << " s = " + << error << " m/s2" << endl; + LOGMSG << "Best score at " << best_score_t + << " s = " << best_score << " m/s2" << endl; } // restore drag coefficients to normal values and restart time counter of // each object _t_integrator->SetTime(0.0); + _t_integrator->FromStationary(t_integrator); for (auto obj : LineList) { obj->scaleDrag(1.0 / ICDfac); obj->setTime(0.0); diff --git a/source/Point.cpp b/source/Point.cpp index 4e97064b..aea793e2 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -107,6 +107,7 @@ Point::addLine(Line* theLine, EndPoints end_point) attachment a = { theLine, end_point }; attached.push_back(a); + SuperCFL::AddChild(theLine); }; EndPoints @@ -120,6 +121,7 @@ Point::removeLine(Line* line) // This is the line's entry in the attachment list end_point = it->end_point; attached.erase(it); + SuperCFL::RemoveChild(line); LOGMSG << "Detached line " << line->number << " from Point " << number << endl; diff --git a/source/Point.hpp b/source/Point.hpp index 0e131a67..466b5498 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -67,7 +67,7 @@ typedef std::shared_ptr WavesRef; * weight or float via the point's mass and volume parameters * - Coupled: The point position and velocity is externally imposed */ -class Point final : public io::IO, public CFL +class Point final : public io::IO, public SuperCFL { public: /** @brief Costructor diff --git a/source/Rod.cpp b/source/Rod.cpp index 6ea1724c..4c5ca541 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -196,6 +196,7 @@ Rod::addLine(Line* l, EndPoints l_end_point, EndPoints end_point) LOGERR << "Rod only has end points 'A' or 'B'" << endl; throw moordyn::invalid_value_error("Invalid end point"); } + SuperCFL::AddChild(l); } EndPoints @@ -211,6 +212,7 @@ Rod::removeLine(EndPoints end_point, Line* line) // This is the line's entry in the attachment list line_end_point = it->end_point; lines->erase(it); + SuperCFL::RemoveChild(line); // TODO Waves - we probably want to clean up the line node wave kin // stores in the waves class diff --git a/source/Rod.hpp b/source/Rod.hpp index 1a800d32..3eb7a999 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -63,7 +63,7 @@ class Line; * Each end point of the rod can be fixed or pinned to another object, let free * or control it externally */ -class Rod final : public io::IO, public CFL +class Rod final : public io::IO, public SuperCFL { public: /** @brief Costructor diff --git a/source/State.cpp b/source/State.cpp index 30ef5b47..bc67ba57 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -176,6 +176,40 @@ StateVar>::operator-(const StateVar>& rhs) return out; } +template<> +void +StateVar::Mix(const StateVar& rhs, const real& f) +{ + pos = pos * (1.0 - f) + rhs.pos * f; + vel = vel * (1.0 - f) + rhs.vel * f; +} + +template<> +void +StateVar::Mix(const StateVar& rhs, const real& f) +{ + pos = pos * (1.0 - f) + rhs.pos * f; + vel = vel * (1.0 - f) + rhs.vel * f; +} + +template<> +void +StateVar::Mix(const StateVar& rhs, const real& f) +{ + pos = pos * (1.0 - f) + rhs.pos * f; + vel = vel * (1.0 - f) + rhs.vel * f; +} + +template<> +void +StateVar>::Mix(const StateVar>& rhs, const real& f) +{ + for (unsigned int i = 0; i < pos.size(); i++) { + pos[i] = pos[i] * (1.0 - f) + rhs.pos[i] * f; + vel[i] = vel[i] * (1.0 - f) + rhs.vel[i] * f; + } +} + template<> string StateVarDeriv::AsString() const @@ -366,6 +400,45 @@ StateVarDeriv>::operator-( return out; } +template<> +real StateVarDeriv::MakeStationary(const real &dt) +{ + real ret = acc.norm(); + vel = 0.5 * dt * acc; + acc = vec::Zero(); + return ret; +} + +template<> +real StateVarDeriv::MakeStationary(const real &dt) +{ + real ret = acc.head<3>().norm(); + vel = 0.5 * dt * acc; + acc = vec6::Zero(); + return ret; +} + +template<> +real StateVarDeriv::MakeStationary(const real &dt) +{ + real ret = acc.head<3>().norm(); + vel = XYZQuat::fromVec6(0.5 * dt * acc); + acc = vec6::Zero(); + return ret; +} + +template<> +real StateVarDeriv>::MakeStationary(const real &dt) +{ + real ret = 0.0; + for (unsigned int i = 0; i < vel.size(); i++) { + ret += acc[i].norm(); + vel[i] = 0.5 * dt * acc[i]; + acc[i] = vec::Zero(); + } + return ret; +} + string MoorDynState::AsString() const { @@ -471,6 +544,20 @@ MoorDynState::operator-(const MoorDynState& rhs) return out; } +void +MoorDynState::Mix(const MoorDynState& visitor, const real& f) +{ + real ret = 0.0; + for (unsigned int i = 0; i < lines.size(); i++) + lines[i].Mix(visitor.lines[i], f); + for (unsigned int i = 0; i < points.size(); i++) + points[i].Mix(visitor.points[i], f); + for (unsigned int i = 0; i < rods.size(); i++) + rods[i].Mix(visitor.rods[i], f); + for (unsigned int i = 0; i < bodies.size(); i++) + bodies[i].Mix(visitor.bodies[i], f); +} + string DMoorDynStateDt::AsString() const { @@ -597,4 +684,19 @@ DMoorDynStateDt::operator-(const DMoorDynStateDt& rhs) return out; } +real +DMoorDynStateDt::MakeStationary(const real &dt) +{ + real ret = 0.0; + for (unsigned int i = 0; i < lines.size(); i++) + ret += lines[i].MakeStationary(dt); + for (unsigned int i = 0; i < points.size(); i++) + ret += points[i].MakeStationary(dt); + for (unsigned int i = 0; i < rods.size(); i++) + ret += rods[i].MakeStationary(dt); + for (unsigned int i = 0; i < bodies.size(); i++) + ret += bodies[i].MakeStationary(dt); + return ret; +} + } // ::moordyn diff --git a/source/State.hpp b/source/State.hpp index ab8c28af..056c6841 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -87,6 +87,16 @@ class StateVar * @param visitor The entity to sum */ StateVar operator-(const StateVar& visitor); + + /** @brief Mix this state with another one + * + * This can be used as a relaxation method when looking for stationary + * solutions + * @param visitor The other state + * @param f The mix factor. If 0.0, the state is not altered at all. If 1.0 + * the state is completely replaced by the @p visitor + */ + void Mix(const StateVar& visitor, const real& f); }; /** @class StateVarDeriv Time.hpp @@ -141,6 +151,24 @@ class StateVarDeriv * @param visitor The entity to subtract */ StateVarDeriv operator-(const StateVarDeriv& visitor); + + /** @brief Transform the variation rate to a stationary case + * + * In MoorDyn the states variation rates are called velocity and + * acceleration, because that is indeed the physical meaning they have. + * + * However, they are actually the position variation rate and the velocity + * variation rate respectively. Thus, replacing the former by the later + * multiplied by half of the time step, and vanishing the later, would + * be equivalent to getting an infinite viscosity, i.e. the system would + * not take velocity at all. + * + * This can be use therefore to look for stationary solutions + * @param dt Time step. + * @return The module of the linear acceleration, or their sum in case + * of lists of accelerations + */ + real MakeStationary(const real &dt); }; /// The state variables for lines @@ -212,6 +240,16 @@ class MoorDynState * @param visitor The entity to sum */ MoorDynState operator-(const MoorDynState& visitor); + + /** @brief Mix this state with another one + * + * This can be used as a relaxation method when looking for stationary + * solutions + * @param visitor The other state + * @param f The mix factor. If 0.0, the state is not altered at all. If 1.0 + * the state is completely replaced by the @p visitor + */ + void Mix(const MoorDynState& visitor, const real& f); }; /** @class DMoorDynStateDt Time.hpp @@ -265,6 +303,23 @@ class DMoorDynStateDt * @param visitor The entity to sum */ DMoorDynStateDt operator-(const DMoorDynStateDt& visitor); + + /** @brief Transform the variation rate to a stationary case + * + * In MoorDyn the states variation rates are called velocity and + * acceleration, because that is indeed the physical meaning they have. + * + * However, they are actually the position variation rate and the velocity + * variation rate respectively. Thus, replacing the former by the later + * multiplied by half of the time step, and vanishing the later, would + * be equivalent to getting an infinite viscosity, i.e. the system would + * not take velocity at all. + * + * This can be use therefore to look for stationary solutions + * @param dt Time step. + * @return The sum of the linear acceleration norms + */ + real MakeStationary(const real &dt); }; } // ::moordyn diff --git a/source/Time.cpp b/source/Time.cpp index 12aa4094..40e67e4b 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -95,11 +95,15 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) waves->updateWaves(); for (unsigned int i = 0; i < lines.size(); i++) { + if (!_calc_mask.lines[i]) + continue; std::tie(rd[substep].lines[i].vel, rd[substep].lines[i].acc) = lines[i]->getStateDeriv(); } for (unsigned int i = 0; i < points.size(); i++) { + if (!_calc_mask.points[i]) + continue; if (points[i]->type != Point::FREE) continue; std::tie(rd[substep].points[i].vel, rd[substep].points[i].acc) = @@ -107,6 +111,8 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) } for (unsigned int i = 0; i < rods.size(); i++) { + if (!_calc_mask.rods[i]) + continue; if ((rods[i]->type != Rod::PINNED) && (rods[i]->type != Rod::CPLDPIN) && (rods[i]->type != Rod::FREE)) continue; @@ -115,6 +121,8 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) } for (unsigned int i = 0; i < bodies.size(); i++) { + if (!_calc_mask.bodies[i]) + continue; if ((bodies[i]->type != Body::FREE) && (bodies[i]->type != Body::CPLDPIN)) continue; std::tie(rd[substep].bodies[i].vel, rd[substep].bodies[i].acc) = @@ -141,6 +149,87 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) ground->setDependentStates(); // NOTE: (not likely needed) } +template +void +TimeSchemeBase::FromStationary(const StationaryScheme& state) +{ + r[0] = state.r[0]; +} + + +StationaryScheme::StationaryScheme(moordyn::Log* log, moordyn::WavesRef waves) + : TimeSchemeBase(log, waves) + , _error(0.0) + , _booster(1.0) +{ + name = "Stationary solution"; +} + +#ifndef STATIONARY_BOOSTING +#define STATIONARY_BOOSTING 1.01 +#endif + +#ifndef STATIONARY_MAX_BOOSTING +#define STATIONARY_MAX_BOOSTING 10.0 +#endif + +#ifndef STATIONARY_MIN_BOOSTING +#define STATIONARY_MIN_BOOSTING 0.1 +#endif + +#ifndef STATIONARY_RELAX +#define STATIONARY_RELAX 0.5 +#endif + +void +StationaryScheme::Step(real& dt) +{ + Update(0.0, 0); + CalcStateDeriv(0); + const real error_prev = _error; + _error = rd[0].MakeStationary(dt); + if (error_prev != 0.0) { + if (error_prev >= _error) { + // Let's try to boost the convergence + _booster *= STATIONARY_BOOSTING; + } + else if (error_prev < _error) { + // We clearly overshot, so let's relax the solution and reduce the + // boosting + _booster /= STATIONARY_BOOSTING; + r[0].Mix(r[1], STATIONARY_RELAX); + Update(0.0, 0); + CalcStateDeriv(0); + _error = rd[0].MakeStationary(dt); + } + } + if (_booster > STATIONARY_MAX_BOOSTING) + _booster = STATIONARY_MAX_BOOSTING; + else if (_booster < STATIONARY_MIN_BOOSTING) + _booster = STATIONARY_MIN_BOOSTING; + + real new_dt = _booster * dt; + // Check that the time step is not too large, or limit it otherwise + real v = 0.5 * dt * _error; + for (auto obj : lines) + new_dt = (std::min)(new_dt, obj->cfl2dt(cfl, v)); + for (auto obj : points) { + new_dt = (std::min)(new_dt, obj->cfl2dt(cfl, v)); + } + for (auto obj : rods) { + new_dt = (std::min)(new_dt, obj->cfl2dt(cfl, v)); + } + for (auto obj : bodies) { + new_dt = (std::min)(new_dt, obj->cfl2dt(cfl, v)); + } + + r[1] = r[0]; + r[0] = r[0] + rd[0] * new_dt; + t += dt; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + EulerScheme::EulerScheme(moordyn::Log* log, moordyn::WavesRef waves) : TimeSchemeBase(log, waves) { @@ -158,6 +247,91 @@ EulerScheme::Step(real& dt) TimeSchemeBase::Step(dt); } +LocalEulerScheme::LocalEulerScheme(moordyn::Log* log, moordyn::WavesRef waves) + : EulerScheme(log, waves) + , _initialized(false) +{ + name = "1st order Local-Timestep Euler"; +} + +void +LocalEulerScheme::Step(real& dt) +{ + // BUG: We need a way to grant that the first passed dt is actually dtM0 + if (!_initialized) { + LOGMSG << name << ":" << endl; + for (auto line : lines) { + const real dt_line = line->cfl2dt(cfl); + _dt0.lines.push_back(0.999 * dt_line); + _dt.lines.push_back(dt_line); + LOGMSG << "Line " << line->number << ": dt = " << dt_line + << " s (updated each " << std::ceil(dt_line / dt) + << " timesteps)" << endl; + } + for (auto point : points) { + _dt0.points.push_back(0.0); + _dt.points.push_back(0.0); + } + for (auto rod : rods) { + _dt0.rods.push_back(0.0); + _dt.rods.push_back(0.0); + } + for (auto body : bodies) { + _dt0.bodies.push_back(0.0); + _dt.bodies.push_back(0.0); + } + _initialized = true; + } + SetCalcMask(dt); + Update(0.0, 0); + CalcStateDeriv(0); + r[0] = r[0] + rd[0] * dt; + t += dt; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + +void LocalEulerScheme::SetCalcMask(real& dt) +{ + unsigned int i = 0; + for (i = 0; i < lines.size(); i++) { + _dt.lines[i] += dt; + if (_dt.lines[i] >= _dt0.lines[i]) { + _dt.lines[i] = dt; + _calc_mask.lines[i] = true; + } else { + _calc_mask.lines[i] = false; + } + } + for (i = 0; i < points.size(); i++) { + _dt.points[i] += dt; + if (_dt.points[i] >= _dt0.points[i]) { + _dt.points[i] = dt; + _calc_mask.points[i] = true; + } else { + _calc_mask.points[i] = false; + } + } + for (i = 0; i < rods.size(); i++) { + _dt.rods[i] += dt; + if (_dt.rods[i] >= _dt0.rods[i]) { + _dt.rods[i] = dt; + _calc_mask.rods[i] = true; + } else { + _calc_mask.rods[i] = false; + } + } + for (i = 0; i < bodies.size(); i++) { + _dt.bodies[i] += dt; + if (_dt.bodies[i] >= _dt0.bodies[i]) { + _dt.bodies[i] = dt; + _calc_mask.bodies[i] = true; + } else { + _calc_mask.bodies[i] = false; + } + } +} + HeunScheme::HeunScheme(moordyn::Log* log, moordyn::WavesRef waves) : TimeSchemeBase(log, waves) { @@ -334,6 +508,8 @@ create_time_scheme(const std::string& name, TimeScheme* out = NULL; if (str::lower(name) == "euler") { out = new EulerScheme(log, waves); + } else if (str::lower(name) == "leuler") { + out = new LocalEulerScheme(log, waves); } else if (str::lower(name) == "heun") { out = new HeunScheme(log, waves); } else if (str::lower(name) == "rk2") { diff --git a/source/Time.hpp b/source/Time.hpp index f8f2018e..eb17c766 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -46,6 +46,8 @@ namespace moordyn { +class StationaryScheme; + /** @class TimeScheme Time.hpp * @brief Time scheme abstraction * @@ -215,6 +217,16 @@ class TimeScheme : public io::IO Next(); } + /** @brief Get the CFL factor + * @return The CFL factor + */ + inline real GetCFL() const { return cfl; } + + /** @brief Set the CFL factor + * @param cfl The CFL factor + */ + inline void SetCFL(const real& cfl) { this->cfl = cfl; } + /** @brief Prepare everything for the next outer time step * * Always call this method before start calling TimeScheme::Step() @@ -232,7 +244,7 @@ class TimeScheme : public io::IO * the derivatives are initialized in any way. * @note It is assumed that the coupled entities were already initialized */ - virtual void init() = 0; + virtual void Init() = 0; /** @brief Run a time step * @@ -243,6 +255,11 @@ class TimeScheme : public io::IO */ virtual void Step(real& dt) { t_local += dt; }; + /** @brief Resume the simulation from the stationary solution + * @param state The stationary solution + */ + virtual void FromStationary(const StationaryScheme& state) {}; + protected: /** @brief Costructor * @param log Logging handler @@ -276,6 +293,9 @@ class TimeScheme : public io::IO real t; /// The local time, within the outer time step real t_local; + + /// Maximum CFL factor + real cfl; }; // Forward declare waves @@ -319,6 +339,8 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < rd.size(); i++) { rd[i].lines.push_back(dstate); } + // Add the mask value + _calc_mask.lines.push_back(true); } /** @brief Remove a line @@ -339,6 +361,7 @@ class TimeSchemeBase : public TimeScheme r[i].lines.erase(r[i].lines.begin() + i); for (unsigned int i = 0; i < rd.size(); i++) rd[i].lines.erase(rd[i].lines.begin() + i); + _calc_mask.lines.erase(_calc_mask.lines.begin() + i); return i; } @@ -366,6 +389,8 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < rd.size(); i++) { rd[i].points.push_back(dstate); } + // Add the mask value + _calc_mask.points.push_back(true); } /** @brief Remove a point @@ -386,6 +411,7 @@ class TimeSchemeBase : public TimeScheme r[i].points.erase(r[i].points.begin() + i); for (unsigned int i = 0; i < rd.size(); i++) rd[i].points.erase(rd[i].points.begin() + i); + _calc_mask.points.erase(_calc_mask.points.begin() + i); return i; } @@ -413,6 +439,8 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < rd.size(); i++) { rd[i].rods.push_back(dstate); } + // Add the mask value + _calc_mask.rods.push_back(true); } /** @brief Remove a rod @@ -433,6 +461,7 @@ class TimeSchemeBase : public TimeScheme r[i].rods.erase(r[i].rods.begin() + i); for (unsigned int i = 0; i < rd.size(); i++) rd[i].rods.erase(rd[i].rods.begin() + i); + _calc_mask.rods.erase(_calc_mask.rods.begin() + i); return i; } @@ -460,6 +489,8 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < rd.size(); i++) { rd[i].bodies.push_back(dstate); } + // Add the mask value + _calc_mask.bodies.push_back(true); } /** @brief Remove a body @@ -480,6 +511,7 @@ class TimeSchemeBase : public TimeScheme r[i].bodies.erase(r[i].bodies.begin() + i); for (unsigned int i = 0; i < rd.size(); i++) rd[i].bodies.erase(rd[i].bodies.begin() + i); + _calc_mask.bodies.erase(_calc_mask.bodies.begin() + i); return i; } @@ -488,11 +520,12 @@ class TimeSchemeBase : public TimeScheme * the derivatives are initialized in any way. * @note It is assumed that the coupled entities were already initialized */ - virtual void init() + virtual void Init() { // NOTE: Probably is best to populate all the entities to the time // integrator, no matter if they are free or not. Thus they can change - // types (mutate) without needing to micromanage them in the time scheme + // types (mutate) without needing to micromanage them in the time + // scheme for (unsigned int i = 0; i < bodies.size(); i++) { if ((bodies[i]->type != Body::FREE) && (bodies[i]->type != Body::CPLDPIN)) // Only fully coupled bodies are intialized in MD2.cpp continue; @@ -529,6 +562,11 @@ class TimeSchemeBase : public TimeScheme */ virtual void Step(real& dt) { TimeScheme::Step(dt); }; + /** @brief Resume the simulation from the stationary solution + * @param state The stationary solution + */ + void FromStationary(const StationaryScheme& state); + /** @brief Produce the packed data to be saved * * The produced data can be used afterwards to restore the saved information @@ -692,7 +730,70 @@ class TimeSchemeBase : public TimeScheme /// The list of state derivatives std::array rd; + /// The waves instance std::shared_ptr waves; + + /** @brief A mask to determine which entities shall be computed. + * + * Useful for local time steps + */ + typedef struct _mask { + /// The lines mask + std::vector lines; + /// The points mask + std::vector points; + /// The rods mask + std::vector rods; + /// The bodies mask + std::vector bodies; + } mask; + + /// The TimeSchemeBase::CalcStateDeriv() mask + mask _calc_mask; +}; + +/** @class StationaryScheme Time.hpp + * @brief A stationary solution + * + * The stationary solution is featured by the lack of velocity on the system, + * i.e. the system positions are integrating directly from the accelerations + */ +class StationaryScheme : public TimeSchemeBase<2, 1> +{ + template + friend class TimeSchemeBase; + + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + */ + StationaryScheme(moordyn::Log* log, WavesRef waves); + + /// @brief Destructor + ~StationaryScheme() {} + + /** @brief Run a time step + * + * This function is the one that must be specialized on each time scheme + * @param dt Time step + */ + void Step(real& dt); + + /** @brief Get the error computed at the last time step + * @return The error, StationaryScheme::_error + */ + inline real Error() const { return _error; } + + private: + /** The last computed acceleration module + * @see DMoorDynStateDt::MakeStationary() + * @see StationaryScheme::Error() + */ + real _error; + + /// The convergence boosting rate + real _booster; }; /** @class EulerScheme Time.hpp @@ -711,7 +812,7 @@ class EulerScheme : public TimeSchemeBase<1, 1> EulerScheme(moordyn::Log* log, WavesRef waves); /// @brief Destructor - ~EulerScheme() {} + virtual ~EulerScheme() {} /** @brief Run a time step * @@ -721,6 +822,65 @@ class EulerScheme : public TimeSchemeBase<1, 1> virtual void Step(real& dt); }; +/** @class LocalEulerScheme Time.hpp + * @brief A modification of the 1st order Euler's time scheme, which is + * considering different time steps for each instance. + * + * The local time step of each entity is computed according to the maximum CFL + * factor of all entities. Such local time step is indeed an integer times the + * time step provided to LocalEulerScheme::Step(). + * + * Thus, the derivatives recomputation is delayed until those time steps are + * fulfilled + */ +class LocalEulerScheme : public EulerScheme +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + */ + LocalEulerScheme(moordyn::Log* log, WavesRef waves); + + /// @brief Destructor + ~LocalEulerScheme() {} + + /** @brief Run a time step + * @param dt Time step + */ + virtual void Step(real& dt); + + private: + /** @brief Set the calculation mask + * @param dt Time step + */ + void SetCalcMask(real& dt); + + /** @brief The timestep of each instance + */ + typedef struct _sdeltat { + /// The lines mask + std::vector lines; + /// The points mask + std::vector points; + /// The rods mask + std::vector rods; + /// The bodies mask + std::vector bodies; + } deltat; + + /// Do the time steps have been initialized + bool _initialized; + + /// The timestep of each instance + deltat _dt0; + + /// The counter of already integrated timestep for each instance. + deltat _dt; +}; + + + /** @class HeunScheme Time.hpp * @brief Quasi 2nd order Heun's time scheme * diff --git a/source/Util/CFL.hpp b/source/Util/CFL.hpp index a4f9e4c6..fb19f0dc 100644 --- a/source/Util/CFL.hpp +++ b/source/Util/CFL.hpp @@ -37,6 +37,7 @@ #include "Misc.hpp" #include #include +#include using namespace std; @@ -57,7 +58,7 @@ class CFL public: /** @brief Constructor */ - CFL() {}; + CFL() : _l(std::numeric_limits::max()) {}; /** @brief Destructor */ @@ -74,12 +75,41 @@ class CFL * @return CFL factor */ virtual inline real dt2cfl(const real dt) const { return 0.0; } + + /** @brief Get the timestep from a CFL factor and velocity + * @param cfl CFL factor + * @param v velocity + * @return The timestep + */ + virtual inline real cfl2dt(const real cfl, const real v) const { return cfl * length() / v; } + + /** @brief Get the CFL factor from a timestep and velocity + * @param dt Timestep + * @param v velocity + * @return CFL factor + */ + virtual inline real dt2cfl(const real dt, const real v) const { return dt * v / length(); } + + protected: + /** @brief Set the characteristic length of the system + * @param l lenght + */ + inline void length(real l) { _l = l; } + + /** @brief Get the characteristic length of the system + * @return lenght + */ + inline real length() const { return _l; } + + private: + /// Length + real _l; }; /** @class NatFreqCFL CFL.hpp * @brief CFL for objects based on a natural frequency */ -class NatFreqCFL +class NatFreqCFL : public CFL { public: /** @brief Constructor @@ -94,13 +124,27 @@ class NatFreqCFL * @param cfl CFL factor * @return The timestUtilep */ - virtual inline real cfl2dt(const real cfl) const { return cfl * period(); } + inline real cfl2dt(const real cfl) const { return cfl * period(); } /** @brief Get the CFL factor from a timestep * @param dt Timestep * @return CFL factor */ - virtual inline real dt2cfl(const real dt) const { return dt / period(); } + inline real dt2cfl(const real dt) const { return dt / period(); } + + /** @brief Get the timestep from a CFL factor and velocity + * @param cfl CFL factor + * @param v velocity + * @return The timestep + */ + inline real cfl2dt(const real cfl, const real v) const { return CFL::cfl2dt(cfl, v); } + + /** @brief Get the CFL factor from a timestep and velocity + * @param dt Timestep + * @param v velocity + * @return CFL factor + */ + inline real dt2cfl(const real dt, const real v) const { return CFL::dt2cfl(dt, v); } protected: /** @brief Set the stiffness of the system @@ -141,4 +185,86 @@ class NatFreqCFL real _m; }; +/** @class SuperCFL CFL.hpp + * @brief CFL extracted from connected objects + * + * Some objects has not an actual CFL definition, but they instead compute it + * from the entities attached to it. + */ +class SuperCFL : public CFL +{ + public: + /** @brief Constructor + */ + SuperCFL() {}; + + /** @brief Destructor + */ + virtual ~SuperCFL() {}; + + /** @brief Get the timestep from a CFL factor + * @param cfl CFL factor + * @return The timestUtilep + */ + inline real cfl2dt(const real cfl) const { + auto dt = CFL::cfl2dt(cfl); + for (auto obj : _children) + dt = (std::min)(dt, obj->cfl2dt(cfl)); + return dt; + } + + /** @brief Get the CFL factor from a timestep + * @param dt Timestep + * @return CFL factor + */ + inline real dt2cfl(const real dt) const { + auto cfl = CFL::dt2cfl(dt); + for (auto obj : _children) + cfl = (std::max)(cfl, obj->dt2cfl(dt)); + return cfl; + } + + /** @brief Get the timestep from a CFL factor and velocity + * @param cfl CFL factor + * @param v velocity + * @return The timestep + */ + inline real cfl2dt(const real cfl, const real v) const{ + auto dt = CFL::cfl2dt(cfl, v); + for (auto obj : _children) + dt = (std::min)(dt, obj->cfl2dt(cfl, v)); + return dt; + } + + /** @brief Get the CFL factor from a timestep and velocity + * @param dt Timestep + * @param v velocity + * @return CFL factor + */ + inline real dt2cfl(const real dt, const real v) const { + auto cfl = CFL::dt2cfl(dt, v); + for (auto obj : _children) + cfl = (std::max)(cfl, obj->dt2cfl(dt, v)); + return cfl; + } + + protected: + /** @brief Add a child + * @param c child + */ + inline void AddChild(CFL* c) { _children.push_back(c); } + + /** @brief Remove a child + * @param c child + */ + inline void RemoveChild(CFL* c) { + _children.erase(std::remove(_children.begin(), _children.end(), c), + _children.end()); + } + + private: + /// List of children + std::vector _children; +}; + } // ::moordyn diff --git a/tests/Mooring/BeamCantilevered.txt b/tests/Mooring/BeamCantilevered.txt index 03b3839c..43f59552 100644 --- a/tests/Mooring/BeamCantilevered.txt +++ b/tests/Mooring/BeamCantilevered.txt @@ -15,17 +15,16 @@ ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutput ---------------------- POINT PROPERTIES -------------------------------- ID Type X Y Z Mass Volume CdA Ca (#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) -1 Free 10 0.0 10.0 0 0 0 0 +1 Free 10 0.0 9.9 0 0 0 0 ---------------------- LINES ---------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-) 1 beam R1B 1 10 19 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -1e-5 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep 10 WtrDpth water depth (m) -0.25 dtIC time interval for analyzing convergence during IC gen (s) -20.0 TmaxIC max time for ic gen (s) -1.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +40.0 TmaxIC max time for ic gen (s) +1e-5 threshIC threshold for IC convergence (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/BeamSimplySupported.txt b/tests/Mooring/BeamSimplySupported.txt index fab65167..47a8073f 100644 --- a/tests/Mooring/BeamSimplySupported.txt +++ b/tests/Mooring/BeamSimplySupported.txt @@ -15,10 +15,9 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 1 beam 1 2 10 19 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -1e-5 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep 10 WtrDpth water depth (m) -0.25 dtIC time interval for analyzing convergence during IC gen (s) -20.0 TmaxIC max time for ic gen (s) -1.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +40.0 TmaxIC max time for ic gen (s) +1e-5 threshIC threshold for IC convergence (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/RodHanging.txt b/tests/Mooring/RodHanging.txt index 7cbb0fd6..659a7037 100644 --- a/tests/Mooring/RodHanging.txt +++ b/tests/Mooring/RodHanging.txt @@ -27,8 +27,5 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 2 writeLog Write a log file 2e-3 dtM time step to use in mooring integration (s) 150 WtrDpth water depth (m) -0.25 dtIC time interval for analyzing convergence during IC gen (s) -100.0 TmaxIC max time for ic gen (s) -1.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +0 TmaxIC max time for ic gen (s) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/WD0050_Chain.txt b/tests/Mooring/WD0050_Chain.txt index c54eac36..f8229ecf 100644 --- a/tests/Mooring/WD0050_Chain.txt +++ b/tests/Mooring/WD0050_Chain.txt @@ -12,17 +12,16 @@ ID Type X Y Z Mass Volume CdA Ca ---------------------- LINES ---------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-) -1 chain 1 2 410 82 - +1 chain 1 2 410 41 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -0.001 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep 1.0e5 kBot bottom stiffness (Pa/m) 1.0e4 cBot bottom damping (Pa-s/m) 1025.0 WtrDnsty water density (kg/m^3) 50 WtrDpth water depth (m) 1.0 dtIC time interval for analyzing convergence during IC gen (s) -200.0 TmaxIC max time for ic gen (s) -4.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +100.0 TmaxIC max time for ic gen (s) +1.0e-2 threshIC threshold for IC convergence (-) 0.5 FrictionCoefficient general bottom friction coefficient, as a start (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/WD0200_Chain.txt b/tests/Mooring/WD0200_Chain.txt index 7bb17d38..cb6f3588 100644 --- a/tests/Mooring/WD0200_Chain.txt +++ b/tests/Mooring/WD0200_Chain.txt @@ -7,22 +7,21 @@ chain 0.252 390 1.674e9 -1.0 0 1.37 1.0 0. ---------------------- POINT PROPERTIES -------------------------------- ID Type X Y Z Mass Volume CdA Ca (#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) -1 Fixed 700 0.0 -200.0 0 0 0 0 +1 Fixed 700 0.0 -200.0 0 0 0 0 2 Vessel 0.0 0.0 0.0 0 0 0 0 ---------------------- LINES ---------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-) -1 chain 1 2 760 82 - +1 chain 1 2 760 76 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -0.001 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep 1.0e5 kBot bottom stiffness (Pa/m) 1.0e4 cBot bottom damping (Pa-s/m) 1025.0 WtrDnsty water density (kg/m^3) 200 WtrDpth water depth (m) 1.0 dtIC time interval for analyzing convergence during IC gen (s) -200.0 TmaxIC max time for ic gen (s) -4.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +100.0 TmaxIC max time for ic gen (s) +1.0e-2 threshIC threshold for IC convergence (-) 0.5 FrictionCoefficient Coulomb friction between the line and the seabed (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/WD0600_Chain.txt b/tests/Mooring/WD0600_Chain.txt index e5cea0d4..233538e9 100644 --- a/tests/Mooring/WD0600_Chain.txt +++ b/tests/Mooring/WD0600_Chain.txt @@ -12,17 +12,16 @@ ID Type X Y Z Mass Volume CdA Ca ---------------------- LINES ---------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-) -1 chain 1 2 1700 82 - +1 chain 1 2 1700 170 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -0.001 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep 1.0e5 kBot bottom stiffness (Pa/m) 1.0e4 cBot bottom damping (Pa-s/m) 1025.0 WtrDnsty water density (kg/m^3) 600 WtrDpth water depth (m) 1.0 dtIC time interval for analyzing convergence during IC gen (s) -200.0 TmaxIC max time for ic gen (s) -4.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -1.0e-3 threshIC threshold for IC convergence (-) +100.0 TmaxIC max time for ic gen (s) +1.0e-2 threshIC threshold for IC convergence (-) 0.5 FrictionCoefficient Coulomb friction between the line and the seabed (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/pendulum.txt b/tests/Mooring/pendulum.txt index a449a68a..21a67f9e 100644 --- a/tests/Mooring/pendulum.txt +++ b/tests/Mooring/pendulum.txt @@ -16,12 +16,11 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 1 main 1 2 100.5 20 - ---------------------- OPTIONS ----------------------------------------- 2 writeLog Write a log file -1E-4 dtM time step to use in mooring integration (s) +0.1 cfl CFL to determine the simulation timestep RK4 tScheme The time integration Scheme (-) 1000.0 WtrDnsty water density (kg/m^3) 500 WtrDpth water depth (m) -1E-3 dtIC time interval for analyzing convergence during IC gen (s) -1.0 TmaxIC max time for ic gen (s) -1.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -0.01 threshIC threshold for IC convergence (-) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +10000.0 TmaxIC max time for ic gen (s) +1e-4 threshIC threshold for IC convergence (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/rod_tests/AddedMass.txt b/tests/Mooring/rod_tests/AddedMass.txt index e46b40ca..8fbb392a 100644 --- a/tests/Mooring/rod_tests/AddedMass.txt +++ b/tests/Mooring/rod_tests/AddedMass.txt @@ -16,15 +16,12 @@ ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOut 1 floatRod free 0 -1 -10 0 1.0 -10 4 - -------------------------- SOLVER OPTIONS---------------------------------------------------------- 0 writeLog - Write a log file -0.0005 dtM - time step to use in mooring integration +0.0005 dtM - time step to use in mooring integration rk4 tScheme - Solver 3.0e6 kb - bottom stiffness 3.0e5 cb - bottom damping 16.0 WtrDpth - water depth -2.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen -0.0015 threshIC - threshold for IC convergence -0.0 TmaxIC - threshold for IC convergence -0.0001 dtIC - Time lapse between convergence tests (s) +0 TmaxIC - max time for ic gen (s) 0 Currents - Whether or not to pull in currents 0 WaveKin - Whether or not to pull in waves ------------------------- need this line -------------------------------------- diff --git a/tests/quasi_static_chain.cpp b/tests/quasi_static_chain.cpp index 06135d81..320565d3 100644 --- a/tests/quasi_static_chain.cpp +++ b/tests/quasi_static_chain.cpp @@ -153,6 +153,10 @@ validation(const char* depth, const char* motion) return false; } + stringstream vtk_file; + vtk_file << depth << ".vtm"; + MoorDyn_SaveVTK(system, vtk_file.str().c_str()); + // Compute the static tension int num_lines = 1; float fh, fv, ah, av; From 840549ba74da627d99e6e0b8d14b52d282d1a2f0 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sun, 31 Dec 2023 09:51:44 +0100 Subject: [PATCH 037/145] Drop debugging VTK file printing --- tests/quasi_static_chain.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/tests/quasi_static_chain.cpp b/tests/quasi_static_chain.cpp index 320565d3..06135d81 100644 --- a/tests/quasi_static_chain.cpp +++ b/tests/quasi_static_chain.cpp @@ -153,10 +153,6 @@ validation(const char* depth, const char* motion) return false; } - stringstream vtk_file; - vtk_file << depth << ".vtm"; - MoorDyn_SaveVTK(system, vtk_file.str().c_str()); - // Compute the static tension int num_lines = 1; float fh, fv, ah, av; From 495cabc4461bd949cc9f15716447f40083d9fda6 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sun, 31 Dec 2023 11:15:48 +0100 Subject: [PATCH 038/145] Test the local-Euler and Euler time schemes consistency --- tests/CMakeLists.txt | 1 + tests/Mooring/local_euler/duplicated.txt | 35 ++++++++++++++ tests/local_euler.cpp | 61 ++++++++++++++++++++++++ 3 files changed, 97 insertions(+) create mode 100644 tests/Mooring/local_euler/duplicated.txt create mode 100644 tests/local_euler.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index fe9f1b6c..e23a5dab 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -45,6 +45,7 @@ set(CATCH2_TESTS beam conveying_fluid polyester + local_euler ) function(make_executable test_name, extension) diff --git a/tests/Mooring/local_euler/duplicated.txt b/tests/Mooring/local_euler/duplicated.txt new file mode 100644 index 00000000..8c5d4c10 --- /dev/null +++ b/tests/Mooring/local_euler/duplicated.txt @@ -0,0 +1,35 @@ +--------------------- MoorDyn Input File ------------------------------------ +Input file to test that Local-Euler (with local time steps for each entity) +behaves so far like the normal Euler time scheme. + +To this end, we set 2 totally independent duplicated lines, in such a way that +one of the lines has a smaller time step. + +Since both lines are independent, the system shall actually behave like 2 +separate systems governed by regular Euler tme schemes. +----------------------- 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.252 390 1.674e9 -1.0 0 1.37 1.0 0.64 0.0 +---------------------- POINT PROPERTIES -------------------------------- +ID Type X Y Z Mass Volume CdA Ca +(#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) +1 Fixed 700 0.0 -200.0 0 0 0 0 +2 Vessel 0.0 0.0 0.0 0 0 0 0 +---------------------- LINES ---------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs +(#) (name) (#) (#) (m) (-) (-) +1 chain 1 2 760 76 - +2 chain 1 2 760 152 - +---------------------- OPTIONS ----------------------------------------- +2 writeLog Write a log file +0.1 cfl CFL to determine the simulation timestep +1.0e5 kBot bottom stiffness (Pa/m) +1.0e4 cBot bottom damping (Pa-s/m) +1025.0 WtrDnsty water density (kg/m^3) +200 WtrDpth water depth (m) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +100.0 TmaxIC max time for ic gen (s) +1.0e-2 threshIC threshold for IC convergence (-) +lEuler tScheme The time integration Scheme (-) +------------------------- need this line -------------------------------------- diff --git a/tests/local_euler.cpp b/tests/local_euler.cpp new file mode 100644 index 00000000..1452a83f --- /dev/null +++ b/tests/local_euler.cpp @@ -0,0 +1,61 @@ +#include +#include "MoorDyn2.h" +#include + +#define DUPLICATED_TOL 1e-4 + +double compare_lines(MoorDynLine line1, MoorDynLine line2) +{ + unsigned int n1, n2; + REQUIRE(MoorDyn_GetLineN(line1, &n1) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_GetLineN(line2, &n2) == MOORDYN_SUCCESS); + REQUIRE(((n1 != n2) && (n2 % n1 == 0))); + unsigned int m = n2 / n1; + double error = 0.0; + for (unsigned int i = 0; i < n1; i++) { + double pos1[3], pos2[3]; + REQUIRE(MoorDyn_GetLineNodePos(line1, i, pos1) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_GetLineNodePos(line2, i * m, pos2) == MOORDYN_SUCCESS); + const double e_x = pos2[0] - pos1[0]; + const double e_z = pos2[2] - pos1[2]; + const double e = sqrt(e_x * e_x + e_z * e_z); + if (error < e) + error = e; + } + return error; +} + +TEST_CASE("Duplicated line with different resolutions") +{ + MoorDyn system = MoorDyn_Create("Mooring/local_euler/duplicated.txt"); + REQUIRE(system); + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + auto point = MoorDyn_GetPoint(system, 2); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x) == MOORDYN_SUCCESS); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + auto line1 = MoorDyn_GetLine(system, 1); + REQUIRE(line1); + double l; + REQUIRE(MoorDyn_GetLineUnstretchedLength(line1, &l) == MOORDYN_SUCCESS); + auto line2 = MoorDyn_GetLine(system, 2); + REQUIRE(line2); + auto e0 = compare_lines(line1, line2); + REQUIRE(e0 / l <= DUPLICATED_TOL); + + double f[3]; + double t = 0.0, dt = 1.0; + dx[0] = -1.0; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + auto e = compare_lines(line1, line2); + REQUIRE(e / l <= DUPLICATED_TOL); + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} From c982879454565123616833344f4ab5365b168964 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jan 2024 19:21:00 +0100 Subject: [PATCH 039/145] Allow initializing lines hanging above the seabed --- source/Line.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 23cc40b2..ff798ee8 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -464,11 +464,17 @@ Line::initialize() real XF = dir(Eigen::seqN(0, 2)).norm(); // horizontal spread if (XF > 0.0) { - - real ZF = dir[2]; - real LW = ((rho - env->rho_w) * A) * env->g; - real CB = 0.; - real Tol = 1e-5; + // Check if the line touches the seabed, so we are modelling it. Just + // the end points are checked + const real Tol = 1e-5; + real CB = -1.0; + for (unsigned int i = 0; i <= N; i += N) { + const real waterDepth = getWaterDepth(r[i][0], r[i][1]); + if(r[i][2] <= waterDepth * (1.0 - Tol)) + CB = 0.0; + } + const real ZF = dir[2]; + const real LW = ((rho - env->rho_w) * A) * env->g; // locations of line nodes along line length - evenly distributed // here From 1d57ab622910a9e119ae5719d7af5431beab4932 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jan 2024 19:24:58 +0100 Subject: [PATCH 040/145] Local-Euler test on a hanging line split on the middle --- source/Time.cpp | 28 +++++++++++++++++++--- source/Time.hpp | 7 ++++++ tests/Mooring/local_euler/hanging.txt | 34 +++++++++++++++++++++++++++ tests/local_euler.cpp | 33 ++++++++++++++++++++++++++ 4 files changed, 99 insertions(+), 3 deletions(-) create mode 100644 tests/Mooring/local_euler/hanging.txt diff --git a/source/Time.cpp b/source/Time.cpp index 40e67e4b..a6309529 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -257,26 +257,32 @@ LocalEulerScheme::LocalEulerScheme(moordyn::Log* log, moordyn::WavesRef waves) void LocalEulerScheme::Step(real& dt) { - // BUG: We need a way to grant that the first passed dt is actually dtM0 if (!_initialized) { LOGMSG << name << ":" << endl; + real dtM = ComputeDt(); for (auto line : lines) { const real dt_line = line->cfl2dt(cfl); _dt0.lines.push_back(0.999 * dt_line); _dt.lines.push_back(dt_line); LOGMSG << "Line " << line->number << ": dt = " << dt_line - << " s (updated each " << std::ceil(dt_line / dt) + << " s (updated each " << std::ceil(dt_line / dtM) << " timesteps)" << endl; } for (auto point : points) { + LOGMSG << "Point " << point->number << ": dt = " << dtM + << " s (updated each 1 timesteps)" << endl; _dt0.points.push_back(0.0); _dt.points.push_back(0.0); } for (auto rod : rods) { + LOGMSG << "Rod " << rod->number << ": dt = " << dtM + << " s (updated each 1 timesteps)" << endl; _dt0.rods.push_back(0.0); _dt.rods.push_back(0.0); } for (auto body : bodies) { + LOGMSG << "Body " << body->number << ": dt = " << dtM + << " s (updated each 1 timesteps)" << endl; _dt0.bodies.push_back(0.0); _dt.bodies.push_back(0.0); } @@ -291,7 +297,23 @@ LocalEulerScheme::Step(real& dt) TimeSchemeBase::Step(dt); } -void LocalEulerScheme::SetCalcMask(real& dt) +real +LocalEulerScheme::ComputeDt() const +{ + real dt = std::numeric_limits::max(); + for (auto obj : lines) + dt = (std::min)(dt, obj->cfl2dt(cfl)); + for (auto obj : points) + dt = (std::min)(dt, obj->cfl2dt(cfl)); + for (auto obj : rods) + dt = (std::min)(dt, obj->cfl2dt(cfl)); + for (auto obj : bodies) + dt = (std::min)(dt, obj->cfl2dt(cfl)); + return dt; +} + +void +LocalEulerScheme::SetCalcMask(real& dt) { unsigned int i = 0; for (i = 0; i < lines.size(); i++) { diff --git a/source/Time.hpp b/source/Time.hpp index eb17c766..25e905f3 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -851,6 +851,13 @@ class LocalEulerScheme : public EulerScheme virtual void Step(real& dt); private: + /** @brief Compute the model time step + * + * This can be done since we know the TimeScheme::cfl factor + * @return The model time step + */ + real ComputeDt() const; + /** @brief Set the calculation mask * @param dt Time step */ diff --git a/tests/Mooring/local_euler/hanging.txt b/tests/Mooring/local_euler/hanging.txt new file mode 100644 index 00000000..3e91b10a --- /dev/null +++ b/tests/Mooring/local_euler/hanging.txt @@ -0,0 +1,34 @@ +--------------------- MoorDyn Input File ------------------------------------ +Input file to test that simplest coupled lines work nice when Local-Euler time +scheme is considered. + +More specifically, a hanging line from 2 horizontal points is split into 2 +identical parts, each one simulated with a different number of nodes, and thus +with different time steps. +----------------------- 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.252 390 1.674e9 -1.0 0 1.37 1.0 0.64 0.0 +---------------------- POINT PROPERTIES -------------------------------- +ID Type X Y Z Mass Volume CdA Ca +(#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) +1 Vessel -350 0.0 0.0 0 0 0 0 +2 Vessel 350 0.0 0.0 0 0 0 0 +3 Free 0 0.0 -140.0 0 0 0 0 +---------------------- LINES ---------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs +(#) (name) (#) (#) (m) (-) (-) +1 chain 1 3 380 76 - +2 chain 2 3 380 152 - +---------------------- OPTIONS ----------------------------------------- +2 writeLog Write a log file +0.1 cfl CFL to determine the simulation timestep +1.0e5 kBot bottom stiffness (Pa/m) +1.0e4 cBot bottom damping (Pa-s/m) +1025.0 WtrDnsty water density (kg/m^3) +1000 WtrDpth water depth (m) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +100.0 TmaxIC max time for ic gen (s) +1.0e-3 threshIC threshold for IC convergence (-) +lEuler tScheme The time integration Scheme (-) +------------------------- need this line -------------------------------------- diff --git a/tests/local_euler.cpp b/tests/local_euler.cpp index 1452a83f..cc44495e 100644 --- a/tests/local_euler.cpp +++ b/tests/local_euler.cpp @@ -1,8 +1,10 @@ #include +#include #include "MoorDyn2.h" #include #define DUPLICATED_TOL 1e-4 +#define HANGING_TOL 1e-1 double compare_lines(MoorDynLine line1, MoorDynLine line2) { @@ -59,3 +61,34 @@ TEST_CASE("Duplicated line with different resolutions") REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); } + +TEST_CASE("Hanging split line") +{ + MoorDyn system = MoorDyn_Create("Mooring/local_euler/hanging.txt"); + REQUIRE(system); + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 6); + + double x[6], dx[6]; + for (unsigned int i = 0; i < 2; i++) { + auto point = MoorDyn_GetPoint(system, i + 1); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x + 3 * i) == MOORDYN_SUCCESS); + } + std::fill(dx, dx + 6, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + double f[6]; + double t = 0.0, dt = 1.0; + dx[0] = 1.0; + dx[3] = -1.0; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + auto joint = MoorDyn_GetPoint(system, 3); + REQUIRE(joint); + REQUIRE(MoorDyn_GetPointPos(joint, x) == MOORDYN_SUCCESS); + REQUIRE(std::abs(x[0]) < HANGING_TOL); + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} From cd1f7b57a9300b0ba1ef73f01a67909ebf486fc8 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jan 2024 19:29:23 +0100 Subject: [PATCH 041/145] We do not need to initialize twice --- source/MoorDyn2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index fe3d52ea..f64de837 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -318,7 +318,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // Initialize the system state _t_integrator->SetCFL(cfl); - _t_integrator->Init(); + // _t_integrator->Init(); // Let the stationary solution deal with this // ------------------ do dynamic relaxation IC gen -------------------- From 53ed9ce149c4c9bf663490084e2df10f227387e0 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jan 2024 08:36:22 +0100 Subject: [PATCH 042/145] Upgraded Orcaflex validation to Catch2 --- tests/CMakeLists.txt | 2 +- tests/quasi_static_chain.cpp | 113 +++++++---------------------------- 2 files changed, 24 insertions(+), 91 deletions(-) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index e23a5dab..e0e8fd68 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -30,7 +30,6 @@ set(CPP_TESTS io rods bodies_and_rods - quasi_static_chain wavekin_4 tripod seafloor @@ -45,6 +44,7 @@ set(CATCH2_TESTS beam conveying_fluid polyester + quasi_static_chain local_euler ) diff --git a/tests/quasi_static_chain.cpp b/tests/quasi_static_chain.cpp index 06135d81..948bb038 100644 --- a/tests/quasi_static_chain.cpp +++ b/tests/quasi_static_chain.cpp @@ -28,20 +28,19 @@ * POSSIBILITY OF SUCH DAMAGE. */ -/** @file minimal.cpp +/** @file quasi_static_chain.cpp * Validation against Orcaflex */ #include "MoorDyn2.h" -#include -#include #include #include #include +#include #include #include -#include #include +#include using namespace std; @@ -88,10 +87,8 @@ read_tab_file(const char* filepath) vector> data; fstream f; f.open(filepath, ios::in); - if (!f.is_open()) { - cerr << "Cannot open file " << filepath << endl; + if (!f.is_open()) return data; - } string line; while (getline(f, line)) { data.push_back(parse_tab_line(line.c_str())); @@ -104,14 +101,11 @@ read_tab_file(const char* filepath) /** @brief Run a validation against a quasi-static code * @return true if the test worked, false otherwise */ -bool +void validation(const char* depth, const char* motion) { auto it = std::find(DEPTHS.begin(), DEPTHS.end(), depth); - if (it == DEPTHS.end()) { - cerr << "Unhandled water depth: " << depth << endl; - return false; - } + REQUIRE(it != DEPTHS.end()); const unsigned int depth_i = (it - DEPTHS.begin()); stringstream lines_file, motion_file, ref_file; @@ -124,59 +118,31 @@ validation(const char* depth, const char* motion) auto ref_data = read_tab_file(ref_file.str().c_str()); MoorDyn system = MoorDyn_Create(lines_file.str().c_str()); - if (!system) { - cerr << "Failure Creating the Mooring system" << endl; - return false; - } + REQUIRE(system); unsigned int n_dof; - if (MoorDyn_NCoupledDOF(system, &n_dof) != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - return false; - } - if (n_dof != 3) { - cerr << "3x1 = 3 DOFs were expected, but " << n_dof << "were reported" - << endl; - MoorDyn_Close(system); - return false; - } + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); - int err; double x[3], dx[3]; // Set the fairlead points, as they are in the config file std::fill(x, x + 3, 0.0); std::fill(dx, dx + 3, 0.0); - err = MoorDyn_Init(system, x, dx); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - cerr << "Failure during the mooring initialization: " << err << endl; - return false; - } + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); // Compute the static tension int num_lines = 1; float fh, fv, ah, av; - err = MoorDyn_GetFASTtens(system, &num_lines, &fh, &fv, &ah, &av); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - cerr << "Failure getting the initial tension: " << err << endl; - return false; - } + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); const double ffair0 = sqrt(fh * fh + fv * fv); const double ffair_ref0 = 1.e3 * STATIC_FAIR_TENSION[depth_i]; - cout << "Static tension on the fairlead = " << ffair0 << endl; - cout << " Reference value = " << ffair_ref0 << endl; const double fanch0 = sqrt(ah * ah + av * av); const double fanch_ref0 = 1.e3 * STATIC_ANCHOR_TENSION[depth_i]; - cout << "Static tension on the anchor = " << fanch0 << endl; - cout << " Reference value = " << fanch_ref0 << endl; const double efair0 = (ffair0 - ffair_ref0) / ffair_ref0; const double eanch0 = (fanch0 - fanch_ref0) / fanch_ref0; - if ((efair0 > MAX_STATIC_ERROR) || (eanch0 > MAX_STATIC_ERROR)) { - MoorDyn_Close(system); - cerr << "Too large error" << endl; - return false; - } + REQUIRE(efair0 <= MAX_STATIC_ERROR); + REQUIRE(eanch0 <= MAX_STATIC_ERROR); // Start integrating. The integration have a first chunk of initialization // motion to get something more periodic. In that chunk of the simulation @@ -198,22 +164,13 @@ validation(const char* depth, const char* motion) x[j] = motion_data[i][j + 1]; dx[j] = (motion_data[i + 1][j + 1] - x[j]) / dt; } - err = MoorDyn_Step(system, x, dx, f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - cerr << "Failure during the mooring step: " << err << endl; - return false; - } + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); if (t_ref < 0.0) continue; - err = MoorDyn_GetFASTtens(system, &num_lines, &fh, &fv, &ah, &av); - if (err != MOORDYN_SUCCESS) { - MoorDyn_Close(system); - cerr << "Failure getting the initial tension: " << err << endl; - return false; - } + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); const double ffair = sqrt(fh * fh + fv * fv) - ffair0; const double ffair_ref = 1.e3 * ref_data[i_ref][3] - ffair_ref0; const double fanch = sqrt(ah * ah + av * av) - fanch0; @@ -234,44 +191,20 @@ validation(const char* depth, const char* motion) i_ref++; } - err = MoorDyn_Close(system); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure closing Moordyn: " << err << endl; - return false; - } + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); - cout << "Maximum dynamic error in the fairlead = " << ef_value << endl; - cout << " at time = " << ef_time << endl; ef_value = ef_value / (2.0 * ef_ref); - if (ef_value > MAX_DYNAMIC_ERROR) { - cerr << ef_value << " is an excesively large error" << endl; - return false; - } - cout << "Maximum dynamic error in the anchor = " << ea_value << endl; - cout << " at time = " << ea_time << endl; + REQUIRE(ef_value <= MAX_DYNAMIC_ERROR); ea_value = ea_value / (2.0 * ea_ref); - /* For the time being we better ignore these errors - if (ea_value > MAX_DYNAMIC_ERROR) - { - cerr << ea_value << " is an excesively large error" << endl; - return false; - } - */ - - return true; + // For the time being we better ignore these errors + // REQUIRE(ea_value <= MAX_DYNAMIC_ERROR); } -/** @brief Runs all the test - * @return 0 if the tests have ran just fine, 1 otherwise - */ -int -main(int, char**) +TEST_CASE("Validation") { for (auto depth : DEPTHS) { for (auto motion : MOTIONS) { - if (!validation(depth.c_str(), motion.c_str())) - return 1; + validation(depth.c_str(), motion.c_str()); } } - return 0; } From a811fd00559d0c2ae1ada37e97f9fdacd8ef1411 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jan 2024 10:28:39 +0100 Subject: [PATCH 043/145] Show a renormalized error, which makes more sense --- source/MoorDyn2.cpp | 5 +++-- source/Time.cpp | 2 +- source/Time.hpp | 16 ++++++++++++++++ 3 files changed, 20 insertions(+), 3 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index f64de837..c8a8b97a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -404,10 +404,11 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } if (!skip_ic) { + auto n_states = t_integrator.NStates(); LOGMSG << "Remaining error after " << t << " s = " - << error << " m/s2" << endl; + << error / n_states << " m/s2" << endl; LOGMSG << "Best score at " << best_score_t - << " s = " << best_score << " m/s2" << endl; + << " s = " << best_score / n_states << " m/s2" << endl; } // restore drag coefficients to normal values and restart time counter of diff --git a/source/Time.cpp b/source/Time.cpp index a6309529..60befbc4 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -170,7 +170,7 @@ StationaryScheme::StationaryScheme(moordyn::Log* log, moordyn::WavesRef waves) #endif #ifndef STATIONARY_MAX_BOOSTING -#define STATIONARY_MAX_BOOSTING 10.0 +#define STATIONARY_MAX_BOOSTING 50.0 #endif #ifndef STATIONARY_MIN_BOOSTING diff --git a/source/Time.hpp b/source/Time.hpp index 25e905f3..3d322df7 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -785,6 +785,22 @@ class StationaryScheme : public TimeSchemeBase<2, 1> */ inline real Error() const { return _error; } + /** @brief Compute the number of state variables + * + * This can be used to renormalize the error, so it makes more sense to the + * final user + * @return The number of state variables + * @note Each entry on the states is considered a single variable, that is + * no matter if the state is a scalar, a vector or a quaternion, it is + * considered as a single entry + */ + inline unsigned int NStates() const { + unsigned int n = bodies.size() + rods.size() + points.size(); + for (unsigned int i = 0; i < lines.size(); i++) + n += r[0].lines[i].pos.size(); + return n; + } + private: /** The last computed acceleration module * @see DMoorDynStateDt::MakeStationary() From c9e03eb234f2ac8a596dacebe54e15b5e403f362 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jan 2024 16:45:25 +0100 Subject: [PATCH 044/145] Complex system local-euler test --- tests/Mooring/local_euler/complex_system.txt | 53 ++++++++++++++++++++ tests/local_euler.cpp | 34 +++++++++++++ 2 files changed, 87 insertions(+) create mode 100644 tests/Mooring/local_euler/complex_system.txt diff --git a/tests/Mooring/local_euler/complex_system.txt b/tests/Mooring/local_euler/complex_system.txt new file mode 100644 index 00000000..b08ada28 --- /dev/null +++ b/tests/Mooring/local_euler/complex_system.txt @@ -0,0 +1,53 @@ +Complex system where some minor parts excesively conditionate the time step + +Thus a local Euler shall result on heavy performance benefits +------------------------- LINE TYPES -------------------------------------------------- +LineType Diam MassDenInAir EA BA/-zeta EI Can Cat Cdn Cdt +(-) (m) (kg/m) (N) (Pa-s/-) (n-m^2) (-) (-) (-) (-) +cable 0.116 25 362e6 -1.0 1e2 1.0 0.0 1.1 0.008 +bouyancy 0.361 59 362e6 -1.0 1e2 1.0 0.469 2.617 0.345 +stiffner 0.19 25 362e6 -1.0 38e3 1.0 0.0 1.1 0.008 +nylon 0.116 25 5e5 -1.0 0.0 1.0 0.0 2.0 0.1 +---------------------- ROD TYPES ------------------------------------ +TypeName Diam Mass/m Cd Ca CdEnd CaEnd +(name) (m) (kg/m) (-) (-) (-) (-) +conn 0.116 25 1.1 1.0 1.1 1.0 +---------------------------- BODIES ----------------------------------------------------- +ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca +(#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) +1 Free 452.0 0 -313.0 0 0 0 29.5 0 0.098 0.014 0.5|0.5 1.0 +---------------------- RODS ---------------------------------------- +ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs +(#) (name) (#/key) (m) (m) (m) (m) (m) (m) (-) (-) +1 conn Free 455.5 0 -313.0 455.5 0 -313.0 0 - +2 conn Free 448.5 0 -313.0 448.5 0 -313.0 0 - +3 conn Free 375.0 0 -250.0 375.0 0 -250.0 0 - +4 conn Free 290.0 0 -215.0 290.0 0 -215.0 0 - +----------------------- POINTS ---------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed 600.0 0 -320.0 0 0 0 0 +2 Fixed 452.0 0 -320.0 0 0 0 0 +3 Body1 0.0 0 0.0 0 0 0 0 +4 Coupled 0.0 0 -63.6 0 0 0 0 +-------------------------- LINES ------------------------------------------------- +Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs +(-) (-) (-) (-) (m) (-) (-) +1 nylon 2 3 7.0 7 - +2 cable 1 R1A 147.0 15 - +3 stiffner R1B 3 3.12 2 - +4 stiffner 3 R2A 3.12 2 - +5 cable R2B R3A 107.0 11 - +6 bouyancy R3B R4A 80.0 8 - +7 cable R4B 4 340.0 34 - +-------------------------- SOLVER OPTIONS--------------------------------------------------- +2 writeLog - Write a log file +0.09 cfl - CFL to determine the simulation timestep +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +320 WtrDpth - water depth +50.0 TmaxIC - threshold for IC convergence +1e-16 threshIC - threshold for IC convergence +1 dtIC - Time lapse between convergence tests (s) +lEuler tScheme - Time integrator +--------------------------- need this line ------------------------------------------------- diff --git a/tests/local_euler.cpp b/tests/local_euler.cpp index cc44495e..4ac04f10 100644 --- a/tests/local_euler.cpp +++ b/tests/local_euler.cpp @@ -1,5 +1,6 @@ #include #include +#include #include "MoorDyn2.h" #include @@ -92,3 +93,36 @@ TEST_CASE("Hanging split line") REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); } + +TEST_CASE("Complex system performance test") +{ + MoorDyn system = MoorDyn_Create("Mooring/local_euler/complex_system.txt"); + REQUIRE(system); + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + auto point = MoorDyn_GetPoint(system, 4); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x) == MOORDYN_SUCCESS); + std::fill(dx, dx + 3, 0.0); + auto in_init = std::chrono::steady_clock::now(); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + auto out_init = std::chrono::steady_clock::now(); + auto dt_init = std::chrono::duration_cast< + std::chrono::duration>>( + out_init - in_init).count(); + + double f[6]; + double t = 0.0, dt = 50.0; + auto in_step = std::chrono::steady_clock::now(); + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + auto out_step = std::chrono::steady_clock::now(); + auto dt_step = std::chrono::duration_cast< + std::chrono::duration>>( + out_step - in_step).count(); + REQUIRE(dt_step < dt_init); + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} From bb3b339ba4214d83ac8f6b065e075624b6a1696b Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 13 Jan 2024 08:43:19 +0100 Subject: [PATCH 045/145] Slightly reduce the time step so it is stable when using ctest --- tests/Mooring/local_euler/complex_system.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/Mooring/local_euler/complex_system.txt b/tests/Mooring/local_euler/complex_system.txt index b08ada28..7828bb18 100644 --- a/tests/Mooring/local_euler/complex_system.txt +++ b/tests/Mooring/local_euler/complex_system.txt @@ -42,7 +42,7 @@ Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs 7 cable R4B 4 340.0 34 - -------------------------- SOLVER OPTIONS--------------------------------------------------- 2 writeLog - Write a log file -0.09 cfl - CFL to determine the simulation timestep +0.08 cfl - CFL to determine the simulation timestep 3.0e6 kb - bottom stiffness 3.0e5 cb - bottom damping 320 WtrDpth - water depth From 1fb94360effa78d29f45a92daf07a19d7dd5cdeb Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 13 Jan 2024 09:08:13 +0100 Subject: [PATCH 046/145] Base class for local-timestep integrators --- source/Time.cpp | 155 ++++++++++++++++++++++++------------------------ source/Time.hpp | 97 +++++++++++++++++++++--------- 2 files changed, 146 insertions(+), 106 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index 60befbc4..f3851f53 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -247,113 +247,112 @@ EulerScheme::Step(real& dt) TimeSchemeBase::Step(dt); } -LocalEulerScheme::LocalEulerScheme(moordyn::Log* log, moordyn::WavesRef waves) - : EulerScheme(log, waves) - , _initialized(false) -{ - name = "1st order Local-Timestep Euler"; -} - -void -LocalEulerScheme::Step(real& dt) -{ - if (!_initialized) { - LOGMSG << name << ":" << endl; - real dtM = ComputeDt(); - for (auto line : lines) { - const real dt_line = line->cfl2dt(cfl); - _dt0.lines.push_back(0.999 * dt_line); - _dt.lines.push_back(dt_line); - LOGMSG << "Line " << line->number << ": dt = " << dt_line - << " s (updated each " << std::ceil(dt_line / dtM) - << " timesteps)" << endl; - } - for (auto point : points) { - LOGMSG << "Point " << point->number << ": dt = " << dtM - << " s (updated each 1 timesteps)" << endl; - _dt0.points.push_back(0.0); - _dt.points.push_back(0.0); - } - for (auto rod : rods) { - LOGMSG << "Rod " << rod->number << ": dt = " << dtM - << " s (updated each 1 timesteps)" << endl; - _dt0.rods.push_back(0.0); - _dt.rods.push_back(0.0); - } - for (auto body : bodies) { - LOGMSG << "Body " << body->number << ": dt = " << dtM - << " s (updated each 1 timesteps)" << endl; - _dt0.bodies.push_back(0.0); - _dt.bodies.push_back(0.0); - } - _initialized = true; - } - SetCalcMask(dt); - Update(0.0, 0); - CalcStateDeriv(0); - r[0] = r[0] + rd[0] * dt; - t += dt; - Update(dt, 0); - TimeSchemeBase::Step(dt); -} - -real -LocalEulerScheme::ComputeDt() const -{ - real dt = std::numeric_limits::max(); - for (auto obj : lines) - dt = (std::min)(dt, obj->cfl2dt(cfl)); - for (auto obj : points) - dt = (std::min)(dt, obj->cfl2dt(cfl)); - for (auto obj : rods) - dt = (std::min)(dt, obj->cfl2dt(cfl)); - for (auto obj : bodies) - dt = (std::min)(dt, obj->cfl2dt(cfl)); - return dt; -} - +template void -LocalEulerScheme::SetCalcMask(real& dt) +LocalTimeSchemeBase::SetCalcMask(real& dt) { unsigned int i = 0; - for (i = 0; i < lines.size(); i++) { + for (i = 0; i < this->lines.size(); i++) { _dt.lines[i] += dt; if (_dt.lines[i] >= _dt0.lines[i]) { _dt.lines[i] = dt; - _calc_mask.lines[i] = true; + this->_calc_mask.lines[i] = true; } else { - _calc_mask.lines[i] = false; + this->_calc_mask.lines[i] = false; } } - for (i = 0; i < points.size(); i++) { + for (i = 0; i < this->points.size(); i++) { _dt.points[i] += dt; if (_dt.points[i] >= _dt0.points[i]) { _dt.points[i] = dt; - _calc_mask.points[i] = true; + this->_calc_mask.points[i] = true; } else { - _calc_mask.points[i] = false; + this->_calc_mask.points[i] = false; } } - for (i = 0; i < rods.size(); i++) { + for (i = 0; i < this->rods.size(); i++) { _dt.rods[i] += dt; if (_dt.rods[i] >= _dt0.rods[i]) { _dt.rods[i] = dt; - _calc_mask.rods[i] = true; + this->_calc_mask.rods[i] = true; } else { - _calc_mask.rods[i] = false; + this->_calc_mask.rods[i] = false; } } - for (i = 0; i < bodies.size(); i++) { + for (i = 0; i < this->bodies.size(); i++) { _dt.bodies[i] += dt; if (_dt.bodies[i] >= _dt0.bodies[i]) { _dt.bodies[i] = dt; - _calc_mask.bodies[i] = true; + this->_calc_mask.bodies[i] = true; } else { - _calc_mask.bodies[i] = false; + this->_calc_mask.bodies[i] = false; } } } +template +real +LocalTimeSchemeBase::ComputeDt() +{ + this->LOGMSG << this->name << ":" << endl; + real dt = std::numeric_limits::max(); + for (auto obj : this->lines) + dt = (std::min)(dt, obj->cfl2dt(this->cfl)); + for (auto obj : this->points) + dt = (std::min)(dt, obj->cfl2dt(this->cfl)); + for (auto obj : this->rods) + dt = (std::min)(dt, obj->cfl2dt(this->cfl)); + for (auto obj : this->bodies) + dt = (std::min)(dt, obj->cfl2dt(this->cfl)); + + for (auto line : this->lines) { + const real dt_line = line->cfl2dt(this->cfl); + _dt0.lines.push_back(0.999 * dt_line); + _dt.lines.push_back(dt_line); + this->LOGMSG << "Line " << line->number << ": dt = " << dt_line + << " s (updated each " << std::ceil(dt_line / dt) + << " timesteps)" << endl; + } + for (auto point : this->points) { + this->LOGMSG << "Point " << point->number << ": dt = " << dt + << " s (updated each 1 timesteps)" << endl; + _dt0.points.push_back(0.0); + _dt.points.push_back(0.0); + } + for (auto rod : this->rods) { + this->LOGMSG << "Rod " << rod->number << ": dt = " << dt + << " s (updated each 1 timesteps)" << endl; + _dt0.rods.push_back(0.0); + _dt.rods.push_back(0.0); + } + for (auto body : this->bodies) { + this->LOGMSG << "Body " << body->number << ": dt = " << dt + << " s (updated each 1 timesteps)" << endl; + _dt0.bodies.push_back(0.0); + _dt.bodies.push_back(0.0); + } + + return dt; +} + +LocalEulerScheme::LocalEulerScheme(moordyn::Log* log, moordyn::WavesRef waves) + : LocalTimeSchemeBase(log, waves) +{ + name = "1st order Local-Timestep Euler"; +} + +void +LocalEulerScheme::Step(real& dt) +{ + SetCalcMask(dt); + Update(0.0, 0); + CalcStateDeriv(0); + r[0] = r[0] + rd[0] * dt; + t += dt; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + HeunScheme::HeunScheme(moordyn::Log* log, moordyn::WavesRef waves) : TimeSchemeBase(log, waves) { diff --git a/source/Time.hpp b/source/Time.hpp index 3d322df7..0d20936b 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -565,7 +565,7 @@ class TimeSchemeBase : public TimeScheme /** @brief Resume the simulation from the stationary solution * @param state The stationary solution */ - void FromStationary(const StationaryScheme& state); + virtual void FromStationary(const StationaryScheme& state); /** @brief Produce the packed data to be saved * @@ -838,33 +838,53 @@ class EulerScheme : public TimeSchemeBase<1, 1> virtual void Step(real& dt); }; -/** @class LocalEulerScheme Time.hpp - * @brief A modification of the 1st order Euler's time scheme, which is - * considering different time steps for each instance. - * - * The local time step of each entity is computed according to the maximum CFL - * factor of all entities. Such local time step is indeed an integer times the - * time step provided to LocalEulerScheme::Step(). - * - * Thus, the derivatives recomputation is delayed until those time steps are - * fulfilled +/** @class TimeSchemeBase Time.hpp + * @brief A generic abstract integration scheme + * + * This class can be later overloaded to implement a plethora of time schemes */ -class LocalEulerScheme : public EulerScheme +template +class LocalTimeSchemeBase : public TimeSchemeBase { public: + /// @brief Destructor + virtual ~LocalTimeSchemeBase() {} + + /** @brief Create an initial state for all the entities + * @note Just the first state is written. None of the following states, nor + * the derivatives are initialized in any way. + * @note It is assumed that the coupled entities were already initialized + */ + inline void Init() + { + TimeSchemeBase::Init(); + ComputeDt(); + } + + /** @brief Resume the simulation from the stationary solution + * @param state The stationary solution + */ + inline void FromStationary(const StationaryScheme& state) + { + TimeSchemeBase::FromStationary(state); + ComputeDt(); + } + + protected: /** @brief Costructor * @param log Logging handler - * @param waves Waves instance + * @param waves The simulation waves object, needed so that we can tell it + * about substeps */ - LocalEulerScheme(moordyn::Log* log, WavesRef waves); - - /// @brief Destructor - ~LocalEulerScheme() {} + LocalTimeSchemeBase(moordyn::Log* log, moordyn::WavesRef waves) + : TimeSchemeBase(log, waves) + { + } - /** @brief Run a time step + /** @brief Set the calculation mask * @param dt Time step */ - virtual void Step(real& dt); + void SetCalcMask(real& dt); private: /** @brief Compute the model time step @@ -872,12 +892,7 @@ class LocalEulerScheme : public EulerScheme * This can be done since we know the TimeScheme::cfl factor * @return The model time step */ - real ComputeDt() const; - - /** @brief Set the calculation mask - * @param dt Time step - */ - void SetCalcMask(real& dt); + real ComputeDt(); /** @brief The timestep of each instance */ @@ -892,9 +907,6 @@ class LocalEulerScheme : public EulerScheme std::vector bodies; } deltat; - /// Do the time steps have been initialized - bool _initialized; - /// The timestep of each instance deltat _dt0; @@ -902,6 +914,35 @@ class LocalEulerScheme : public EulerScheme deltat _dt; }; +/** @class LocalEulerScheme Time.hpp + * @brief A modification of the 1st order Euler's time scheme, which is + * considering different time steps for each instance. + * + * The local time step of each entity is computed according to the maximum CFL + * factor of all entities. Such local time step is indeed an integer times the + * time step provided to LocalEulerScheme::Step(). + * + * Thus, the derivatives recomputation is delayed until those time steps are + * fulfilled + */ +class LocalEulerScheme : public LocalTimeSchemeBase<1, 1> +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + */ + LocalEulerScheme(moordyn::Log* log, WavesRef waves); + + /// @brief Destructor + ~LocalEulerScheme() {} + + /** @brief Run a time step + * @param dt Time step + */ + void Step(real& dt); +}; + /** @class HeunScheme Time.hpp From 16326996a85d251ae1679bcfb8dd0086771a5c2d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 13 Jan 2024 09:25:52 +0100 Subject: [PATCH 047/145] Non-tested local timestep Adam-Bashforth schemes --- source/Time.cpp | 28 +++++++++++++++++++--------- source/Time.hpp | 42 +++++++++++++++++++++++++++++++++++++++--- 2 files changed, 58 insertions(+), 12 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index f3851f53..556594fa 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -438,13 +438,16 @@ RK4Scheme::Step(real& dt) TimeSchemeBase::Step(dt); } -template -ABScheme::ABScheme(moordyn::Log* log, moordyn::WavesRef waves) - : TimeSchemeBase(log, waves) +template +ABScheme::ABScheme(moordyn::Log* log, moordyn::WavesRef waves) + : LocalTimeSchemeBase(log, waves) , n_steps(0) { stringstream s; - s << order << "th order Adam-Bashforth"; + s << order << "th order "; + if (local) + s << "Local-"; + s << "Adam-Bashforth"; name = s.str(); if (order > 4) { LOGWRN << name @@ -453,14 +456,15 @@ ABScheme::ABScheme(moordyn::Log* log, moordyn::WavesRef waves) } } -template +template void -ABScheme::Step(real& dt) +ABScheme::Step(real& dt) { Update(0.0, 0); shift(); // Get the new derivative + SetCalcMask(dt); CalcStateDeriv(0); // Apply different formulas depending on the number of derivatives available @@ -538,11 +542,17 @@ create_time_scheme(const std::string& name, } else if (str::lower(name) == "rk4") { out = new RK4Scheme(log, waves); } else if (str::lower(name) == "ab2") { - out = new ABScheme<2>(log, waves); + out = new ABScheme<2, false>(log, waves); } else if (str::lower(name) == "ab3") { - out = new ABScheme<3>(log, waves); + out = new ABScheme<3, false>(log, waves); } else if (str::lower(name) == "ab4") { - out = new ABScheme<4>(log, waves); + out = new ABScheme<4, false>(log, waves); + } else if (str::lower(name) == "lab2") { + out = new ABScheme<2, false>(log, waves); + } else if (str::lower(name) == "lab3") { + out = new ABScheme<3, false>(log, waves); + } else if (str::lower(name) == "lab4") { + out = new ABScheme<4, false>(log, waves); } else if (str::startswith(str::lower(name), "beuler")) { try { unsigned int iters = std::stoi(name.substr(6)); diff --git a/source/Time.hpp b/source/Time.hpp index 0d20936b..fca8d899 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1035,8 +1035,8 @@ class RK4Scheme : public TimeSchemeBase<5, 4> * Actually, the 1st order and the 2nd order are the same schemes than the * Euler's and Heun's ones */ -template -class ABScheme : public TimeSchemeBase<5, 1> +template +class ABScheme : public LocalTimeSchemeBase<5, 1> { public: /** @brief Costructor @@ -1091,12 +1091,48 @@ class ABScheme : public TimeSchemeBase<5, 1> /// The number of derivatives already available unsigned int n_steps; + /** @brief Shift the derivatives + * @param org Origin derivative that will be assigned to the @p org + 1 one + */ + inline void shift(unsigned int org) + { + const unsigned int dst = org + 1; + for (unsigned int i = 0; i < lines.size(); i++) { + if (!_calc_mask.lines[i]) + continue; + rd[dst].lines[i].vel = rd[org].lines[i].vel; + rd[dst].lines[i].acc = rd[org].lines[i].acc; + } + + for (unsigned int i = 0; i < points.size(); i++) { + if (!_calc_mask.points[i] && (points[i]->type == Point::FREE)) + continue; + rd[dst].points[i].vel = rd[org].points[i].vel; + rd[dst].points[i].acc = rd[org].points[i].acc; + } + + for (unsigned int i = 0; i < rods.size(); i++) { + if (!_calc_mask.rods[i] && ((rods[i]->type != Rod::FREE) || + (rods[i]->type != Rod::PINNED))) + continue; + rd[dst].rods[i].vel = rd[org].rods[i].vel; + rd[dst].rods[i].acc = rd[org].rods[i].acc; + } + + for (unsigned int i = 0; i < bodies.size(); i++) { + if (!_calc_mask.bodies[i] && (bodies[i]->type == Body::FREE)) + continue; + rd[dst].bodies[i].vel = rd[org].bodies[i].vel; + rd[dst].bodies[i].acc = rd[org].bodies[i].acc; + } + } + /** @brief Shift the derivatives */ inline void shift() { for (unsigned int i = 0; i < rd.size() - 1; i++) - rd[i + 1] = rd[i]; + shift(i); } }; From cf6283129252e9d8abd4d56295caf9bad9571cac Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sat, 13 Jan 2024 14:53:51 +0100 Subject: [PATCH 048/145] Adams-Bashforths were not actually working as themselves --- source/Time.cpp | 4 +++- source/Time.hpp | 2 +- tests/time_schemes.cpp | 6 +++--- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index 556594fa..241fe7d6 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -464,7 +464,8 @@ ABScheme::Step(real& dt) shift(); // Get the new derivative - SetCalcMask(dt); + if (local && (n_steps == order)) + SetCalcMask(dt); CalcStateDeriv(0); // Apply different formulas depending on the number of derivatives available @@ -490,6 +491,7 @@ ABScheme::Step(real& dt) rd[3] * (dt * 637.0 / 360.0) + rd[4] * (dt * 251.0 / 720.0); } + n_steps = (std::min)(n_steps + 1, order); t += dt; Update(dt, 0); TimeSchemeBase::Step(dt); diff --git a/source/Time.hpp b/source/Time.hpp index fca8d899..67b366d5 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1036,7 +1036,7 @@ class RK4Scheme : public TimeSchemeBase<5, 4> * Euler's and Heun's ones */ template -class ABScheme : public LocalTimeSchemeBase<5, 1> +class ABScheme : public LocalTimeSchemeBase<1, 5> { public: /** @brief Costructor diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index f32e70a7..f9095e34 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -69,9 +69,9 @@ static std::vector dts({ "1.5E-4", "1.8E-4", "2.6E-4", "4.9E-4", - "1.7E-4", - "1.7E-4", - "1.7E-4", + "1.5E-4", + "1.1E-4", + "1.0E-4", "1.8E-4", "1.8E-4", "1.9E-4", From a5ec183fbd21b33fffa4287e2239480a61a6d5d8 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Sun, 14 Jan 2024 17:21:24 +0100 Subject: [PATCH 049/145] Added the new local-timestep schemes to the docs --- docs/inputs.rst | 10 +++++++--- source/Time.hpp | 2 -- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index c3038297..7bf0cdea 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -558,9 +558,13 @@ The list of possible options is: 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 or the OpenFAST time step. - - 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 + - tScheme (RK2): The time integrator. It should be one of + Euler, LEuler, Heun, RK2, RK4, AB2, AB3, AB4, LAB2, LAB3, LAB4, + BEuler2, BEuler3, BEuler4, BEuler5, Midpoint2, Midpoint3, Midpoint4, + Midpoint5. + RK stands for Runge-Kutta while AB stands for Adams-Bashforth. The + integrators with a L prefix are considering different time steps for each + object on the simulation, which might result on some performance benefits - 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. diff --git a/source/Time.hpp b/source/Time.hpp index 67b366d5..824b01cd 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -943,8 +943,6 @@ class LocalEulerScheme : public LocalTimeSchemeBase<1, 1> void Step(real& dt); }; - - /** @class HeunScheme Time.hpp * @brief Quasi 2nd order Heun's time scheme * From b3bb9de5ae762630edfcd833f2e7d75249d29b6a Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 15 Jan 2024 15:07:03 +0100 Subject: [PATCH 050/145] Windows... --- source/Time.cpp | 2 +- source/Util/CFL.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index 241fe7d6..662b16d6 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -295,7 +295,7 @@ real LocalTimeSchemeBase::ComputeDt() { this->LOGMSG << this->name << ":" << endl; - real dt = std::numeric_limits::max(); + real dt = (std::numeric_limits::max)(); for (auto obj : this->lines) dt = (std::min)(dt, obj->cfl2dt(this->cfl)); for (auto obj : this->points) diff --git a/source/Util/CFL.hpp b/source/Util/CFL.hpp index fb19f0dc..5a7b3e6d 100644 --- a/source/Util/CFL.hpp +++ b/source/Util/CFL.hpp @@ -58,7 +58,7 @@ class CFL public: /** @brief Constructor */ - CFL() : _l(std::numeric_limits::max()) {}; + CFL() : _l((std::numeric_limits::max)()) {}; /** @brief Destructor */ @@ -68,7 +68,7 @@ class CFL * @param cfl CFL factor * @return The timestep */ - virtual inline real cfl2dt(const real cfl) const { return std::numeric_limits::max(); } + virtual inline real cfl2dt(const real cfl) const { return (std::numeric_limits::max)(); } /** @brief Get the CFL factor from a timestep * @param dt Timestep From dc5710cebc06c40af1a83ef02928acecdb28874e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 15 Jan 2024 15:12:24 +0100 Subject: [PATCH 051/145] More Windows... --- source/MoorDyn2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index c8a8b97a..b9b43f5b 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -87,7 +87,7 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) , ICTmax(120.0) , ICthresh(0.001) , WaveKinTemp(waves::WAVES_NONE) - , dtM0(std::numeric_limits::max()) + , dtM0((std::numeric_limits::max)()) , cfl(0.5) , dtOut(0.0) , _t_integrator(NULL) From 380192bf43ac44612837acb6cd86bb7a87143da9 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 6 Feb 2024 14:19:13 +0100 Subject: [PATCH 052/145] Newmark implicit scheme (ACA) --- source/State.cpp | 140 +++++++++++++++++++++++++++++++++ source/State.hpp | 66 ++++++++++++++++ source/Time.cpp | 82 +++++++++++++++++++ source/Time.hpp | 51 ++++++++++++ tests/Mooring/time_schemes.txt | 6 +- tests/time_schemes.cpp | 10 ++- 6 files changed, 350 insertions(+), 5 deletions(-) diff --git a/source/State.cpp b/source/State.cpp index bc67ba57..f8f20434 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -439,6 +439,100 @@ real StateVarDeriv>::MakeStationary(const real &dt) return ret; } +template<> +StateVarDeriv +StateVarDeriv::Newmark( + const StateVarDeriv& visitor, const real& dt, + real gamma, real beta) +{ + StateVarDeriv ret; + const vec acc_gamma = (1 - gamma) * acc + gamma * visitor.acc; + const vec acc_beta = (0.5 - beta) * acc + beta * visitor.acc; + ret.vel = vel + dt * acc_beta; + ret.acc = acc_gamma; + return ret; +} + +template<> +StateVarDeriv +StateVarDeriv::Newmark( + const StateVarDeriv& visitor, const real& dt, + real gamma, real beta) +{ + StateVarDeriv ret; + const vec6 acc_gamma = (1 - gamma) * acc + gamma * visitor.acc; + const vec6 acc_beta = (0.5 - beta) * acc + beta * visitor.acc; + ret.vel = vel + dt * acc_beta; + ret.acc = acc_gamma; + return ret; +} + +template<> +StateVarDeriv +StateVarDeriv::Newmark( + const StateVarDeriv& visitor, const real& dt, + real gamma, real beta) +{ + StateVarDeriv ret; + const vec6 acc_gamma = (1 - gamma) * acc + gamma * visitor.acc; + const vec6 acc_beta = (0.5 - beta) * acc + beta * visitor.acc; + ret.vel = vel + XYZQuat::fromVec6(dt * acc_beta); + ret.acc = acc_gamma; + return ret; +} + +template<> +StateVarDeriv> +StateVarDeriv>::Newmark( + const StateVarDeriv>& visitor, const real& dt, + real gamma, real beta) +{ + StateVarDeriv> ret; + ret.vel.reserve(vel.size()); + ret.acc.reserve(acc.size()); + for (unsigned int i = 0; i < vel.size(); i++) { + const vec acc_gamma = (1 - gamma) * acc[i] + gamma * visitor.acc[i]; + const vec acc_beta = (0.5 - beta) * acc[i] + beta * visitor.acc[i]; + ret.vel.push_back(vel[i] + dt * acc_beta); + ret.acc.push_back(acc_gamma); + } + return ret; +} + +template<> +void +StateVarDeriv::Mix(const StateVarDeriv& rhs, const real& f) +{ + vel = vel * (1.0 - f) + rhs.vel * f; + acc = acc * (1.0 - f) + rhs.acc * f; +} + +template<> +void +StateVarDeriv::Mix(const StateVarDeriv& rhs, const real& f) +{ + vel = vel * (1.0 - f) + rhs.vel * f; + acc = acc * (1.0 - f) + rhs.acc * f; +} + +template<> +void +StateVarDeriv::Mix(const StateVarDeriv& rhs, const real& f) +{ + vel = vel * (1.0 - f) + rhs.vel * f; + acc = acc * (1.0 - f) + rhs.acc * f; +} + +template<> +void +StateVarDeriv>::Mix(const StateVarDeriv>& rhs, const real& f) +{ + for (unsigned int i = 0; i < vel.size(); i++) { + vel[i] = vel[i] * (1.0 - f) + rhs.vel[i] * f; + acc[i] = acc[i] * (1.0 - f) + rhs.acc[i] * f; + } +} + string MoorDynState::AsString() const { @@ -699,4 +793,50 @@ DMoorDynStateDt::MakeStationary(const real &dt) return ret; } +DMoorDynStateDt +DMoorDynStateDt::Newmark(const DMoorDynStateDt& rhs, + const real& dt, + real gamma, + real beta) +{ + DMoorDynStateDt out; + + if (lines.size() != rhs.lines.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.lines.reserve(lines.size()); + for (unsigned int i = 0; i < lines.size(); i++) + out.lines.push_back(lines[i].Newmark(rhs.lines[i], dt, gamma, beta)); + if (points.size() != rhs.points.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.points.reserve(points.size()); + for (unsigned int i = 0; i < points.size(); i++) + out.points.push_back(points[i].Newmark(rhs.points[i], dt, gamma, beta)); + if (rods.size() != rhs.rods.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.rods.reserve(rods.size()); + for (unsigned int i = 0; i < rods.size(); i++) + out.rods.push_back(rods[i].Newmark(rhs.rods[i], dt, gamma, beta)); + if (bodies.size() != rhs.bodies.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.bodies.reserve(bodies.size()); + for (unsigned int i = 0; i < bodies.size(); i++) + out.bodies.push_back(bodies[i].Newmark(rhs.bodies[i], dt, gamma, beta)); + + return out; +} + +void +DMoorDynStateDt::Mix(const DMoorDynStateDt& visitor, const real& f) +{ + real ret = 0.0; + for (unsigned int i = 0; i < lines.size(); i++) + lines[i].Mix(visitor.lines[i], f); + for (unsigned int i = 0; i < points.size(); i++) + points[i].Mix(visitor.points[i], f); + for (unsigned int i = 0; i < rods.size(); i++) + rods[i].Mix(visitor.rods[i], f); + for (unsigned int i = 0; i < bodies.size(); i++) + bodies[i].Mix(visitor.bodies[i], f); +} + } // ::moordyn diff --git a/source/State.hpp b/source/State.hpp index 056c6841..8c2bdf75 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -169,6 +169,39 @@ class StateVarDeriv * of lists of accelerations */ real MakeStationary(const real &dt); + + /** @brief Carry out a Newmark step + * + * The resulting state rate of change will have the following velocity + * + * \f[ u(t_{n+1}) = u(t_{n}) + \Delta t ( + * (1/2 - \beta) \dot{u(t_{n})} + + * \beta \dot{u(t_{n+1})}) \f] + * + * and the following acceleration + * + * \f[ \dot{u(t_{n+1})} = (1 - \gamma) \dot{u(t_{n})} + + * \gamma \dot{u(t_{n+1})}) \f] + * + * @param visitor The acceleration at the next time step + * @param dt Time step. + * @param gamma The Newmark gamma factor. + * @param beta Time Newmark beta factor. + */ + StateVarDeriv Newmark(const StateVarDeriv& visitor, + const real& dt, + real gamma = 0.5, + real beta = 0.25); + + /** @brief Mix this state variation rate with another one + * + * This can be used as a relaxation method when looking for stationary + * solutions + * @param visitor The other state variation rate + * @param f The mix factor. If 0.0, the state is not altered at all. If 1.0 + * the state is completely replaced by the @p visitor + */ + void Mix(const StateVarDeriv& visitor, const real& f); }; /// The state variables for lines @@ -320,6 +353,39 @@ class DMoorDynStateDt * @return The sum of the linear acceleration norms */ real MakeStationary(const real &dt); + + /** @brief Carry out a Newmark step + * + * The resulting state rate of change will have the following velocity + * + * \f[ u(t_{n+1}) = u(t_{n}) + \Delta t ( + * (1/2 - \beta) \dot{u(t_{n})} + + * \beta \dot{u(t_{n+1})}) \f] + * + * and the following acceleration + * + * \f[ \dot{u(t_{n+1})} = (1 - \gamma) \dot{u(t_{n})} + + * \gamma \dot{u(t_{n+1})}) \f] + * + * @param visitor The acceleration at the next time step + * @param dt Time step. + * @param gamma The Newmark gamma factor. + * @param beta Time Newmark beta factor. + */ + DMoorDynStateDt Newmark(const DMoorDynStateDt& visitor, + const real& dt, + real gamma = 0.5, + real beta = 0.25); + + /** @brief Mix this state variation rate with another one + * + * This can be used as a relaxation method when looking for stationary + * solutions + * @param visitor The other state variation rate + * @param f The mix factor. If 0.0, the state is not altered at all. If 1.0 + * the state is completely replaced by the @p visitor + */ + void Mix(const DMoorDynStateDt& visitor, const real& f); }; } // ::moordyn diff --git a/source/Time.cpp b/source/Time.cpp index 662b16d6..762a984f 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -527,6 +527,78 @@ ImplicitEulerScheme::Step(real& dt) TimeSchemeBase::Step(dt); } +ImplicitNewmarkScheme::ImplicitNewmarkScheme(moordyn::Log* log, + moordyn::WavesRef waves, + unsigned int iters, + real gamma, + real beta) + : TimeSchemeBase(log, waves) + , _iters(iters) + , _gamma(gamma) + , _beta(beta) +{ + stringstream s; + s << "gamma=" << gamma << ",beta=" << beta << " implicit Newmark (" + << iters << " iterations)"; + name = s.str(); +} + +void +ImplicitNewmarkScheme::Step(real& dt) +{ + // Initialize the velocity and acceleration for the next time step as + // the ones from the current time step + rd[1] = rd[0]; + + t += dt; + rd[2] = rd[0]; // We use rd[2] just as a tmp storage to compute relaxation + for (unsigned int i = 0; i < _iters; i++) { + // At the time of computing r acts as an input, and rd as an output. + // Thus we just need to apply the Newmark scheme on r[1] and store + // the new rates of change on rd[1] + r[1] = r[0] + rd[0].Newmark(rd[1], dt, _gamma, _beta) * dt; + Update(dt, 1); + CalcStateDeriv(1); + + if (i < _iters - 1) { + // We cannot relax the last step + const real relax = Relax(i); + rd[1].Mix(rd[2], relax); + rd[2] = rd[1]; + } + } + + // Apply + r[1] = r[0] + rd[0].Newmark(rd[1], dt, _gamma, _beta) * dt; + r[0] = r[1]; + rd[0] = rd[1]; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + +#ifndef INEWMARK_RELAX_INIT +#define INEWMARK_RELAX_INIT 0.95 +#endif + +#ifndef INEWMARK_RELAX_POW +#define INEWMARK_RELAX_POW 3 +#endif + +#ifndef INEWMARK_RELAX_CFL +#define INEWMARK_RELAX_CFL 2.0 +#endif + +real +ImplicitNewmarkScheme::Relax(const unsigned int& iter) +{ + const real f = (real)iter / _iters; + const real relax = INEWMARK_RELAX_INIT * (1 - pow(f, INEWMARK_RELAX_POW)); + // The relax factor shall be bounded by the CFL + const real relax_cfl = (std::min)(INEWMARK_RELAX_INIT, + INEWMARK_RELAX_CFL * GetCFL()); + return (std::max)(relax, relax_cfl); +} + TimeScheme* create_time_scheme(const std::string& name, moordyn::Log* log, @@ -573,6 +645,16 @@ create_time_scheme(const std::string& name, s << "Invalid Midpoint name format '" << name << "'"; throw moordyn::invalid_value_error(s.str().c_str()); } + } else if (str::startswith(str::lower(name), "aca")) { + try { + unsigned int iters = std::stoi(name.substr(3)); + out = new ImplicitNewmarkScheme(log, waves, iters, 0.5, 0.25); + } catch (std::invalid_argument) { + stringstream s; + s << "Invalid Average Constant Acceleration name format '" + << name << "'"; + throw moordyn::invalid_value_error(s.str().c_str()); + } } else { stringstream s; s << "Unknown time scheme '" << name << "'"; diff --git a/source/Time.hpp b/source/Time.hpp index 824b01cd..b12abd5e 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1173,6 +1173,57 @@ class ImplicitEulerScheme : public TimeSchemeBase<2, 1> real _dt_factor; }; +/** @class ImplicitNewmarkScheme Time.hpp + * @brief Implicit Newmark Scheme + * + * The implicit Newmark scheme is quite popular because is able to produce + * unconditionally stable time integrators for dynamic response of structures + * and solids, specifically on its Average Constant Acceleration incarnation + * @see https://en.wikipedia.org/wiki/Newmark-beta_method + */ +class ImplicitNewmarkScheme : public TimeSchemeBase<2, 3> +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + * @param gamma The gamma factor + * @param beta The beta factor + */ + ImplicitNewmarkScheme(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10, + real gamma = 0.5, + real beta = 0.25); + + /// @brief Destructor + ~ImplicitNewmarkScheme() {} + + /** @brief Run a time step + * + * This function is the one that must be specialized on each time scheme + * @param dt Time step + */ + virtual void Step(real& dt); + + private: + /** @brief Compute the relaxation factor + * + * This method is responsible of avoiding overshooting when computing the + * derivatives + * @param iter The current iteration + */ + real Relax(const unsigned int& iter); + + /// The number of iterations + unsigned int _iters; + /// Alpha factor + real _gamma; + /// Beta factor + real _beta; +}; + /** @brief Create a time scheme * @param name The time scheme name, one of the following: * "Euler", "Heun", "RK2", "RK4", "AB3", "AB4" diff --git a/tests/Mooring/time_schemes.txt b/tests/Mooring/time_schemes.txt index ca66cf64..cef4aea0 100644 --- a/tests/Mooring/time_schemes.txt +++ b/tests/Mooring/time_schemes.txt @@ -18,10 +18,10 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 2 writeLog Write a log file @DT@ dtM time step to use in mooring integration (s) @TSCHEME@ tScheme The time integration Scheme (-) +1.0 cfl CFL to determine the simulation timestep 1000.0 WtrDnsty water density (kg/m^3) 500 WtrDpth water depth (m) -1E-2 dtIC time interval for analyzing convergence during IC gen (s) +1.0 dtIC time interval for analyzing convergence during IC gen (s) 10.0 TmaxIC max time for ic gen (s) -1.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) -0.01 threshIC threshold for IC convergence (-) +1e-4 threshIC threshold for IC convergence (-) ------------------------- need this line -------------------------------------- diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index f9095e34..f9e1cf2c 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -64,7 +64,10 @@ static std::vector schemes({ "Euler", "Midpoint2", "Midpoint3", "Midpoint4", - "Midpoint5" }); + "Midpoint5", + "ACA5", + "ACA10", + "ACA15" }); static std::vector dts({ "1.5E-4", "1.8E-4", "2.6E-4", @@ -79,7 +82,10 @@ static std::vector dts({ "1.5E-4", "2.8E-4", "2.8E-4", "2.8E-4", - "2.8E-5" }); + "2.8E-4", + "2.0E-4", + "2.0E-3", + "2.4E-3" }); using namespace std; From ed9a666587d3495a86e15f96552a5b3840a0e4aa Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 19 Feb 2024 14:57:36 +0100 Subject: [PATCH 053/145] Optimized Midpoint and Backward Euler schemes --- docs/inputs.rst | 7 +- docs/relaxation_001.png | Bin 0 -> 31944 bytes docs/relaxation_002.png | Bin 0 -> 32128 bytes docs/relaxation_003.png | Bin 0 -> 37707 bytes docs/relaxation_004.png | Bin 0 -> 40782 bytes docs/relaxation_005.png | Bin 0 -> 17845 bytes docs/rsc/backward_euler.py | 120 +++++++++++++ docs/rsc/midpoint.py | 107 +++++++++++ docs/tschemes.rst | 314 +++++++++++++++++++++++++++++++++ source/MoorDyn2.cpp | 3 +- source/Time.cpp | 34 +++- source/Time.hpp | 144 ++++++++++++++- tests/Mooring/time_schemes.txt | 2 +- tests/time_schemes.cpp | 32 ++-- 14 files changed, 734 insertions(+), 29 deletions(-) create mode 100644 docs/relaxation_001.png create mode 100644 docs/relaxation_002.png create mode 100644 docs/relaxation_003.png create mode 100644 docs/relaxation_004.png create mode 100644 docs/relaxation_005.png create mode 100644 docs/rsc/backward_euler.py create mode 100644 docs/rsc/midpoint.py create mode 100644 docs/tschemes.rst diff --git a/docs/inputs.rst b/docs/inputs.rst index 7bf0cdea..478a6411 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -560,11 +560,8 @@ The list of possible options is: :ref:`driver file ` dtC value or the OpenFAST time step. - tScheme (RK2): The time integrator. It should be one of Euler, LEuler, Heun, RK2, RK4, AB2, AB3, AB4, LAB2, LAB3, LAB4, - BEuler2, BEuler3, BEuler4, BEuler5, Midpoint2, Midpoint3, Midpoint4, - Midpoint5. - RK stands for Runge-Kutta while AB stands for Adams-Bashforth. The - integrators with a L prefix are considering different time steps for each - object on the simulation, which might result on some performance benefits + BEuler\ *N*, Midpoint\ *N*, ACA\ *N*. Look at the + :ref:`time schemes documentation ` to learn more about this. - 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. diff --git a/docs/relaxation_001.png b/docs/relaxation_001.png new file mode 100644 index 0000000000000000000000000000000000000000..2a8d4b5b6d9f24734f657ec34936517fe91180a8 GIT binary patch literal 31944 zcmeFZWms10*FE}>qO^b@9U>iqbg86DDoBH%lyrAVgMf&187L?%-6bIi2uOEHH_~zD z+WYsu|2$vMr?aoiYi~C^>$%sx<~`?_V~n}NRF&oNuTWk=p-}ku6=WWvQ0RUr6xuWn zHvAuf-tl?(mxz8oMl>!FB+8_rIoMM#Qpa8fZA&%DIlephxoPc1rTM2GCoRBfD8DFqu* zgd+b;*cG~<7~!A33UyRC{Ey-5WPZrsUF5LdA-|BOhQ`0g#K$wg8Bcy~8IK}l($SDwyfw8SD;w>;mUiHw+-xQIK}h$6T&Alvq4 zY*@6^dE%{St?DC-G4ixC{VGx>Q+3|)Wj|tBcGt_NzImVQ%Y{CIulX*T+=cVh+Ip%k zt)imB!MZtw&}^|gEwRg#LzWqKr*A7Ym&UL3xvA;w=B8nO*VI(T?5y#(Z{Kk6@Nx^4 zjEoq9f`a1PK7IO>D&cv}(9lrv=Hq}iPWa?dH!q%pqvK_`*~Ui6wx+c*6ec^VwMp@e z2ASjTpRQ-!sUrBa2@sFBYe-m>iLPEXUgynivcYZe^F#6R^LLh}i8x}ju&{V}dvi?O zWMJ?=Jap@v!zJe?x^}JAALEkwM3r+uE5`tTN|)7eq5pg7klD30t984zWCtVNw}fNw z^|TD1Jh@h`C*&vn$JSr9rluyB=FPycH5vsKRi{~o_mh0VZ|YGcD)P`gi=K5W~2;MnyUHD2k+QtR>egJyvN>U&#Te~u>4`SDOa`sAmGjnxCJ4KD0Oz8u~X+r!@R=mNGFlwc^EU zezA+N;9abz80_rqu+V_hQ!mSqzP0PYckkRmu_&ji78#kCR4P1t*!-MtW@hH@)2H;@ z+}wi%N-}Gz_wQfcUF^B^^v};EVKP!}5yr81=!O1o_2$;kd2+asjEv#HaISBp=n}*=F+80scC5< zKBpDTQjCm|ExdT?zUS^JTDNI52&IZd&)yET5p3_rg1lr*#+!TBiHI#n3XL$Pyms+7 zHZ~Mf1o2UGACx=M|4F`migA(WN{PJwg4Uxbc2s9Jij59fyIAi|n+~_7a}rsf(J% zXJo`h!Q=*RXns;>%PJ7QTB8qlZ=>U|qdr}I|Nechc5(2-1a9roD_5>))p`gR85!Z9 z9|s%RZPp&}xvUL8$msd;!)UnB2onoyyGv+lYbB@P+tWt$cuws{IYS~YYZSL`-8wy} zzc4vJJ@UFZJMcO`TEwFfef#Bc)}T2Zzv<8Exo9cVu4DnLk#9jYHR3jv3-Q?c5q2m0 z>#u0U;_c^Jw;{Xn*^CR@)StQ3ogc5}*qm(oUZlKwh1b~=DKt6!)IK~^tFtlS($Q8k zA)4FaOh~6h7Ta{E6Ir49uWDD@C~A==c{=a!85gH!D9Pg`rhC%TVd3E~wuTIA+-{+y z&h|*Aybtt)7B%y9WbfWZzb59+T=dbveD`w}S|aqX7X zFmGqk%^NogE&6Xllz(3t$jO-)92!dS^YgXY)zH6kU zGUYZC!)4aGabxfmj+)-lg0_=-3;Sc`wmb*PC@3HW`vRS>XeE-%tjGB5rtfqbwlOkx z-ItRKUf3@vHtWgXs_90nQDpLqWR;T2fcv|Byc*Bdp-TlhjfsJw(P3kFFi%&z*c6{i z$R^jN`rSKvm(59iYdTxoO`VpVhe=6E3*C#Tt%HMdaY$sLW3dx=g*()u&Vve}R^&vYu)bMOY6OUTBuxa5273l>nTv zy3a$|Ylk_WN>Wl%rroI)?&Dc1blquUZKp@O8mMrEV*B$`_jqpoE9#QRmy*%BKcW{B zySur)PDn6|8_J7-;7Pbd>xO#QO0Jdp=~M5ghY2rE#@!dwY9QR5!!Og*)4yvnA4=jk zL$SYlrSVBRgdkDzCM>EA0Kp2iyqX#@Y!rvk6}LY>uVdp;s4lqlNE}eZAHC9(^P&3l z762Guy(T)M>OZ#`eD=LKulYNuTRJKy^F5wRzv}JyxL%d>YHNE86Nd{ccPlHW)oFv( z>nja%&-s#GNRU}7)gN`)va(ls^{*ux{Q5=lxS^=1Nc?!|BPki#%(tzTI&SWq)Pdoe_cdtg#@>@rs&}C&E$a)lo2|g!$ya>?GC+F zQadXv&L2O1EXeH*78n{@_i88o{;iIVfnix185){b<+OYio*MczfSxa2Pv&Q3@m75Q zWU)O$W7TkQa(a$npo@aA<3w~xrzIkHcX!B>4$FPa5ATkAdPuIPr&lo-C6>rQH4S;?lN~G>UQP8EXSQWl zBgV_Sqm~8R+ii5ZgZy5LX|8rIE}sDc2n!2ujhJN=xosPFifS`5Dou36afmqn!GrRt z!ObLR!~Lo1oJW=^-hUSo8-2I_(s> zp}D)$$ul=U{~Z!+H^kiG-vZw*Sc|0|?@)^$8ip2}R{)*DD&pIi>!YR5;LqObP){EV z2S)_tgoLq;B(wAxC~Lx^qJ2frQW6SXk5&9&g**6#y{jlD>@#7LM_7 zg*{XGgbS5?6!jOoxcu9>hJWs5V6F0{blqTPzU46A{KjIo4^8Uv@>{-Y^=E;%#pxMq{du^XYo{c!A{VN8&rU02(y5c6ORNJ3B{> z0M?N~GHr$aA*{IAvGP;V*UX4JoVN+s0cR^c8hP}@b;4P*bTvyS8&zWd1na4>@rQ*6 z&G6um)NFmBk@Ez;i%?u#98mjwy5|Oim{@hp2WT2%sz$3_c`|&C*`Q}YqTH0qg62+y z=`MG!es%nHe$%btXVEdq$sLdrC~g^JLJ^7EpZaEk3tvc1a#QgsfDkW0E?$re6;p+a zVwlL`qND89bA7hHC%U2#bH$Oj(an3Ut~4O&)~E^drgEx+lhbWDri{05mvmrx*B`HN zzM7oej>Po<NYV=$rA>FX5Ry2_3rHcrmWEi<7QNYQBA zJR25*DV=`>Qo5jSSXi(@|Kcoh`^)=pe}8sPIu@lH{`pW+LfXvBo6?2v5kmS!Z)Eec z;d#`X)-1i>83_g+VbBEG)NIRn?5}Ch9sIt)U_Pg%Uk_}tTxY*u)&cC0Y2)h*Wnv40*#SV1Mxtbfs55&( z{kbR-4Yq)|0$O;Vwc?f8Omx7$-+`xG?Xv#$*CN0iGiX)UhKmBAvh!Q?-T17M5mjDZ z&b*i+Xl)D!e{G~V1nNAJFXw;6TGI4DH|Mrdxp)X*uuDbiOh#3e2zoUpNy&6c?_)jZ z6UW8wTaZm9PuBQRa*>oRvn>&TRZQ{#LBS^N^gZN(Sh@@FK)b?@Apjfy>$i*6NU9@9 zTKez3A!wa8#w%M3EGe)nD=XdH-HrH?SXo&cCMMDV8VY^sx#wskm~vlP*%ZL4PJLg; z+lb>^kn*qK;w}&5kYB!hS;MDCvvoU8Q(?{+Lv9Gd8T}XFX?gj!D<8ehx>LXKvTK=6 z*0=+1_~o#mdayCEy|?%L*SovoyFd9cv9X^Fw+;-DX=)B#S?})dCX@Wh%*+f`8giJO zow=y5HT*XKPwi?KE;uJhGg6`VD<9BxVIgm)y+9^{0bt*gH|tLFn=BXR=Xt#j?Sctt zIsk|?Lu*VSrdm^bM?`{wrItf{ zj(-%dl8{^%wxjQi=bHPIVr#lNSsNG>q*0|ba#8~j!r`FRs{gZ6-j2Q?*2S*x#m(3+ zeLZ2fX=^Xaq${(l0m{SY{W}BrpdBn7Yix-~Mz8yzP3i}Kg>L6{YU)qx@(EK56=mf= zgSxhPPASk?rlxk#`HURhH(BHz$$`LjoNp&a5c@gwIT%||y@@F)AE>LV2h^WKbf6tV zZ*&Nu%PwC3Vt^g#P%0gmq2+g49gI9XIoO3>IOKERZdgUy1Y zILp$#-G~n;1jdsadNuZadYB|+Yfw4{`Mj)Ao<&w>Wfq{oEF6Fm+o|-a^ZoMDsk=7Z z*ph$gv`BtC1%J+GgrF~<^oSticv5IPB?*x6zK%|^Ne2&5BGnsJoqfL0+j;Hv$^#5} z%OoFF=)C&mvr>v2fF0Kko7$UPwSv+YN#lIj)!JybAk>3zJFj1M+WcYs(tv zS~xz~jE;_0i6du4gPd~ob@Q3VL+Utv(!ZT^1sfl-Ggjg70QNftKEt#*7+-Uphp~?$ zJUm>h@F^M!Qik0GH+w%H@3k&tOrocdE}om2@x!s>MIUvq<4VZu&vp~hK`o> z+O?fY&&};s!;9odDj`0%t?3ufh>0!CeNV=wgxz;;z?LjvJH3#_y{mgW1)b<=$6GeV zB)(65i%;_PwBN7u_#WZ<9(5X03V;3lqo*et;wuTdluOOL6-R$kws&`{S6twqWXKgrv^}w$3PHwJUP5e;psHMxw?=RzToghAekD30IU;x;d z@rj0x&Wr2sk^mQeTAVYCGcw2AGE3G#Gv5^#=Z;Y0S_Ct@Y2syr+}aQtb{7jgXrIESkaO!jZHuDWTOT9$ zLozJTjl54A{MgH@6sjt%SHqtF9WbK`uO#J+@2s3h}10h&uXPanT#~T5kAc;C!@|g7!A?EQ5vjkOA0dVt^rBQ5Rra1Ip&SfG1Q<|D{?xXUqrLbbjw>XdC#AGbVK&Vy7aXoF1P zj^c3@plf}qZT#oOlRTXk=ukK{7ogKg9y0LEi{E^(uDAYyHQUWd9U9$Y(=J8{2^v>d z*D9Cw4ylVH6(G<@-W7$1s%Nc@*FzaCAIvIx`&bZtY2!UQ5%2Z=x}^z$_8&hQ+uA~M zb8{bTVj}D#^hM4G0dlH3IuDeU2_`2e1q@2u7CPd@Pu7apCaN_fz72l--&zfYGqG~M zg%A6{TqqS7)Y>^Y%|kCKBPTcLZ8lck?1y&BvZZX(p@n{E2c%FAp3^Y8J}#Hb>TZwJ zV&!6bKaVjnF_nhku@KN^mK^8PzD#~L8$*;&ir=BDt_?!|I&7vpw^KSnK+;#eYhn54dkK%dihUXbHWdCr6<6foI53oz*g#i&c3vGEB#?$q?Z?lbCF4;}`)ebA ziyteYC46LiipUOZ1vNWYfK>e6+RA7C>)r9l7dcetzY>$+TvHJ4jhi>o6XY-Q|GK1J z)09I!oKQ!-ymANmBm;sS0ctue_XX+NRDL>l(Gx_^W_x<)ADwDA^yN!*1D_)k6s`Mw z3}wNp4igZk|GDr?n(O2YQ1^gRce13;zWBK2N8IW7_lHk3_4IxMnSz!mVEN>Xr_ZpA z;9WNwraG#F=M|k4ZS0TlfH675g-kj~6>pM2t8e>@0syJ9q9PvP0ie~3`y{7)FC>5| zZv;d*J^eJ@=h(u>U9(v!MUa?;Bp@Y)N=;1-;akY|k;4JB!%NT)^sAg^fS=5N{PW9~ zFQ+qvz711TbV5QxqAqLgaE^t6YlaT0;Q{`|pnwP3uj~u*!dIx3__q)h z>;QL=!dBt5{N__0G#Udrnk3h*4Ne!>QeYoUdh#H-Zto~Hl{y%oN)EmVA*u`Nj@g0! zM{;_+Bq&WL^X)Nsl($2HR6$Y;ob^^9dpNzzY^S>6)L$2}p`P+N;R2>^4zkc9V5NMG znv2bgGbt$jDxf7mpJoieqXxe4@bGZ!JBbQ_^*3*>+SDDHavRjN$8+f-Ou_14-dy7) zx?BzFQUTv{uWQ_T?Un_#tpH!8K`8)ez;w{T^W&?Vr)Mlu?d1;+$zm*xD6j#2ilYEX zHuo2!Z44TTTvBE7Ls2|3gS5?yV&dS)X>x?j&bPlYVX0T;^y5m*z{G^>l=ZmBYF;Zs z#MD5C9lsC#@O2Pp((G6B$|+r^yj?$j-vOqGS<|CoL{1%QM1sX#D9Uc7@pvcL-C#tGX zkrlw{@Q53$J=-4(22fRc!p+8Z3wT1aw{PE41ot{g;daTYsl^~VVlyi{`!^R>7nREF zQ9zkSsNk$DvrkiB{(g|Y)Qp;I&N`s9J36U;@6#rT^$$;sM$RL6-os-mXNk}OMY&A` zg~lyc{$;5X;^Utz)Y^CYu%{U0N3M^RBl-fYmCM@R-v0UX=XM|oJj_7U!ZCb0$y5Ny z#)2t1>&1YFDBE^`%6T0Zr?KG8u3KiM{c&y?fZN@>cNb<^IXNNGf9hD5dqrVCa8Sh# z;l|9*Up&5DT~)>Ry!~|!tuK@@;I#q+1MNDw%3miZdkj1yCH|s3vIOnsL`Xq_ZF7yn zh^SwFauI6cO1|2{qO`!&5B!@vgfGOBC4uz^?p+vE1mH3taeXuGq7<|l*IIXh?_Zm& ztsa$x)Ln}Ehy1^A-k;4)TX$fPU7%0b8TFaWs;EfJ&E*6-F=s6{DM@=yi-1-f=MFFt zt9CcEjL%J|LG1z&>eHy!Bt(=$|6ZxL(!0JnDW6lfxG`sFo8mY$9VVQIVq#;PK`3l$ z@W(iUbFvKlbQ&b|lYIb6#YWB8si~<52iIJyIzn2QlaG!~=JyB-!UZ`clkST&c+Jz$ zM78$xYT7W5jHb3+UmAQG3K1G$zu%m0k>a`(c=lds_5Wb^X50Cfx{Nk`+aJ&?4DJn93B z2_KCImWPX&P*UfIOaLrO#a?qjM6>I;Ic$uJ{4{keEqX<9>t$DpkY@E}4f}Z`7A7Vt zK_2!RgKNE1!Uxp0e2Di>h3rrT>$S1+o^QwZG_v}BN1S?fUKki$DlD8a$O-$G++yUZ zJ7fgz!fAap4)hWYPm<-Prh9+7(>f7B#ncqUVg~X3;b#J(LwVeapGQ?%boy<5cBwia z-9Y4tUcty)Sk#~ae~gxV04M>POcW5LBoq|pNt98MkqgB=k{sm|$A4Er8jd!x{xUqQ z^(Hp9Q%NM(us$6P0~=0kMTPL`>1m>rug|B4?f*qvx3=!A75BVBgxXf1r=y`J0Q}dm zapij405}H|6B9aFMSue+IIqT##^UQ+Et`1p03>ulcGAoemib;+dpH|`dUc&Ycxh=V z*z^6j0er=q57P8h(S~1LX+WB7U|9Y~v;7PTKR}T3j!zE}$xAsyvTJ9d(_*Sl0$7Om za7bgA%Jrk7qL3Zkxe!pJd)yF0K*IFN zKrQa}+I{!W_AhBd?aw?cD(OEVLCbl0iO1elG6sChX;_yE6-L*<3{W*5t#~2?m%pxU zZJdhaQ6K_9K%)E9TIAv3u>&3Zc8JueKX8!z)}yya%WYLamq&i*J`_Vx^9DAUfWm{- z@WL53@YP;(H9(W5(69>7GF&5Oa|9x5()Yr9ddGT-QhmfqA>tav z@6+2Erd=N7^g{)3$|z%5RJex*D;>?A0nCZpzW`dq1j)rCBO}f}U4Lru6g4QHT~B0? z4yL#hl<`qMTIbm7V8XQ(_)$C%)0pV#8{Bq&utb8+r4vtk3$Gda%#Xc5#y7XLv;djO z3&M`hOsVAIG{#4O!@;*nU$3n@LYxu z0l|0vz0UVsq0*}-@m4bqE-pVP9j}1ap@4+m3Jq+B^+%JZRuS>EMKm3L^nPioRFTN(XklI1;0o_)r(>Dhq z7KAAlU^L0|!)M@XNd#WZtS8;1C7dkI=CPKRg3-)HHx)DlXxzTporCcl&jeF$;RW>d zJ%W`MENo?BcbrGDdG@S!BIHgdPkk=+U=xp{nvPDm5k+FxAIgje^nbI~T>E)^*0PoJt zTBGJ*ZJ!>&%y(S66|};-TI~RJF5NzLFe&T)iiI@GhF;q(0)+L)M@KVDOIkV15|GWo zg-}N7i-Hyu^l9ifIP`xD{+D+LuqUvZ(AJrMdfWi?!#hac$@?!bgN*eTy}yO}OD>yh)02KFXQfOK0UY z`>D9aBUabXJeS^wyzuHi6R7_7JU*aYh=8E$#ZGZ|?vB#Y*wlGEL^AX#&$Sy47LmY) zF3PgB2mDU}JGekOYlKt<0OBUdG4Ute;1sa?$7?i&NLt6o4v-rQT{jKtPIn$61TF&W zT2C&qf#pyBNr6FE7zqoA=Znzm+tiSAi%De5;wGPeD)`&XZer)=Cj1Ya$7_BE_zaOT zK{)c*Te=HL6j8A{Ceq&BY>lFM=;9&>96U3qv*3M*dHYrdK8b>w43f0=aXF~#U~4%C z56UkPx52?x2`JY6PmYtpX^YfFWmoe|enw`SUmMSHU5jbGT4=@$7#k$nszz_%3`lBU_-s*U6E#yhu`o!l;3xWhm6y@wCof(nP0;z~#d*Ov zR$}DrqAR)@8je;a%IXz|Z|;}1?-w22j&F}mD6pX?0TN$7s4VV`j~qT;k`wV%Ci4UQ zSE2Wb3t;OcNpFw2ORB&_EPO)W3YRNr@Tq&%G4Ol;9+B=dz9eWtG67!e92Wa0b(td1 z6=dYxFLE3loh`2!r0rZ?huSkjw?Jvc;02qIPR5)ekB=a_mQH}$0E;x` zC%tBH?yH2Rt5u5H+uEYPbt?ucLkukI83i`+wA= zE^TIWMZ?KPaXu^kHVzIo^I!CTdNO*z2G9=Pf+grhZ0nA00x(1HA)=b@?KxQnA>QLs z)klw-5Q@ePax9>bA_tkbx)?<2sQ4lsG%ffU!aA&;$;!*`f={a$6bn=%c;WlP01kC!*gY)I!n22aTRjWlc+ytPQ(hI za;u2;=+3t;p%4}l7}3g^V5%jMLJ$tZI#n1^@iqSM@qfvG@0UN|; zKWBnzlP6rLXfUQh{q02lKumy$L<>B1b8l}9Py)NKGur&($SwK*+vIIj1OO=Fkl)3n zM9Y1vf!h!oiUVI$0mY5W8Z^)N52_IKR%7R9Cr3*kqy2y_9HZ99eDp<*2W4$zt_43_ zS%Y5wJ1-un)k+|w!ir?8a55kLU$P0*N(``dKv&W~{2pRkfh+SrTr#icz7>c3;~+y| zsoe=zB3rY@=|ZUJu!DRbyjD z@Ez$v#{%te6D(SZ++V%pt0vl%%a}EiG$8}}!BfH5g4P}BzP14ml(n9KJCzaWlcpo& zxLA#q<#nu2`kYu3&`JJ8G+q84amRswJPw70zjlPd5`!upc{O5{Z(sB1qGQr`q4D@F z?$`&f;ix}vBS1X8#$$lj04)}{Z^|5GG#op+S}+qQ#v80!t;$x06S@$%^gpM*OHJTx zgM+g*8^JT^CZ(;d4J_0&VhNuBOE_5V9+V^J5OSv};5T8Bfi>$y2vKM#zx=8L#sj=3 zFQ^M{rvfUl458O#B`=dbDx~RRAO}(J6gq#=yyNMFBw`+WU1y9qnD>F@}3H*tF# zT^juv$>F9i6Ux;x#MBv1f`qs@6s~y)&iSpGX7F!7Hwx-{ZvQzLRV&+qjnvICSlQTS zVAr35$J_~0Y3qrKf&y##D<$X%!KVswMrvp{CECLI7i`|Kpe`30HG|=*%thEmsj`r( zBV^s2yAr$~iW!nLerT>;bJ@^&CGC_`HiL0 z$5S?|ZcoK0BF`4Zd$B0iZgHAu{R)DG56sC8lZph@YW_FDGLD;w< zAP|Qb`uw1)z-w-Reg3;TO z(96Ae#>SaB|DCP-)Gm0hmRv!~DQs`9CH1G>4T-V1J!;!NT<`lrFWWz9M!GDUvop}Q z`%gb5xqFw0NVRFTV90h@DN>2lZ>XcCB?z2DKzLNHmyL0*1J+*H;Cs|MHkPtke^IBW z3lV&Aw&{x)Xv1E;vf4_7afM{c|723|7-Da1lqNn9z!P?jI+e~+xH#urmiqI?C-e1Q zEH;aZSgg-vz+ME`eV%=m0M!TCBd$f|(%cNRW|#MWFjXiKH~M2Y#&l!4ZqZj*a=ffA z%Z#jNii)}zyD3(!j`gk-Bbx^dDzB)7qQD121RM^PZOvWq2SMMC&8;#O&!x3IJ$(mQ z@($}M@Th`IjJ*VG@xwVl5CQQjVn2%s5CDkCAV33XJUl#~6_a-AqnMfBrgz*}4N>en zNM$)|knM|35^?XC*~y;3;_1WHiM7GBPfzyl5mmkC*QtF^M~}YZFY`-`@XG|wH!9Mo z8q;cV>hc8|)$&WsXRzD^ep3B=^BI3OA_EUuz z822hO;4U1X5bOEh(c5Oip?g^wR21lb@T~i9%6+L-Wsh{iWm#)sSt8SymV2Y=1V@yU}j9*+qa0So}YMPVxJHb;~!!~6iVfTIj6*$ANceGzxDNC z7KRe$K)ib*a#T@gr&xU)zWOAeN}MI-6(V*q%R5+x>jS4%NgCB`;JbC@)@y1dc#}#z zf&~O}(4o#`R&sE0EdWJ8cBLvqs=K|t;bUgt)A224Oxt^Q45TD97R`|r#Nj*)sf=%> z5ACzD3sz0p>4ybUh&HKTo?W?2z{xB;zPwZEqVI+5vp++Wu-FN@&h_TOFNlr4h&b42 z3(=Hy$3erKQ`1u<+NfvU80}A{vSWDrB+xFL$me^3T*0bQ2g`4X6rv2hdt=v#uHrGM zbqBia+{g^!VbHI!7#PKmWutf@+{IA__!o*86E9u>WO_uwGc`5+gf$7p%AT8@k%I6P zr!j(P90%>gmMQN{;I!;g+-$z-M=N+DfmLS2eSFcc1!V(+DFbCHiTXw&e$nP#ULJoL z&n3WYY5UK})$ai4yb(YHhZiWYVgOr3_RClAy8Zg|fMHP%hahmSy8!1V<^f0lw@c<- z{**O;7G}9qe#KV?9+DGZMSs7pcR6gIG1JrXo|rpmtNuSo2dCS3lp+vWEhY!n4IPn& z&hNOh3zh5FF{eYN{11tOFBu6Fg_B5_KcwgmbO`5-n(mCDtTDw6iAcyY(fva_TK4+2 zDvrhC19NhodsQb_`-*Za`rFffrz00F@&w{#Z*PxXexomnuI=xv>`MzJ%X`~3kAB7d zqT*>KQe;&Qj8W!gv9DQKbr+e}PmllmgDKOR`2BmLs|ya56{|B36&9~S2aE1pE%3E{ z0GWS?G2Mj1NfuF+At9NNuKaH1f$qJnn|PW{eyYd69->1^Q+I*qv zsC37?dWWNFi=I@ziS;ub_bHm;J+>RKq)YO89ayc?zFpoGmCv@7H1cl=loh=?IucO0 zk%zN7LV0nAoSOQj-#dpfXu00J*`Mw2`%S+YpkV#a=tfFB&=u=JWFs)Sq&oUiFmOhR zl{?UgNRGJ3jY#fcldvprQia~%QgND{%Z@#axf&t(IHq|Gn6HdVQk42~tdX4M=Y zFX>LZ?ahvomHGY^W~E@(L>NF_&X(ip@U3>qhrHGnvcj~1a|*(y#~9DH=~Ep89dR;p zq9#QiDHdA7hAdwGTP-d?HQ1f>Yw23x-yP=M9B40>!?lYDk&9;D1#6hP_H>%C2Wh!u zB_`2J!kG$^s4%-L*Zuit4vD(&-#fZio>Lc9FelO^UVPayP2T+JWg}vOKo=*LT+fG1 z9w)>^vw^XXQAEGCE^!&pA<^3|P-!=FFAmG#Pw&SPVM7I~rtO>5N?{zVlJ=NnB*;D=KSbpO6aN0n%EdpBk(c9DLwzH-^|By8&m zInDvk4RQ1)u}Wf}G{Tu%KA7^AvunA%Vll@bAnSbZPLuMj+d3Dz{g)gg&u znGq(IyG7GJck@bqs;?`0K~7yTl%JV&?ZEPGCh>Mfx3?HGX%aY_1Ib$kc@|XD;Q`V( zM15PAI2n-*P3CXrMcf=vvEeXW!J0f`YTK$?3gRJlBl5=}Chd)+wqXdt;lp9d!`AF6 zbMCk~zREe{Lw=c%jiDxue@0)Ih;~liO^8RQZ098s&uWFi_TWb|e3jnoROlWMc*MOG@4X(HzIK5k4q=msm+pK+q(kIS5<^OImv$&t>4t^OYu~uB*d$iw z?+bXul8d2R^)k;Z?#i%eGI|^mjTEfM;c}`^hYgb;D~)`YogE5dye379nEMh@P)MCD-XYFK7r ztm(NrBA5|c_=r)oN{_a2bu740d84AL3~Llnn3Z7hMWWgT1c6dAWWyNBj;^k}y?YUB z7$L0pIX=s(@ovZ%Glrvo5bjY`CYHs%t2yCH)n>(5`z_SmF(&laBStY%68kiAV(+o5 zlciW28`ge;_`a_hjmeRxuLo>#2h`(OFh#b@5#7Ao03?=!)}Dc zq%wrxW@N4Eh%1@=toK1D^=1c8Nc(GJMloUH-aM=r?=hmukId;@PGotZw`pNRjWxko zhp3?-n0zDk2qC1MACC@UyB~0^g`whV&|T7mrABR=IZU4!HLg*?1wN2iLmC-F1oLL$)bRn zCMJ0<#=l%VJUx%boRz|OB!MosKYWtS-E+W`(+$n@;)eVkQx>P*N#<}gY-T56dDP!pNRpcZ~@(iwlt z_&W~B{tvaZw1UnJeU6yHL@)9wRN8fR{B1sSk@_O#(;>>mFYX` zt~`t;3m1r;v9{L!*_?? zmM`8Xl@*)fe-sJz9x(FuMm;QHN||za>5}?!rH9oof$d<2HQkUPhCx=Q%=N~%5Fujk zGn~zhfD~QJY-2iRX43}`UU;_)DrMlq5biL+!n-6=zyGsiq+Ea2_!0{dLtsp;wnOqi zGr?q|LRQ0mAtCbXFXOReQd6zgiRQz<>4BXi3?xgC?tiqm)AKV0d?3kUn7EuZUZy$N zVyQyAei&v%%@Y1HXS^ymviUlrxH56y4ky~Vd&y<~xv@!^9A#ygh3fz=H#OVMpUeR+dELF-hga3s6=j?c=)V=vsd?-4H|3E1`npX}c=_LD zmNAKmjg2yB=@+x2&Q4FkRF=y->Iwt1S3bV1FL7Ddxv7}g07_2-3>T_f8-gCGr_Yi9 zcVTTUm#{cem77x8$43&v~%%-s_~krG_~{`_M8br1J`?){ynw(jotssWD2nWlRqg)|*Of0xf}Z(_Xz1sSw% zkkK8-tjo1W|0AU2jN2fiHej?v_7dTCZrvj*vOq*Xh%~-8u2!3pKBIB>C)HTO9mkA6 zU>udOq!6c0qwQq-=!+SK6wA1$z4vaA9hH6Cmmk5gUSKO*jdqS1Sow@kR-g}f;`Sba z2y`NPutN@v~>{&^yD7@w1)z9}Nr3V?a7i!pP>d!!|OJz1_i4fat@WOYcEa zg3+iaVgxb4rqG9Z>>)Nx#HL4mV#K3e&DSon<|mSc-x|lb$r9|C`bF=<%C4@`+pBAD z?~7$viDDXl&=(6`T6rKSPjQkEb6A>p{1O+Sa=Phb6wsgXFpLhCgoko+*dXqL`6mnr zITWy`u(aYmL!gxarz)n2#=&r_&M45eHemJ|8J>ywodbTUC^{({ww7c%$|)1kdf6+A0c08GB-ko6=Nz>zuFANaI>e^~UT==>Fm^<08IQS5bMXv1h~C z5+)cPhz6^0gvbd$0%kA*)`bqf;vlxipVg1Yc_OO7j4bGNhY>$}t*%sx?uS_ME-5*| z-9~N02a(wvvXf7v>^C(cYIqkPm)NE$WoO=Sc z*%SsBZwrBrmy~2txi!0#?)`j2_(xCxcEUH^$B!uQOVS*M`BN|E=S0s}X7=X~Xp72{ z_P&oLq4DtS^?4^nEa9a-9~L@H40THoQ4he!k^w#zNAn&@K9|(_@$*OAXY*Jnoqc3~L&RyG)IRmOap}or2XR@?0!7gv14hx&n5bIaU-qx1h`mpdy;2B3 zE`-(0E9`xI8%7Nlrw^p;toqUT>T16qJ?5%#yOk&|YL{#tWslpUUi;PSVZX?zXKJSO z9RmFiG|RvH)1oj&f1PWhxp~AH-U9|F^A_|q)taiR4KM*SQg2HaBIMf>R?rjU{XHzz z(Yl?(T3(Pwq;*0sQxLc2<9wR_Q@c;al{&y=F-TE zr<^9*0#v3*;jSlvt#IRVEpw{Wy0ncE#o}`NeH;3Sv7GS`rj|gFH2RK3yfnru%cB!% z%HFzt_6qckX*$!>zrGMhE5On=)KL$L-(+O;fQ?|J-i#+i@U$V!)z6Lg46qa7Sk(jofn)KU9o1rbJ-87x)!~CP!qddmj^1@M5y#=A-NiA7x=f6$zN>@0rw?GT%2&>u&A9>S{DvJd^g=+Q-wpYl1|&NE$w+<_05TLH5nf(1|N zCR^%y2;amf_o%Sw+HDx~j>xen|B5btmFsYFZN9I2o#Jl#^4`YGgXr_TCGiTbbzd^S z>a1(BAWa=Hllk?TBjWx!o$q}0UpDGP713oW%I9eoT_a6f9E*R>>P8pT?@{-K?mWnn zR*;nNsP1?6qf4{JV=N3HZ)r(`)X~%)Q{OsLx#A77M(CA07O2IZ3^SD#SFe+0SL#uh zsK@epKSb&7Jh3NbS^BB%p;4K~;x1D~&D?RoB3jDve#mdo>H5_>A&vfSB{&#Ol$&>e z08eHEs~d|+#0}qiXO=1NVJ3qunUgnMy@jVo?PhDkuY8N+lDM^`V+5V-=UGk;A zuAoV2jL^DUfz#ZQiHbu4voWxmVLG@>9^j`aIQQM`dt+_v(eT1U+e^RBgy4LSACGVkU9?^0OjqqLa2iaal&tP-x#P0>Fh|)Ci^wwqwdD~jZXHmVh z+kJ)pf${)(UYWh{x(r6}BTfr>4j-4R@7qYokE*%$@dVm^s9<7Q3Ri3Sokva{>Le)> zr~(2fS+C<$%j4)}8FedEl(N1bccdph+>^00JIWgDL)0Uc(Rn$KM~W9X+oIg;R_+m5 zw4}jm@TxSb(s-nZm%UzZ4JJ7)smk;)oa3EJ3%#r^Z+sqZG5?VWPMhvv?v;k`-(?Vs z7%~$yTFL=qTE;L|r?Ed(VnG7TFfy40gM_p`hekJ5(#OrWX&*{7#2-99^yw6dqO)f@ z^MY@r5xHyjie2uHmxy%WE<=;9*{}B>lhUO}dFP{OG3Cn9MsMq^!J_+|5E2&#nZd*x z0AGtuK-~@kEHVcRGegXrxw8{YFnG`bE}|q5{D2*ogty0-fH?sfo1Qw`aQ#a;7DgAf zz2GT!G}Fl$MeD+RrbpBkA?ENh>Q38(@=CoWnj5*!H`m2Tdo9hWu%~(>rn{~E%l=Yk zATgc*1)E#1;x))Fyg(2C?=xgU=ZJkC-m$@{Q-b5Sv}EqGG5+HrPp$eQ`quArC&Aj{ zfK4G2`}udcEIpST#>Zn~Wl+R%HlPupCBJU){0%bd&uxno{rUKD%} zpml_id4{6E)x=hi?++= z0&OJx-=+c4Ai#|>NYIwg_OA@q5wwn|`tT@AY$irW-)kuWz}MH)3k?fn5D`flvpJa( zaRVI&v9ZV5ko+HSFM99(57gJ^C^c<39HibZz* z?s`=WVCI@pT%6huEC_vleVk`Z|GuXPniEd#Z-HMw3gEx`!=1pwSlwr2o?dR2d z(7!1JtthNVOTc)T0%qSju;9wQDs#_SU;OYBCZE9M`~h5n_*Cy`zF2cZSh~ZIIrtyj z;LR^!IxB(~tjL9z9pzX{f?-cKnpR>9oFBZruRS*^<;!tu*UBozUeL$QI`5X!b_x`L967$$ii)|}RxJJT! zL_g@1f|B6jkc+B0g4G}&sM%`51y7dPD~wA76fm5OT(Jn|xBl}h9pF!%gtv?F&Cbrk zds#egD;IX@={wx=*falVSnneT7H;IVNpmpGAqdlvqoHa-hNWF?z+B*iD|;?Z)8H12 zoEXC{jzG%Ixdl#KxUxIEhKi5YbL|%5UB!Otb-LX)uwOp3X+!4s|Fn1JaXF@KAHNI3 zgshQ5GZgQI0p1gSC{Re4n5@QYNryfLV~@0`}U@-TTgul z4}ecs`>7TIjH&A}d;R{VVW(%zaC$Nhu_ad0+)@v%`=8BluJ+eGe{8wcy*TX$)pL#) zKWQz11k|jSV2SG1uYUncqd3(unrn2tJvUsZT)mftLdJ^Sx_wxakc-raFUxuM_dTXw zzVGT9J*`3FFe@vo$;bthlDraJ-XHkXFIzm(pSLLOxNc8W0BDz;Pz3iMvD_s@Ct<+5 z zec0m%V;zRIu2rgzBwVx^=+sFXVVL7I>haa3op^^hz^Fe@{B0;;{Fh!HmmhiJkz?h+ znPPlEdZzud09(Np6|Zi7??%(ct?ZnqZswBk!sB?t>O1V_jzCA-lf8-z9h}z(24GF^dNFSk|LB?d|BH8<22TA zb~f4UE))h_^Tntwl+GSn>N;fT&^CJ3O*4m-jE`=&II3S+#kKHe$=%;kik6{c5Oz+X zK2`^{ihcM3m`4MxxoQ!q@46_h-t_k6ns__K;k$6+grPjB#N=|sAgH9{3g*$8Sa|Q^ z3fiR?cyFr8p`6_rcW0ra`DxIimAK)@UEz8#3w_k7)AmpE9Uk&sBHC!%Hr=c7;6a0w zt2Dpa@WZ^g8`n${pKl-2^}u$o^5TN(2m!J~9l=2=4^blwO9)s5s}%iI_kf=}cenaA z#Pci1LvQM@1?i zt);VJC!`{zTCLh{kUFA+{k&G2U?HR_`5YRuso0==kv6LH#PqHxE3ym!%(@lREniG! zOir>Ct094CV3G4LaC>^qV~a}i9@D5fE1I=$@5mii$F-tgjj(x$+*JREMs1Au3cA6U z#%&v%8b%{Vd>=`~Fj^B|{_6xCem+Z~=J^o5TWXVoZGJ7fd+Y8Oic9-)?}!a8l}6Z{ z_yY$txqQ3}2iFG&-#A$l-9Q3}fmt0%myw0V&ri_G<>1Ah({a?bgWv?W<=&{OczF2K z9CeL(BK3>xGN`^NrjDJd9{)9q>?

G(xLoJld?;;1C&f|NB4Q7*oeO9W6O3fR;07 z&P4NV=hKmdqaRc$WLkjI@@`rL&$jHY*ms0RQG>>fV_ekvxp95;)2xnTxt6BORFds( z78KM=raZQ}mKd`sB=T#j5L6^BTDSILFNjHrv`b&+FnO50kCWwK%oXG2%-LSB^lJNl zE0iB2S{E&iNFvy~MF*d{y3Ld#ec3K)tKr*j+Op-blqLqJ&`oBPeii4~P8dH-Dt544 ziv{*7%B6m5_SolUXJj-KNSD^;i(06Ue0=JY=TscGwR-!@>63cT2tJ(EsqA}FkGJ8;9N-+dss8Js!kB+;gEjzOWBgzYxKxx{qHGPAlGzu>Cpiz0V+ z@WzYeUUbmkHfFVA4ep|59gQx=SG}L$@B~Jps&wWBuST|`0104$2Z!u=IYyT37rn_L zmS0}kd9vctC4S|KRjahK_2FtjY+I9KpPG}iMZ9n*np8Z}SEi=p>NhquwO;(w#*KBR zw;!vcIkDCKu1l*n)xSSQ$9`3@YZwmp!H~`#$Qn-=y*TTYLlLv|K zo~w@zE-sP1Z&?{kmT{=0?saiX_+X8DS&mnDyYCh0%ff5EwT8tdCE@M9&FYt-+_d}F z%Qp0<%hD^pa5c34J+j5=(V-+I7&#?Fk!RaWM`J-Ih4mYa{3Z2P0ewljW1DT?=#N?uwz@f zdk20 zOHt>8Mi!)JGCV@R6@;}fiWWONOLlzyF08uqCj*W(xQU9-x9a;!*;9fF@CdtwM!mz8}&!>v3<7a9klN` zx9=y8j+<|IRnCghd6Shl)%>N}2mYUi!0{WqDO$8>ft2jn>C?Wo%&Jeu`8RFX&X*oN zdi7f@lb+8G=Gf20NxR=JTa_dpQ^FCk%dYdOZZNb67@-u;_aip3*=vUy+1hpo`y&`A z90_0MdKI1z?bNB$W3d#?%WTh9n1ZjMoJm{{kM>?K7m!7zf@DgUbVZPXNXFTrd>4uC zxr52MPVdK8`H=#eb}ZUzm0sj+`XweFZK;FeOvM}dHe8vlee*P0)P7YP-!b-{WjM}*GZMd z|4VRYOb0ci4`EL{*~~(0viG*DD$n$i!6mB7-F^IV1@^{Vs8R$tE;%J7KUejOdn2hK z1XESJCM#aYs~mUXPxaZf)LtfPePrhV!3gI=E2S4ElzF%fPX!xjjT$vdF>`T&8i=A1 z*lqD;@GY;Qe)17}b-FsyV)@#&aYKN2eXOVFC#>K5_syD&>bA(LmeT}0&TMeo13PM~ z-q+Kzpwq3r5o04zHc>Ac3}|B6gp&X&;7V_=N(7aErxhO z4B6#k#z@f6(2#N69OB7Ur;MHh2KX7wVGWa%;<%Vg0VSnWV1|I>e_*o|OaO{fbA78tW!tgvbXa?17z! z4hc?jGzTDM?lz#_;Sr;*4_3VMx4dsU+4LEg@esDtV$@%PWhg65V=>-0|Vx~iOxcg}WvD1GkIlf0$y&#`P zZI1Gk-Pabm`uff(cQTdG@HJas5&EBHQ2)F9>+j$FPh(T~*?H%F8A(R}A&yKeZh&+; zGvjQ$NHq5y^pB+FDqTGG_mTzZFrVO)qiEd7cej-Ss~3AAB-7&%!xh4h6KyrVL?KX8 z=i~EnQ=ot^NF7prBaN~;87c7Loc#X77C#PH&;bLUWHx8delCtvn<{_|Ybm^gDGZvc zsU6p@g3JVOTp%`}f;$sY5{mCtT?1@l*&jr-bM)`_ukb0IBkihMV3@+Pmc z*Uv6(8rr@_h46L<|6Da-_}fba3Dw6zO}5hKJ5%WNkLMZi3;P>?KUsz~F`q z*$=hyM)%)9B<#H^Otfmn<=Q1sEf{o;sd`n}yHOn~`P8*qnV4A?EL>REf-F^XV){?# z_n8||B^^We`XSiG6aSqlAJ=F4sW++ z#@jS<>-v`rZ^!(8f2Gl~#W2fZ^|Q}2wCw;%w?Dp4>IZwF<*nvWfMqJ7GdZMO>76XD_$ z6HTmLU0g2t6= zh2KuRzc=ODwL@oK_|l6c>*q%L(4D*Pmfx5be3C$WuX$m2+Swr z>p|C?7R)!ee@;YYBHoWgvbd!5p4Ap*&s!_Hs1IGT-zq>nF53tGnyoxvkXRsB==XGS zFU^`N4NF*<^y)^?^)5UYQlBD7IQ%#^eo1}7qV9nm{8Z53%@j-+m5f;1U@H``G1mF} z&n+}(cEc7g=yBkFVrrp>LWr|0EWxfs=h=;3*_cU_cH&18SrRDv*z4Du@QP+;bNXml zALe;1lMA5{SWM;vq0BKOQ;3Q{mp(gaACmqCP}E~a-C0&-Z#9;urkSG=PeF%e!xu_5q6@xtMYE!aw&A1*|<%(Winslma*6C z#_ATMZVK0;TxcVcXCL&FEOz?H5Uc{`UPFBTW zO0L^!WJqgo`n3gYg}X~#Xi2bl-@0?h2*3{^U~g;{z~SX<)}#XWVMP6eK7;?#R~X)t z=k)pVc>>0IyLN&6k)x*=KborKRZ+MzYnT^coN14o|9TkIBh0XhY!HNCGBTGmtj3wd zLkI@V#hZ3<*JOnt`WQ2Q6`OYE%nnwQ5Q26sa+fQfFy>HeZ*nm(?~tN5c@S&D%S2`? zA(}r<$#lPUGu+no*d?qORj5@Y5znuBRaJsLZ{-c;{V)*KnQnRY#wlH9MLJ!<+VcUO zQSma%sJ>S>8jvInFDolEVqUy>AqbU1eXNgnAso(P zi1zg1wLqY)7?{7wv6pUTa&od$rR#&sM_Am+)O>qS=6zf1$ewg;?+2#wW*nb9YdimE8I_#|U$^`m| zhuTClrMCXYmv%ERZ}O^;^*?N=QJtyO{>H=A2N_r_>Kvk)L zlpL)PzDyvGGc)iU`#S_GlIY@8&95Jy?6`J5IPbP?U-d5u3J#vcw}3X^ig#qC8s{{y zfc}nY8lUydl*#EaLMs02JzxTFW`|F{a^*^Hp6SSts|}w|d#5L<+>6Kyfg>i@f$Wrx zMoGu~_5wgUe%h}T;_XELcale9ah53)mIaFzg+E>N)H1g5pK@50;ofX9^xQ@T5A#?K z4+XO9N04C9sMcA>Xlu!mM62*5B6P&;6RO0K6HI|j!K@m*eEeDH{U$n)L0A*kb>)D7 z2SyvaDhLvP?-$?f=NG{_0A-JEtYy=nF>3`|k$3xDc_e`y-Y{gluTP~&Ac*{x4vq3# z9TUT&jG+)tI``{W`s)iyrP<+oM@uBLQPrrd31qWo{NFU|{ytg!H#>oPTa2eC&)$tmb3b->k31_LQjw|KVj-*45pY zI_yni`EK#sAQ>$y^D$l1#D(3sw2kKEmh?n95cH7vVnz3HPqwzix->i zo;`ckMdry4Qfu=-9LJRQ+qDDzyLIbE&8HllGoBa2+(d%-y&S#plJd4Q`aF!J!X!j~ zQw}_1TA^pdh7F-c@0Y4mi3HP3WnAQYVo{5(ii{t}?{He%IAzyalRM;jA3=MhYGTen z%Maw-R_4I@zx~!g4C~@mwzPMF%1Xw(C%Rnu?4P}YQpjdG-Ur`5 zdUOK?{{1|EGsh!G@``QNN=^qAT$72Be=PsgR9)TF=1G0d8(Fz$k6q}#kS5U%RMYgR zUmxESe7&mk{ALZ9r4Ny21!=woP5o0p4cz#q7H+@gK=shNN!tN(m`0{(*VwhHYk)i- zEukZVaEH*a7BwcL(ldk;vBjrhv^~KyrCIr0mXOBA(`yyVa)ihqMVo0+_M+ev(8epE zF=Ea|w1@QJ6sdbotb-PHU}vY(K^rP&Ai`w;vsza)kA{4$_yV@J(lX@BY+_?u4NE zWs0C6iIv=1X66Md!^!c745itP5LC92YYwS=df_SOv{P^}0UylM`|9n>0GM z>Q0UA55J!okF$9(bVBvMa~m-b>&$S5SZbjk2#lcv#T+xwXs3d)dk;JuM04J)VAE7} zfNz3kYzH)TVbbsVg9aDL;y%M@7(#U@oOc zNk)=hqm*66`_^{Z>h>*qdm%bosuNcG(r*Cnuok9*f+t|77wkg^ng*k>HZSIWes$1o zLFkL1KUCQFmROsFuA0fRjulZwXOA=P&OeqXn&_J=UQ>f=-Ow5AdC@c>r4tK^LrP|e zlZ=!M43fsiEto(5CWiF8v?RYwCCjcB*oc$i9Y1&5pi-omWFukiQu}c%m>eZkKo(|S zJVkp#P)%6j_Mf}B)0?T7j8kY&{&wq@A%%g+YnWsC%VgK_Q0XPxxJ525kag;M_p`es zIKrDZKQB*5;v7LW#(huh{_O6Xz;(gT;1r|DOR9MRcm=7=t)ZxIJTuby=h|N6XOFzt zC;q0Z*M7^mf7#V@W`slQG?=c!ItYV|Fon6r=r%IFx0GFa{-j3#QhKi2t(zsr3nbQB zG$w@_&;HE2Bc2ZQdNl-?nHC*dm}h69mI-Qx5$=`CKGhSCT{PJn^n#m;YudQbnVCnA zXVmurFp+JaJ>z5oIV2=|s+)wb2}U&b9oAc_E0`bOb63{p3lU+~#*HDi+6fH)jIdbG!z&oeVlJ#k``)?CfJqN4EWmmAb(^zFXv*?3-)2hUDc4{`l! zGrPwcbUp+IYO=(&sm=6vb7Q*HiZ3UMbT&n=gFk4KTs%ABTA)<`ov&v^DTNc>Wcqsq|(rxtfPkQzS~)-Ag8<&;WT3 z06=qK@tvKq3GxO>`P9iRd#Sb^V8N)R`V)a`YSg@>t21R#$L`(Jm#HqkmY0RaBwd-hf%{@zBi+Wuj^3dw3GZ!Bp;BUKA;?lv z$?4>iKLM&LM}DjZgV)Ae&d-^8<;KjU179jkLSVS0%FH?jGG~tXqCzXla4kb9zzTBT z09+fl3OTgP0qi^n0L|w4Ds2~VZMU5ck{P=p;HFYHP8zmbIb!QY{nk}b>l>i~WUO$Y z_tEIVs2)h&tjTzpmmYMBY}UN_d5hk;fdMVOMKIFsW_PN6j?OZKwpZ)OD%6LTzwfNq z^T&A)t|qjI&Uq~uIj+0OUz}QY+5KPbZL;X}aVFiT>2!(^PIJ(R1CuvTcc&2{EijVF z7PQ|estR)O5>zH?B>*q?&B< zUlCHR2uV)Y>utCx_`f=&|LTzbKkATnr*a(EmZ3{y3!acwF>{q9wxELam60OQ!k3(u z38DOD}`4vCGD~jb}#w*I0q*yjB+P6Q$q{n>kBe=pTD3lab+O8odx_2(;(>+?swO#@1!mo9=K1V@oHe)_^VxZ3L+mW-gBErrg^sb0gY!kO7o3^`D_$p< zjwq2gYb%_coyVZoVOXr-I2gTqPgX3y=+B;QBYgeF!zoAv2TNoX7^s{A$zBveO#=S; zBv+S7Yq94Q58@{qph|t8jHK>UjEzM#ImxS{1;1%K!**{uOO<(Pb9MFQRLrE6zMiWg zm2E@aU{iLuvdm0|aRAmImz318U>aI|P$k(fU3%sDlq$44ZE_yMAt~Tgji@2l;aYJk zcA}K#6;YhrLi?0~%^b#Ra(tskWsCKlKkew<;rxRlnuqLtW-AT6DQsUo-D&XE%A}}R zT0;tQuM_m$5(;+&_Q>3cq80pn+MHk5hmim`ky2RB;vtpaxM9ODa-P~4+$tZ44-|)$x&-K`p^2RZGYxI1Ds2uU7Gjsp=063fB@TWk3~u$xN1^If!ER-n1#%b zp4sb9n?{<=b`t_v&p#H6zBA)+CkF7(ijE*kjAh}zxdXNP5bl}w79n9jXfBo*aR#RKH zd2?$d26-eTc{HAV3d$+T*hb|P7zJa*{?aSY&Tbv=?rA|~*kj5`#^&Rpf9Tms4TR`; zZ?8>e`sbgOcv@XZl9MqQ4295o@xLo`4CLyls6R-~$w|06a2fEi?)`u1+F@44c#hD% zq-w}PhoX~}b04c=d8$Iv_^mC*e{&fs9uI!?w2Ph3#~sdF=qcA!;&1-_lMuaH^7Bv6 d+kR!Re0+U}%*(SmR9vALGjigHy@nRw{tt4|ZbJY7 literal 0 HcmV?d00001 diff --git a/docs/relaxation_002.png b/docs/relaxation_002.png new file mode 100644 index 0000000000000000000000000000000000000000..86dbbdd210b69bc52637c30d802d17c16823796a GIT binary patch literal 32128 zcmeFZWmHse6gN76fV6~!l%jx23L?@5U{H$E-AZ@EAV^7xNC|?1h=_DccXxM})X)ug zpa1*byWVx{)BSi|&SEKWX3ja!v-hv|349^{goN-4Aqs^edG=IN5rx9`LZPsxF5t;DdbUO=IX!!8b1QrExB6Edjco1ST3PaQ-{ zhsWao_yKM!TN9qE$7gkL5CZF`YIZ0TnI7`O`X!P27KL(OdnWntwR8O1xQpiN-LuBc zK~(MUq(>~paj~VB=e~SNiBTWWGxh!He7WQx$E#bbd#GxtOp zw7de~&rme>H{@&FOB5A3Ik^o#p%?N4meN=+Bqb&5+Hayhz;}!3a38>T$pw>9H<4dA zrb0=wZh$T~B`PmBcWEf+dRFab|?BQqEq}h`1E*xbfh7KzL8Agq^i(j zboE6FvMLOU+o-EPj1*eXhlhvPj~wl;GNt$IqV>SFWh*e=RE$-P+nRFUnBnNR|J}a`WcJi00R80zm-*P4)c5KEc7n zH8nMGdYu+}mh`B16yMjzCNSH+B}+?hj5`yw)*J!@0-o-QxbEB}p}%KuPe(dkh?VVm zdUS)GoyJV&*|X}_)}U|Sz9|mIihBsZeEG6))TA>Z#b&mF;l8!kUxyWCvvS3ILG?9$ zB=k$;rGmzJ!`<`60wKP3-OjHW)BB&x%aaNT2^pH0M8w6Jm7eai3JONAu9|C1!UyN$ z=NE!Ec32rm`SuMJRPSA{e@#Ln@#N%0zleyC@VNyKC#U_+=!rzt)xUVi=v9rS6x<1uEs zc6B(%sBy?Bb$-Wo4zs;mTU&`RM3q zT&+J@Z;ru}(X}ALx5oSlhleq_dDl47>+}tc!|jBl+xT$}6AC{@YCm-}zBWv!oZETD z(1gx#@quF~zEBBU?zU)C$2Lo^KHKPwl;b) z!McZA^EX&o!((FJlvb+c8P_#5@VRUmQgf+GLS4uz+ah!tv+*A{qaiQpQ_WC@RVqVb zJx}1Uyu7TW9noy~+xlj@tb~q^j;NRzhh`$HNL+E4#80be?if3}YhsLid{?jIn2o&6 zRagvizwEFs9Bch2J84$ej>g+(WbV&tNe`-ZKC|KhsJzd6^1W-+Vo{C_};!L zwHUI=B_kswz_iqMwt8o&JnYsloLSKd$SS(5V}-+Pg`=Ybe=)lP(<}Rn3TQI-6S2+R z{VKsK%E>DU2YAlY8oj|*Bs}hB&eOAIM|S0(g2Kq0U0ihe4j%{=68=oNOu?Xex)I24 z7mIQ}-5q>2@Y%05nun)*AYFyWacx8?L@6-fK6@>1Q%lS5*Uln#3&gP7>rD%^?HSL` z&iXR7N{1Ao%urYqnD*bMu6a)M7Vdw4o=hk2Res8j_;(TPL7qQTYlrh_O*%fsMM)ho zyTr?JTs?h_WztFeBb7eBeTPM?H6l;QxW~@pz6R|B;R5FnoOsrc_NF#bem`CX*_$ev zsS;sYSgYd0Doar4MC=m}!p;4HnGLh44Xdd|lbT896EkNjE&;L4ta)EF7taZH`6k&; zO{Jg7%fw1fPtWsntGr>#h~~->ZJ*a%(FD+H*V}lBdwP2Ad!9H4vR=FPPDRHfGS8%w zn#e{eXQgj+v{X`;gR3fXfSQ(8^`A|Df6}*aH;catE9J+FTWApWc386sMfakqtc43c z_NGqvsgcQ>#0Y(zZ(r7wkbf1|+n2+&{C?z7JnqJAj^0|s6hEP`D-+bF2kO73Ri2Wd zIRvnYP5ZpQ6o~$M+3IuUT|(clHK~xl6H+o5o&8|(-4~)`3mdki1-uM-W)lK`l6oyBV{7_W4h) zxgYx^{`^STy0QBwwog_^e*Tb#$U5~`=Uer2x&>^WznqlHrbly>OVJ8k=h)b0REp_r z7Y6*)3&aSBw{CnZWN$n_h~yq0eOZ)AQ(*c~_iACHfSGq#BeFEgQ{}8{ zIP37jvaso<%$=u50tlr@vbDY4TF}oeC|IN!wm3WcSXEUu$9jLCm6P*N9e00H7kR4} z7S5_5NpQU))!e6upwL(m7m802Ic%xc|K3ouhtW_8B=Xtu)h0&t&EB|%=8m@eWclMo z7WON5DwR>5=qdHX3xl_A+`s7k&*jqV$vENN@-)i1XJ3VfqW(Grc@AWf7~37nU%h05 zi`>=Ay0mzy3W*g{%B2!#2gze$hx-|hDO}L}98ThmgoHkRew`nG|7HFS)^N8SvQHFT z3=(=XbF_k1xm`J-S)gmyTaiG4aBeT`k}#IUraYjkL71RVcSZTfGVr;gOLJ)eb)1-rTh7 z-rn8}mHnicmgaZw-zRZ71qObM2?%%o-1m6-#+l_u=N^Aa84rrLCyTb1*=Zk8e4kI4 z8*J2k>N6!;^N;?$z}}7gK(gJ(aw&eoR#t1Kmu>DM@8&W*JbdHEjn5a|*cB2u3o66H z$TBpFej2q#-8CP|uA?r^&gMN%JarZKdwKV3bNKc1%9AsZ5`TH?)gn<(3DcRdHetyK zj7hQCa~82@Kkf)=I(OV7i-`Ove0cXF7oj7`mly&w-K2*&7l~^3^5hxYvDj^IAuvAr zrK)O^RpqHN%hKu5O4j1nn-wnG3;9-)6+^c5msO_b=Ortd>})@Hk5AWHFI{2~e!p8( zdxN=cs%s;Gp@nq%Qv124uuVYeGnPM^WQZT6wIeP*FOhHV4t}q(A!SQC#Pmf33Zy8B+CP$rhLOQfySQ z+PU|C99~YiYZYqoc7)2?N9@+kYzq40)5PAYp^d-UEHh)kd+KgcQBhe>RlTFo*d=8a z*EB_wk&&tAzj?{BBw#hc002Zp<(vj?>Be}c1dVT5BD!JdoWGHxN65M_%qRbVf39E_ zRb&^iV3hFYB~+32IQqL*%Tn75KlQI=y}VA=X8iRU2g~JDC=-rGw0MnS%sk{fdmEDq zfHc!q`m%H?CA-Xef0B55l9p*k=~2nW=341=(-jgBs8V{eZKm4qr3l`5cMr|&6!Czb zFU@7be`}xX$Nc54+yZtk4SkKwV(fnd{aJ6x(_D|*Sy=iP0D7@Hj<1iGM)R9=d>)aw zdbP^YeL^RCYU)EfzsmgC0nXk!m%8UsU`^tl-CU|H1s{F*1Ny!0s0&Q`5*f{G-}?M9 zTlqa@X}g^tO>R@~)YORDcn|AK)`b9hd>YA1?4#p(=!>unAQvB>FnfGXei9ZnGT7T2 z!I4##tJ-8Xn8_#?cdx#-_FZGz{9^6dDW;Z8sx?f)cENx0a60UT=MNl-u5f1Oj~@AA z8&tO^j5$=a2`oljy9&AT-@eMve>45v03%uV7J0vv`Gtk8cEL$ZJ&n#KdivJykNuzT zydBEc3*>UmP%p4O8BR6ns7esab`xBkkegm-KD0oKOHdV_@~`gB;In;v8lkANznjzZ zTj^z&2+h_=q3=SwnDtLOLrKZ!$vUrC6t6uAV`9B`FN&w)z#ACZ7hnvd9upH2JOBEF zq(iRQoS*L7^((2oOqFNES3XYddmRu~#1*CGHtbZF_*F7H;^H1}LV3Q##`-8*NQQk` zi%%%ycY`NyCYiV^$8eq`n6a?f-hpNILl&r%I~>e?vz`WdogB=D)vsH1eFK_DtPAUJ z%y~BC;NSo`Nryo#|6%h&bhSxmO~==41N_yYcSem&6rlrG6RaI69*Tx-<1jWS&&@S> zRw$1Y2zKWrr>PF5YiX2PO4Su0myO`<+qdq!{VK>i{n022eU&OdyuOXWe3OahCT6(* z@f{9+4_r$9!O{X%&OMI163m__)vo%(x!w;1;~#j>oUMp%{8m0GWgj!8;hc<=vMQnEY8Rd`!j zax4;#9@o;+GP9CZS@^ZeW_2h>f4|6Ta-uLY3r=FM@}8xhUUxo6oM3Gf7nS8<=;;%j zA?ZO0oJrcf-k)`*XJ>fi>3HsdfV!M*in#iBzG0cVbS5H+4w z>6fJ*+`o>#duwvSL@JVV*gIy5b-we9i+L{F#u`h<^U*pV#wY)%@sBE3zzHzvOnzdQ zejWFRb0`uiSsfToE7^b~rlE9xUP4bd24b{Sff_ zvkY!kObo5I^EB?KPoLh57IG2MaQ}c6ySP@VUr)Hu9@kjygHJ$AJohusat5}@jhi={ zLY0DEXUxqRj^5?6v9U2UG#pyr-rAb^yONpbTcMnxep%#QvikfS6=Ugs<$1LqN&L~- z)i|Qk6S{+iydbmZnv{Zf`@WedP>Q)$ISf85b!7Yc;~I-1t|l8QQ@i}jvj{eFO3KIk z>*Fr7A%aVjl@bI51S#t+BV{i9K*bhQqP1tDG%TkNHfMwB1w(TT8gm`j)bY!(!&`FH zGgik+dJ7|Y#KkLyPIv$H=dBHd1P9;X&7QODGky62Rq9xcJ}1&a%k4#tn>U9|Rqjkz zmep8hHhepH=hFV=GHykJ*msl8B!hkXB)@>C{Xi~?b*r%(g6V39atyFki>qtM(DQm-9JXqDnV<7IxQHABZv>K`UVDvTdh3Lo;|ze zh?bOmZ^5DC>|A`xowc`;=(9hyhH8Y9&!@RKJ;jxqSRiafN!Zk{U&C2 z2`l8vt+l{_AwZ#3CnxSRv$L`HEYx%Mnwp*#T8^v#6CVHTV6e~@3(T*l5{*_=R6JNp z4x_zqJ>`4Q5%DW&vLY&E?-MPBF$_Ka!Z48O*^3`f&Fn{z~9nrK|x?xr}Uc zPxkj}5<%KAYoEx8a*{`ngCydENE08I9GT22CgoT&UBRIt@B$!3MNLgXL816Z48Zl= z+??Xz@<0YXhw>lYrLOOD3k!-bUQ~U1=;I7UrSn*{ySuwBL9A5r7{nONKF?_lMqdXO zTPXMUmbv-)O@L$M%*>s@hGop>&7j6jPfvru)b-cFY*a}Qp?@Ayba(<`jLF*WqSrPz z4>m;V*j60s_`G;xYqB(7{&9QoKzwa9wdZ>+v;FD;zMh_1q1IotwztY^U8FdDv~Y;; z?CCB=)Orgm_LLA>B4(U7c$;Y|;p4}u_XL#ATg~jtgIUaQQ)RyjM}mTsW7z!Zf6o}brM-TqT`)%9VDn&0hV*p(&}7Ojlw^n7F_I*2_?wvuhuoKw8XU5_ ziz8-Yn>%I1#ckpR&j~WOhOKe05G{sBMJ+5*Fm$kD>snj$CL|=V7Vf3|`0;t@wzIsw z{oV0WCzF4DX(;=pu6JHuDA%2(>ah|#g45%QTUCvX_{_|S6l=zLYRty$Hff>tXQ#(5 z3$Z4uCALO69M*T=bX7TWPKF3hJbm!M%Y*Rwvv-{m{^uw7tw$v0ZKR8Kme-=18Gab$ zWRlR=cwu!_N{l%t6X@u05CUI}cfjYkyVfOP$R$GNTRG$4cCHx}OxDI{{XlUx>5f z-W4wG|2OsUVCU7r93@}jNt4RX?5p)Dq9|KG;X+GoZM;D(lU(15LW^6DKQl=)K)Lqh zCP!g`P(*vroED^N`?ZlsDA^Hpb&{ZK;!~|vh5j|Miq_O5|N2wP(d_2g=^Re zci&Qc6?S0Z0%uFoZNkicF4x9|;C z(S&-w{c;jPjFhBiVC#hkUZAM)d!8I9ZfI1vy95>@FbrP#U(zX@Ola}w1uf^6Qxg}^ z=f})1?2D^C_QxARLoVKG;Ycq<1%&yd&*{%jtw_%;XCAN5O#Wd@2+-FOakx$B?t}k$ zW#A2kF*!NSydu_%x>#DjhnkuU3KFMx;{>hnK9Gts-O<0$`%^CcEYBHzL?C{Ef&+z~ zC}T{Pjz50YG+UXO*6S)Q3KZFR|Ip{b6A5q|@Npl6-!`Vj({bO#MGiDtWQG4h{`D0R zN6zz;MG2YmyLypAwilE$yvf9;h9+M9nXx=;$6x&xkrCwYU%fjRN6UA?vb0^Y+_hgN zGyqg1T0EqTy~2cMx6;_sDs19&928}cO3rp{Szr!+F4E-FWo4Aaumg^R?Aq{ zDP#VvXidG8iAgG2lOB#%sr6k!vTpnq>VxKwnwm#vryJ<)HvZ0Rt4VQ`Y2UBvS~3aQ z*RQE|e_yvyLxajsw5YI@aAmf!QEwf<~9X@2@0hN{LezD=S zSC|Pm%t9Q4e3S95WVMb?hUD;!)`G#Bm^;?{<80VC>Fa4yl64+{RpXzyx(WwTbLm%m zBVGe`7or)<#WnnTnT*-p&G^ecnuDXSpZ(_~pmU2wt*zBvj(K$4Vdcsgx-#&N!MDf$ zzunZKUMPSPfwnu^d8_R*e_7k}&k(<4)M^e-Ji6v}!&QiTup z>Uzl{Q`zr-S4-<8Rr4>-wig}j$-3#s)HIICV;Q5kOWQ!%mKDW#Ju}(-5b(6%1&XRD zIzGPbjW&+G}#-XiP8I0_1#L1>CvulBg<`RL|@`=R^6#{ttCd)*xa zDQ-^A2h&MH$L{XjXScxh>3D+mVr&2q6@VBftMXmyl9CdXrd_+h$%@Xoe%H5$&d$!7 zClRWgQYy=;*_TV|qe@ET4Tx<%zF1kNv z$Ei^m4Cn>**M7OC@@$vqXn!Lt?KWGth#lU9E0MN~FJt4sJg-~sOK^5Q zLv-NPzLP!fQA={^GVbZ|VAHA%gO&8<7d*w_^O(ldX5Nu?wwFQJ7`lk0gfjlahlZXHQfx5|U05Gnut`32kC|Nej$9}|mfCga&oXsRw@lK)7 zeV|M?HC!)iqKd-YDmlOc5-giY`q=;9U%0q4V><$@(Pe-Sr9&B-M+(faFgrVQ702ra z0C_cC<|Ap&FD!abMks8p3`Dfe6HF|6j?$HX6{!uTv)*nO&H+BfO+x5p`|NmkP=`*` znHMgwv#Tqge%(dmwwP*QDcS-G**4cj4{!Kah_z@YOlkRzdg~;LOI2?it$e>Nf0de? zJckDNL5X38PGtfxM%#rpI)I!p&}Ado74jjjT0(}H*e@L&(Rs@2EQznDcId0 zQxL=bDy((V3%28ZZ<)314}pQ-!2tntje?1(12%ZeYGQPBV_Pi$+nyf;pzUjV9?o-W z{q2+Qe{MwQS1rR+E(zC82#f)(zxH~gg%)cLS2g{kOuhHl_$kx2VY! zy<(f54i%E<8(cnMi0m;ic_=rBS@|}&YSv4$;mQ1 z=l{~PhKg;j`;#&zS&sij-L)9$OJJ43Wt8xYAGItEVH9zkT3&AU#wBtF>~tqqR+TfV zMQn)~UDc})k#pcdO(ohAbn=`{0BdQOa-r>=cKL6N6moU3qK9zf6B8BO-9`Vib+2E) zJ`6xRZN+_W*aT2FuhoR;mAh{qv_^5o@);2VqTRcxb{oi~1$;Bxppo?7Kt?N=b>J{R zn&+8}ioogap3|B5B9%qmlcX!5a3@aIl!6?~#s?-Igm06*8wNp+}$+-Pa29jANU~hfW{_fQ9wbPT3hqR=M~1t3_I^r>8i`d`9hG1nyc*lnuFgu20f1;HO{i{ct(PxP2knKr5!%=|q|crJm0l z!=L(5WSy5c_Q4aJ*YYKek5(VePK(~9?s#l4#e#*2ue2iJBc3hO2>7GS0nYnn4rOS= z7pc~yE4DjC)bihugYd>W5EvS2ytg{cIwEL3-)>8Wpp2fDGfb*hyo{j8uk zIk(}_s=|LCD>VA+*EIy`f5*y(#*K(E>IJ4+eX|$v@n@Hp)%4ADoQBVnsGl{Ohk@H~%AwR|HHYHzvvn2nqlG8oXMcl9FNr zRX10!77vx+zV!^Y^}9wFWA(!SozzTz>aAiB@?P9oKB-_!z>jHsGKTvgpNm180h$6`8Ub%SWtc}L zOpX6fjNq@+Mu$JM=Tl>2HUZN<6zEzw(3L=9u2me|+}x~gY)q9b9X22EFCkn5i4xQc zy910K0=e8a${RBP=Vm$tg-98*iS9Gd@s!Eidr}cOCyKgnVtAdGu2Cw886|0pDOBZ+ zXa|Y(F4mO15smk6sM*{(6Ir_Pan!2v>tcc%X+*Oma!rpRQlXly`_Pw(|Mu+<5Xgvw z4v>pJ_heH@kk!{`nQaKc`A|4P!Yn>Ea6aL-!Fuy%z{_OmaA1*0dIPKDO??w~08 z1EGL=|HRy!Q|`-MtgE+f1p@WaIEUMRiH4>zIZPZ98y6rUKupK?zQk@(dD$#-3j`Km z<#A9mQC+DD%*t8X7I8_bV|yF^%@M;}m6~iAg3^lsy)iKolXYB0OSu*R1V{ zfW?8Wt$q1mBR2eD+Hhr8cA1dEipeApB3ZZ=(Kdp_*O163r7!IfB7S(zHR zZ;b5EZKibg%r&^|2AHYp)zKm{D=VuB=UEcyduloOhjWy&VX|{8v!}5g;vFyWy>bku zV@+g7`Z-uwwgh3BULL8r&J8;>6lqZa0v|nojIe{R!2Hf}Zm`uPhf$ml-#M%HU;Va( zU9O^q8$|Osn!Ep15rkJ#I@SqRvwDANK9y3q5H91RM~js1Td#iV7N{?emGCp8PwwdH z>CL-&d1E`zUzR^N!%{F*Fu8MHRfU7DbWd;@h2U2;~?G zB+{fGbid|=vwZLGKU#V>$7gIzlgV}I+Jwix7D_spwi@)o(5x)0Lnhr$rr>S^)$(IP zHVOqoscq2-yRgU#kMqXU{mFpn=${V2gKq_m<4lzVdVGIFqyy#BW$~-iuUDx{#TmV+ z3jC&hH$f@T+vxf6<-e{1+hJ|A2&zmopwCvc*yNa|^U>Q-v3>FL?1~0-F|OA@1_?D6 zpUt>~Z(YNJ*3?5-t``{Yl1&M1FLtsE3y)Brp+JVH1r!u3fv&*ei1@t+nwrg8!CyHgkGRK?rgQzOd5mbR&flT7Rq7$Jr9xDay*zD?Q#6j* zOvLRMAYK6)pcQkydw6(=gr&?!3qx9YDo<)StVaD(3@&tX?<8M$8zuy5f<1W^jP*OZ<84V2(ng>A<|Q~e#QYjQI2f9kuQ$7_Pb zwcn(Is4rZ&a6gx`70q`*|sN1DIY zlFkHNh)>^gGvM*^nzpGW?)H9qOb(i7!_9lID)XJ^v+dD==8emq}Nrmuuq5i~KRm666 zy)V*pW?I1Kwr6fxdFq&(n_E2XM-M`5qi?N_K1&0M;MT&<<9wd6 z_M#n@s>!Jk!K?SEeI)=In@)X16`K$9$tQ?5SDv3*nGR;Q8-$5TgA@k0Oay`=>;eM) z$UrJ2WY@nv{>`)^c9SD0%~uq?p^@94O{*1OwHwA6!X{>XGdn4knlrX zPLOarLCc~OFnvADu{I*LuA~*S<9Qz^aGva6_xJMZ%yA~!1Y#QDXR5F(xf5zTu=fD` zpB-7$$KRgJ;B;Z9|>lMMD75>4HkuiA)TT; zWJ;z$Coq8=6uvQW#kH*;0^5X5FaM8NBxhVz1AJt)QVzj(fo&`vv z@Z4@mvdd}Qfd+*DL*TZW=+j+IkKKNtPE1x>bNy+EnKtG)Y61Bw#GHd>CkNN1v(j6y z$}EeVc~{)&vU`Kx7lXart+8z;*)N7YIi5(nn}dq6)O8Kvh{y{-;A3E}pxaf0g9&|Y z6S}c*uIOPe0!~5Ec#442k^E`Uv{PVrF6vynj$_cKI&qLqN_iON?*3+=uEpO>^dec2 z&N$0@CP?z2-ISG;HMO^=WM_AEvz7=1)hFd-Q|1i^r>3SRw_2M*!vcdeRcnHzBB{> zB&iFvyieujflu-StT;W|MIw%Da+%97t`Hsn)+)WXyD~WF=E3Ah<^^%eJYz!gB7n5PD#F|}n_PRs9L{?pwBF{Dc$yE_VX9`mzvvDSj0o2%1txW@ZIFy=yAk zF03egQidwHyw+efI1-2wNkJnuMk2 zWMkQSJ{BeOQ5wY{+zUCb(v~`|=>vje5Oe(ux<5ZS{)7^ava-a`L~92Jqe0%jXEE|R zbGOiZ*gHC!Mn%g($v3gL|BqH_6t~u25Pq+Hxo6P=p@$YybgKNzu5)TO36-#8wTJhx z#+-d3$0cA7+=o~xR@LO>WOZb~{ehCss*=w4REu2_4;MNU6=0D$oY`8d0v(D0SON_; ztIHtce>iG)Kv#mCuUr_D7~-e}1_l~sI_<5h`H?YqfR3-4HaK+~=#1S$+w|V36*~t< z5S&9EP&Z-wCF`@uy>-^zFHeu^#Tp*5;b7`0vn|WBGRi&!4GAS!Y_zKyd?A*bfSJ4-iIbZq293(jls4&Ni_tVmn=r$6x`1?q2Yy zbMZMu6H8VyOJfAgs8M0!M>oM{yMF)v!3l@Q9-W)8gk;?Y^QMI54?pxZW;C&a1j$Gb zHzHp!xKd+4Izhy|7zwmEFnO%0(v1oOKn`Qj@#a0_|F5Q*>%=Y~f(A&uG#qbKb^`X` zIS_SmaRFm#*b;USj#OMUPrqCn)E2}yN5EpP*az$KZfR z=%6=A4U5^+ysI$d@{@9sMbq-vjn$EFI2l^?bHKb-PQRSq|3QxyRd~;aA;j0?>+!i& zj_Pv;oL`d)q@-RD2oQetQ+67PZV`zeEDI>M)4nv?H}_|O-72c8K7~Iydmleu`VXM-EtssvR6Dy)hixAu9u^ zGmEv$@yks^SsTR(-h4(Xy&>c|*-;ZgDXp zBBB<$y9|()oMWgN>ANL7xKIiq?gIZ7^C50_U0P3+De@5EcXV<8AK!`$itFF;^1)9$lt@^AZH_XSejZMn?|Ae^aqa2 z`{>08_T~zU`}=FbGenknx-Fj{C3p&7ROsZ(yr|Dk9pqbFeE(=~Eoj)>(O$?>&R|*< z&IqX!z_q4UR)X|sLH>P_XDpX0&emdnulLu>>p+cKkp(9b#1A2Jq{%`fhZJ_2Qo3@% ze`jBDe&)8fKCUrS($m{pG8-y_)FDIwhDxZrv(()OI6?DO{8#!QD9M(^(|8C3Ds$Ne zg9!&d5>)R0!u+7G5Qz@}L0T&l6j@N(%#X+5Xxn@#!25YnJi$D+n9Y}&H zEyQT9x;fslwX@rV>=Z<5S-I7|L`5lQbb37F)qJ3>oiM$;{MP+sv$1}JT{cD+?p&Va zIgkf>FXS55fmnp6^Q(I=Q}=Zydl}XG}w@VNF`@{rICKSyuvGTUj}3oMyJuVB)rZ->;XT z!?!uQE%&4ZGl?B}uduSQLBuYEFB&XtrQ(E2WOAe2b+@Lmv2kDkLICpd_p8INKWW*e zg}A3NSVW>HnA()}HR%0&xXjnZ#hHTY9~m0{$l&7S42EqU=`wbl*D3B+y}$IRHx)AW z{;k}l!9Zj*v*mw%*_Zw8|JVsjB?Y7=u=S;Z3L^F`gs*PgxzoM(4lb-P#Mc&q07ACQ z2ab1H<9sam5N+iopqw5#UF#naA1@2ihzmp(IwudmIvu>R=dAss^D&5-afBM<@`omb zel$y)yu=xjl#rS1TJMaDja8d|>95fPCA7<@*1 zB}3zl&CSgqo93&ImKbzGIe9zqXBd}x7LYq!$#mrm?%$+VRvY@Setk`!cW*4mK>{e? zuzo%qGGcsOY}85}#i?dny??k-puOtG)?W)_I`F&CWMm9F;)MW5c4umdKs81LX%tjF zns~}C#xf{Oe{?FDASeV7Q|qXi!|&bZ9B0xZHE%>eig;D0sij~0vjd$jd3exe28K2e zybwqOF*&duqQqGH69Egp=}wX=7*rX_Sx6~JRFFDWd2f?2JJFe@QN#@raYmnk3D6wC zv)cn2R*`0+XaDpk`O}zSDCqmrw;_;TqFpDq=384e_tR1nX5jVvC@H=Put0PV0zDq#&XJkd zVRi;;2F)m8%%@L^|MV0VMUPkWke8A89>gP_g(-5+?m#uSnQJ1qESaa)7%fRNhYN84 zM=CzqYL&^@{U4`z88v@`%zKFKk3EL&2q`kB-Au_kGngyy|pc7L87#R z^5~R6%@#0Gu&}VA+jdQ?AZ0d6bq{ba$Dr`u5bhXE)`0x^5b!$W_fT-t60)lxFM_z^lPVyU2bCRkkVJEVq%Cc4MEhp-Rkd zSnB?nIIesCK+xGKEykQabxC@;t}AffvI`t?hHdzewk_C56G9MGvVE6i_ZksP zM%T8=OlD}=lKB>wiC)~THqzC-3I$wVgnS1&*HTXk5nx76@Ijj+*l9LEV>RD6RlrMd zjegCY?2_z0aN0>P!XTrS!bwd8Ar4|%-Ukt6A~8tYva|b7=lzcu&;Z8(9jymqPHwvy9cuE>lschfQ+X|=K#?bFp?cWcK?%{Y2qD;E?*;KV?O((7ceqc423NA z?pwu8QXsuF;|bsQ)54z4^RWmom33*H-mX`Bhj zcXhZ)-DXt2rX+>cg?kFYxWdCriLU?B^zDS{HYytPu9IQj=Uno77DmmB{!Ygj3K*Zk zbl}f3x%R(2{jxg8+-!h{pyYmxjI1XS9IJv;GT)~Q(pgNr{>iz<`HGj?d2a5M5f7pQ z!T2ec7xzL=BhxH|hURixx&Olfas)4mF-lAc<_jcD_`22Z91+Q%Pe1_~3&;LO1dE2` z&Ye3Cy6<>>|Nb4Nx=>yhfcDG&tkw}y9!Wrft6e&CceST`w@P^26Tky z{fcxD?E^jjlgjtoQc6%8JPEy`vtdMt*Zsiy+Y-$jX!P`h#)H z|#5^-9;Au1Y=gHMWSptt%6CJp!_Z~K2=hLWdR!ZZtV z36cc*FZB!|MPvdI&PwT5Xv;{B0lrnmAseHxeX;K3Z`aNr-o$D7U~ydW3jgxObbpci z=1pGL{dEfz0yab9;~B1V92q5(t&s2rqc%hhW~ED`=XpUmZeUMz*9Rse@|UV8HOKl7 z@{`xDRW~&^-yyE$B_tvWL4Y(!Z={)j%whbG7mtj|90aQgXXxz~YY?X7g`}4iBKpwY z(SNUH8Y^HH)eZEUVht9xw65;Aa2Q=R3knUr2Oc|ddcP^HpPuO1!K^g&q7NDS5OAUc z3Vmx|6@~?o!3b%9wP_x3D?O?Q;fm;@8lZuim;nZh!=jadDN_XQ($Ud1TvpN4gODQ~ ztQ$U9PpZb}xf6LooBN$LIw?PYUh%R487#;(R3^3%rJV$JH4=S|T-3-%G4S#1K|n5V9KC+#mq%O)?^?{&q7(K zP5vBv1fHo@raBG|PLP&jCNSCyczC&hnYJ?pEys$9D#8%0M0_7iWCVFF_ojB@u869v z)K{1&+6WWOQRIX83VjFn0Z2V^l@o2>(xSH|Ec1OU*9V1)pOV`!4G%ltHGgxy*xvTu z%Zo6B&wPj%nOFr_%^NFgKAh_d6k-!F@aGb37}*4swsA zcCGLjG<9iP+uV$`EDu6L!l!a_tlt+aZs#5==r*k&|%pMg1(_c z12%_${s9pnuWhZpj0bmH#!_hZURwx=Hq^pc_N z&Jw2;wod|^Qf}S9AA^KkIz%==(|{dv1Ed-673hC}JA+KKIt_219rqvDaV+YLw)UoS zUS30sr({^sO2>w2z^795F>pcnZXhLlF62}|>Ep;>|L+RI-oI4KizoxIF=kshvJAVu z;^-X1B0Fh=!%Vtg^FSUz(YsP&U}s0siCuYrTe)GWJK1F}{0T}GMrcX~p2^Do05t^A z`}x^1&%f0km^qIga*g`*3H#(cs%m?8b88DG$$t$Ia4!P0mq7tSLQmv{x4v3|wk?x? z4pKU6Vc}^%ltp9{wYskYC00~u2@DHkXJz#T*-k?PaO0%sF&C1#gi|hTjW{cZD+mA@ zKK@5Qqp^tb3Iz}|JlE*FGr^!tUwg-m3bVN6zX3mg4G zcaHA7UYJ%D5FjIn+Q6QlU0Wlmf=^FCM3lF7WqqW8BN2V(lCujuOaYjZabAfg7Up+) zW)hrkTcSiFAhf89>n0uXB~vzD2#^Z3CX0g2n zCgbX4<>cPR)~^p*RY>)Zjg5uzdZ0=MM4y2;RfBE+KXnv-+qtJm1_&0Y3*6*S#~fm0*$}4=iVXy^*!hjyzQNWoG&bIXctjqo zn|qdHstX4Bmg8UIEdK`LGdX(+PB`Ou;WN8`M64qi4%#YP(Q4zKf}PR>^S$~OP+>sO zxNP>nFiYIu3t|x;?9%!!!H@yCX`uA7Le+MArt-~-?zBK#L*HFk&&AlVCpyJiDOE*t@XnScM?MpC>;)Ns9c zmQ*7V+6x}cYm3+w-vud6f3f2$5@!;{RN)}k17=opKx_knRW)-k4+b}&3n&;G-hj9c z67b%iaLZEMkW+%p!fi)38y8r*c%<>(Kc7RLY2l4)Z_uzRH-gDST4=*}v9Ym(A(T{{i5d4 z)-*kbe<1784#)&DhKK>Kf_(japR~Fgcy`TirS#&qS|2yt^+lc7UX<#AIkiE<6^v({OB=&Dw%)H>XA=U-X2I&wGL^D*~Ky8bq)IN*sH)Xwk-3RtaLXiT zh2%a8a#5zSe{5kP$j0zup>-|4=A2w#qeJ}^bNAbPg?;zof=;{}&rZU9M1ul!@23Yw zK13r5m+y8I1kT3O2a!Q)IilJAVnz17LCr-1P*2*uSVnc=#QWtY&9?&Rb#oQbN_uzpRQ##Gdq#eje2a+6U zZl0Dpe<%87k5E~ZZs?Rj>Zqfmy1hGubzVom{q^_Z=#BzX7*?4Oa2AGnAWuB)`A zqI8EERs#<_zk_F29OnK<@d%xwAln7cwm?c8C|C9CtsNbXFO)iJkxrRXgr(D`ZZ)(0$4SzzaOdD&x(b^fz$0*!hX6lZ zw%Y}vkr|E^+dOCvWJfMGj5#AJ7btZ>7AxNq6PZDrBy}NyH97`adr3o8p(gbGNBru2 z&t_ZKs)t;JIpJ6~dZ6e){O`HC`W4{t*T7Q;5sjRl-b_S#W`k0p0#b@V>M<}bxec$; zktdK20o`X!OB@9X&2=76GVwn~G~^eKe{A>f{ngavDTGwTQ(p)kUZ9om6oqQVvs+Q= z{}-y!&m*GWUJ&?>?}t6>FICpab>KR;dFZOcZS~!!5J=At(~`P7UeSL6t!-ff$cgm` zH|{V|Dl2p5b)}>hCCfmVmYn7XYDpK?+?Z3R7_r#6f3yph*CD@x-7)40X{M}XohPJo z0-FtU8H-L;;LRHi`R>@xHJN7U&C~@#+GTcjwpK|+OUX2`+-<)Hp8Ehc9pb#hx#!4X z+&e%sCm?kWPY+&#zbWUVrH-N{e*p+YNe zfOeA#TjRa2FQ9c&ZI4|gZTC$nYED(%6(qj~UdIFQ?uN?U1fehL*1RVGW3^!b$%z5y z`3y^G6A&sdU`sz@x|;n-w9a?e^XxJ62aH?Itwq-2cZ?mpKKS5KkApDP_}B zFt0|6BU?lM{r+b^;_ZE#yGIVN%zr{Xcjo$qyVRkPfDMq|0-ViHk5*bw@4F4; zr{GB}UDc7179hhnfTC<@QF&gG;ZgtLvNSZD5Wo%eKyk8VxS&h(34`I21WD`$ z;FEXZDq2_ojg(eZje$o4kks-9L+2g?7_5}Di$tH20mm2S6oa1_3{W9WH4zFS9U}de zn6W z|6UKiT@jxha1k{;+?D=XwQ-|Mxw=_MHDGXrE;|IXjPP?XpxkZRHU>o@8>=kX2$RLd;jnI zzy9xay>nf2&5Svn&iQ_y@BQ5OXM3y!oTbmr$l$oE;CUzI#^6cU)YBeX{@JUqN9eU5 z8?Gwqs30X6d1)9ho`^q_#}J7@?#9Dacr;xj_q_Jk0jjK?`9|^kA;kkB2wgp?j}zaG zMgfvz3=MUa5gs;B9!tVdne5=@ASIHKK2Jyw>;Eux}l>Rd%}e)7jS5@tag?FF(*qSX5ck zANPb1tQxI(KL)#1yAonqXtz{N>??HE)RFV(9l(o$n;FSo#y!1;M-BkM(nB9#8@m*x zIS#*6UAK-Kd<8hi4Z)L}pdsN=oJVX21}9{Y~a`jKh&?e;?lE&B+WIkh2XzBtD)+d zF(Z#kKb}7FGcD4IO;}k9#Sw99KX$-+_CxvDY_*`@BE^z+a4K&)u{AcG7V z#^a>-zjUdHWM`m0P*=4B&vNnct;gpeuOUfT!50`8`7WgP-ORnovx-At`gE18TRS65 z9-1%1w{ONIoRA3Ja1a2vse*!&ravls4m`>8aOvv<0#587!{bEC?`EuM=L?&01R#=6 z;uQWJI~*50_O@u{YQ6^KNZp11Vi&VOMv4F#H|}DPXI3u9hC0=-9SgYwCeg?~=F$kJ z=guZJyAl{5O-TFXo}8Raer7T_yYHSZ?1^UTF`4?{IJHdJS5X8yeiO4mH_0+k<4Rl$ zumoOGK-yHn&j|Q%9TvM6#<9n8U|3TPyHL=r5eD%1Ls!=_cmVb*ek`1ucO#W~>dB4c zZ&BS&cV<04(&KdLryG`HIX6S+u79x=EhRb~>@WU(o^RrgJ-_1@`7C(0kHYv)#q~qS zt7R-Y?CM4|ZNOk-RKl(ZhtBt;I^aEkF|RrAtfe-~2U>yq> zxTi>Q+}+n>*(X!?;3~&myD7pUH6g_U`sZMiNJk|ti`*9BdDx5S)SBzhZQqu!pIy-s zd}>#{_X)e(4G)5?viE$94i+>x4+!}*IAkfaB45q-cF$g1`8YbA5&dAxt^-YZ7iXkKb9y*v?#jN}>URNH(cX zcZb?l%o8UTadSD@TDJxxonoAhNP}+ksxg;*qU_~=x;>$NxIy8{u~G90QswEJ1-eER z?v{z3_PE^H-F+P!Ow#_R0|Nu+F+zYkf5T=E%~TZg_88=Dm6V79KmmptFt|^;V;$S= zGq26ey9(=<350QaZ_57oD$82_?OGK9no=0ouU`kUgdPDt%PL77F`sM9+j02WnpK>d z=h=;B1U@!j_;Ti|-=?Hyq|Q4L^4K$7EZpN)v%rmFP+~{w#0lX?Dg6-4%s!oqCw45J znKj&_=Y3M};v;jb{&Ysb1UDd{#I+I)n`EU&VkC4_B{i-9kX2MwX@15S<_zJ&qF+|L zIdWlp{A-J{!xu!dLtfrg5Fh4OQHeT(LW5&fQRsN+VD%-O}*b*5e*84 z8?Jv-Q2)T9Pe3Jd;o?QzeWMUPE;G8z@>nA^h3taU#5Nj17dGQqM|0i#O>+#p#}ED1 z5(ktXYR}Zvzu0{KF&0Bw7mUU>{@^R+oypdZ05!lwAcJ%fFO1%CedY`?;_$5bimLmgR7_XP9E&@{m45KFgc}14t*C^AH>$`VzP>8x z_|V3NBRzwG6+YwgwA=q84)EF`BD-=EvCO_3>Y9oJ0xaHDMDyT%qPn~K`}(9X4QM)X zdb;dgOeoIR`)0BDu4ziwipN-8BG!dwK5P^Nd+y^u;$T0p8yg#2RNmst%F4p17LV>n zdho#C^GVZ!#T{H`@OhHLDa&Qh78{91^md6f$Mz!NGHtps`=eW$8-gI%fc7YlX1z>~ zv~y>CRDsvvQG^0Z#5OP-wlY%3xNg+f%yelj?>^9zNwLRt0iv$vPM#C zLf4aHD&2|cM*pB-@=%BD>kM?8W~dU4khDu9pu!6%H9s2CeC%F^`$ln<`5++6hXuhK zS|ir09-7B@mZ=F>rP@B*R>p+;IZI*4V!$EXcXf7c+sY$ilS((+Cnmc*Q#nj$PqqAnBg9FDiD9klHgLD`#aLzp*ks~eFz!}?!!JIi>#^OQ2#`=3RYK=h3^3Gu z^qw2qM**hIB4(ko=L^phnZ*A>Rka|LBri)TLbW11HMqzp51JKkXcF#2jOmZsi!VSS zAuRgH-{1V~$J))R1&vTCN?lrh!0=YPpN`>DepyRht6$PCe;ljiG~7`sS>IJyT8d(M zg(jAE;E;$INqp*n#%g=0E5skqQ|+LP3$Nbi;NZvSnH|3~2K6cBlY?-yvRQ#~)g7}T z+%U+_qSMsvXWR2o!MZg+i%)|d2KWS1-(qV%g zX88^8Nl^>)5PY1GKHM+X;g7!8UWV^lp&c%5LN`VBK%EyzQ8c!qsE5$f*tI@gC^*jf zocJ;!fX617XK6$STM5>NSH@y$T-HF;*N+7@%#m*YTKcL54MBd3 zbjXpwJp5@NHWnR&rc}R=KC0j$2)sj;qENUV@zNNr*LE0y;pL=M03iQMvCjZBxC>Ax zamMX4TBeFv(Uk0qeBgNiK#9Br2m0J`(h;Vx(@;m{)y8Hn0Ria7_ngkIrAj&!esD9* zChhN=np9zgNUUgW#Y$}kQ+EkMt`Cq6Ji#>4y0~0I%YL!6v^3pG0#MGW39+3~_Snsf zkWMDhdeR)GKke8j-j(|Eq)Fizp~0+GS7Xoe-pwlj=fa}cl+c~~9nJjs&LY8=e0>=9 z*hrsfPAKR-z1D zeDr2tbVY@>`Qi|Z;+L?V_XC8p-?)iZFtB+~phS1zJFAhlu9b_;__%?j`9RX!wbP0t zA2x@=g-g64L^FCd07fvEgkTB*uNEEs&>7jdjjuF@_CGH#pVl`ju~l=pwkN%24eAJY zN$`_w(+Awd)WV~7o@?qEBj4D8PQt}S1uWts_bK^dFK{G!KH%gXa0$FxGIuWb# z&X)9a5B7SF#XA!Uu}PkO1%VLx{qs>eta?d7$pRrpULNi8w!zYwgz+3wN%23u8E^SFjHbQ8tpXJRB<4sDPLIyye!*D}aj@j`p4pwpg) zA`PjBzA7xnC3Mapu-NK<3r<&|qGtB@v;e1myVl79+~W5wS84D6z|657*3@`ILTvwxDP@sM&E4s?`gaYz#K` z+nxjefb9vZTRmG>aHGj9eHkGbm0v01&)xKdvznw8vi^&~-)2cfl3qpo8jwB;BzrT~ z8>~um7|^Gh<8jI8Yw)bKDG;pCVr70eqLH|D6SEIy+#R=we23|MEU5O@H~lcGuoAtY z$T%Ll=|QvXd`}bPPyI642kM5e*Mon|^2u(f#Vo5g=lJp0LPFdi!9riJeruYb;3FW8 z>Its>P085Mb@XC14X+#>=^qs^_?^MexhIU(TJ8DciwD|j%xqu9zH%uq&6?6bQ@+2X zF_ncKV7KSS%_|I_^P-GHE~w@w;#+A0xFsPf$^lRbv7Q?YAbv&uk?;{;8mKg_YGoN1 zbNH<-uP6qh*3gOqT^hR3h+4rW z{A>mg4y*Y#zUDAeiB>~Ok%#UjiYbnVfvdSuT8EwfDvhDbr37U3M@&%yX)e$t%mxtJx?p zFwOeiE(@O9xP2a%%Vyqa#*=|eMP(EPd6~{ zc1?7hdYUkKL7Usx=PWXJu4keeM6X!On$I2-7sKV0ta}+$75d-;1Tg5u&`b4bRzvFT)->)(8|w?a{7B&d$EaEUqIU7;r@RD)&_nOV*&~Bcnp~ zb0$PY?@Lwo*-B7ZAem^ch{$gQ+9D_I{Kbof*hbt!W1OJ0Pk!{tss1h-`BqWaSGWww zaL!y@501AX*s0Fub@5a@^O27Kf>TsSJPQMsY7q>tmBc0WcQtpx@eDW^3H8hMlC8;q zIQcLKYuzB*Y^u>vU#FMw>a3@O2*EIHa|B0Um3bstFp3+$$3{|e=@iz{BEDDupPv%K zJi>sYXLLOvt<0<2>CqW6?Pc`AT?!o=APz5H@>OK2(*?5G5BuXJei zemT%ZZW9B#cOGb#cs}u>y##kN5hN*O)KvhA1BZ2P=~CcCXK(L(JPed>;qULL@e93~ zoI=ESw`Yb&B-DHaBD)9R>oR|Gef`6r6&LW8%W?7uQlPc~C5RkeexU9lnkUkilQa)h zrYYVN{cX|{);sA>2ohr$w(ZEq`ZR)eos{9YLWF@qFrN!$xqAC|S)58>3`xuGj66<^ zC(WuAb8tr*+63e$ZPb47c`n7;oU#9`mzOD4VR&pglHScrg4QDq0}L4nzu-aizz}ey z_YgXm?}KHGn7UE*e!rRp|Fe(zzs|Yr%}(K&qb(vSSyCoic=g-k{59f*6-Ieg;W5G} zOXgqvFNaZ1n?7C3VTp?PLt`d{{b~@nKv(P|Sr7w=$1^|YkOh#Q&3*Rg7`$Ib!Wb9u zN}@>l8r9->~+GXQBsnh6V_MU+uc3Zo)3{$TsBr;QW>2=_tAEMAz}|g z!qLOf&=z9R+m3Z&H4H3g=BklC6DWnqs_^`d87DB+5ZDXBps#497TrTjA)<;yaew7v zaDIz2NB*4=C-2QzOliq5cfm03;jzpvis8)6KPy}c zyPSIF0am9Z{R?jOW*uu#Z6JRFpA_kLwskf0#QgH;;jRJqDs_>9`b|to?m-#8P3NO`&8x z;u0_noT%6*;ZOyjeQpt}lyc&Uhpo)aJ%iIqkcH0`+2O_DCP4N()D7w-SRj^nR+}zp z3lERMgTFG`@X-Q$$05rBDhdT{>=+^qhC#Ocl#Iz0x$1LC`=31I=|@cx1bUe10d|P` z14pW68q#ooW)b!}(( zVPK0Z(#G~*__H(agf&*s;J2LAKNVEDm07;NzTA2oqa{)k;Z7iF04P(*`1gRMfkNM* zP^}1DnC^}jmqS8Ail}WuqxN@S>(|*6Kt1*o`UTxRJz`K-;)UdC(K`a?4s1t~b}yiS zA(fOg6r!A~Ku1y|BU=5)Jbu-~&C34=tqhq4C6emkeP}_V4oGu5l`7mS5y$3#5vrOL zfB3@r^BW$HcgBv6XDA1)OPj}e5Dh8<_s!U6-^D}DxBA%8$X*Hff>iXNou52*2G&h- zBX<|;kh5R=k?x7-=l_?(&h*6@`MJ4d;($OKx~V+?ddzxCi;D?jrVLsP#gf@Wwpbwh zBKEN^R8Dajhn61zN@VQK!%p5(m#ILlG3}u^)Bz|`Kw8NkbJofo`Zx~Z!Gv6i=N>jvLF+!|V2GCNpM^YA#XOo&1y?dKR(l$UltOnnv3>XQV*oYd1 zlUMK?6Lc_~`JuNLVzU)#6H|Z2v;L#;h0-N{1pP*K35~n>-Qcpd`x>Isw7d7UEkddS z@Hn}&iHMQ>J!qB7B?K?41!(LIXmxVbwmr>oE_pf1zZB7OuGe6{fISC92IRt17gT#6 zh2s8mOVvTwJ}$XwT?vV{bRVGycIt zUJ96-;Mk-O<0vm1r{Dl~)3?c+AzJx&$OMXU>KRny^0V+V6ayd0#!w70BM5f4$(giV z|6}@gNrx{CSFFs;fC0(+FVSweY?+yvSVk0@h4{fol|t|m0z+3fhyc)fwC~j^NK@&6 z4+c0Bw^OIaVZK@HfJ~3iB--UiZ`22J+S=QZZ6|pt&-flxeBgt3Ju!JT;m^jXWbONG z&PQW-f5fPr1HQths`nld7uN4wVQ}D{K0OzP5kRo@z}(D`5CIc(bv~zQBBt8cl+>Rf&6KC zDXFap_a?H<`y@4NUnx+#myI2TF1u3kn>;RS{&~nF4}$eh0k!ly>@bzN1T*WmADQCK zadD#4s&PB%v7EG*^FN#qX-H0)zlNfikN(44mb@)IHV&c<*fYwJT}{qSd@)s^{X3Ga zg9W1UItwo8X; zt{~krNjzbbfdc{OC|=-ydVC+tL=Bh!fXhODBdmemOlkhmFR zgYcjThvUM0|GoF{ecg|7&QH^ML`JNrdOL2n@x}$YCVV*@R)4 z=2d@HPgZOXOTXEo>x z={9t~N2)%2cmP!aAH~K>g9QOPk7pq{>w}Z_%{E;M62=Yl#!}RFI&B?>S3u^EZTTMb zIi&psRcs1r6-mFsOarzDcDCS@0SuFKWo2jPNYO?l?9$Bz3sZvHgOBsURrc80vz3Um zMEL(+=ddsOnIEX75$lnme(V`bp#W`NP-dlNz8K-eh1i6iLx*Q*IN-NU8-y8T*v7a9 zh@++BDL^iwnNS4u|HQ_PCsMi*VGqm6Op7-E0dkxGd7~nCBEhvf%(VXk?$mzHdJc5_ z#>o&ylsR4-2~Skd)3#q+Lh|7)D?d%gG<^e#pbG6PdJEs{Lb`5?5=TjCkT36z`-oFs zSMeZx28K^$q>!nbPJsdO1DCVD9$WOUs`=onj*p)v_5uEHZk(k+TP@IOWKIOF+~Aje zu;9J*@QPzX5J)*6KJ4FD42V2Dch`hwI#KB9h@qh&oHg2?Z<0+3NJ<*sg^%^kaT(~2 zERlYptXcqs@C0<#Iwo|s`MJr)gCObj-8 z@VAgaBbIbgRHC^KZlH&c&kgJtNUoaUhNV7r>Qs_KBjPBw*!qyIY{$Th7zwv#P*;Sm+YbyrB>PLg7zODh`y>_IE>b3DJctp-|~^N0Ny{?Ila)#@ZsTz|Fqgk zydRl`q%R;hl(mg`>PirQtNQB4)9u_jUtd!_l!`{MdD5sXt`YHW(V*dRjdLtO zm)W2};0JcH3??ZH+RXE@sSAGM*581-2Ra?uLIF5d#e`_}e6Z-=Ak)K835aZ*gZF^4 zJei3bHAadw=WTVFHL`+dv(h~mFbwa);^&3&iWlTx{x8q;O`x+Xb9@Pc!3zs;#=B97 z>Ugnw5{W&e&|w5TF@qO58bH^97w{>aHiOE$XGtxGcDG%p&IC8@=ui`;>*%pCsIT3x zUcFj&d-vM8Kuw_&O0uhnjSg+>g#MA2L%anO@ltD2j*P@}}xc40* zVmXf;agYEPms6<8f71cOzw%KKHXdfnWGn`F4;paHfn;T=)I{hsyzrk;jwCn*;tae7 zaEB0|!bQ~Nxg@I|u_t5BDAz%MMrtFhSBc7Aps2(evLe(S|e8 zEf|>f9bH`TnZg0yNglw$Wl-P|8sR%uHL?^R3Ee4$^8;XPfK_fc@_jL?<|ftQAc1^r ze!rbkD~l@vsE^J+6#=)UI-;hm%#Kyg&_B|i2yb9bB~m*|opDZ-Rk9P3pime|zJXW3N_Z75 zFy;o*5J15enly5{P;`wR4oz!nhrJplvFg6C5-b>qkUuLi6ucjrBt8Z?8L+zX?F$@T zk%Ee^kBu8iWp|;`&&7ju2qQHaw;_0tAK9WJIUe{$!$%6^L;k$xEh}80B$Gh~Y3QGkOQ^_py=m!djdls-7;GDG40r# zn{g%bs_|+y4Ehkpj;%+YALR-r4NgI7HB@Mp>CSQR^}!wgfB;&gNnn-a88eC1(&x6H z7~+wVfC9>f%7X7=w7&*CA;KbWpiJZq;HbDDunag9UJ#Wqjc$TsivhRy zSU>=akj$Y})_ELXL8w?(>H%Y-yD3gwy{n}s)UPcyOTAp;8j-w{UM#a(mn!( zJ4Mq#e9VB)^!d`0cu(;pRSlKgz(79ai9 w{?!6-ijx(saP)zXEdEm;_`fqc_pcrkqO`p-b3M*jXE4^QZdQp^Hu~*<0SI)}H~;_u literal 0 HcmV?d00001 diff --git a/docs/relaxation_003.png b/docs/relaxation_003.png new file mode 100644 index 0000000000000000000000000000000000000000..eb4b6805cf8f4a5d618d7c3aa167b3c67bbdd2b1 GIT binary patch literal 37707 zcmeFZWmr}1yDvHkDJe-s0YRm^8x;_wK|&goM!G}5AS6Xf8bPE4L`i9oPNln3QbJ1D z_wfC%|Jv(X>pJJdIUn|i?WOOFGMRIXC+_E0_jskMEK7h#g@;0+2=2>CtD{ip{wNgM z3=S6j3;*|t1^Az^i_Alp2lnPJ?j}xVC?yjYhbQ(fPplqYcQbQxwz9Y5e!pUj-?-y{`J6UjEKRNpbZ-VO}r{j!55t$%=&~hZRtx%{p75Am@Xm}*APkQQW z?4Pyn40G|~hx+4%`1@CUt_-ML(zUkEvRx~k(5oJE?X-K8KlMZ4Pr{;lrDkEQEk&$G zp;hH<3q2E4PWrQpqWE1$f1W9#W1ypBbS)owbTuXLS{!v9iEJ-<_Z-p0W-#I1#i4si z-1z8WLKOrn{q_~Hk4&R`A84!hHLSABG@_%0fBlLgfxa10= zIrOHAiyh9qsHm#SRL?y;7`L~t>e`&F!o|aDY-tIMW7qp^J(#z~squH}yVjIYU2SdY zk6R;r4rhZF6D2t~BHl>_{it%cZ)|LQD`-#CpRHmsUS>O}pZj+mc;=GHsC5}gYd*-; z@Y(Ga47<#oG2m(Fvm;Y`e&$Vo<3@P@2gQWOo%vQ_hnd?18q9we4bA=s>`xhl*M#cR z@4N_6yej6w6+}dPuV^?amjzjG!E4#v?r2MIVq#wA=i5YC6&4mQEG|YRCx;~^>Af;@ za&l^GZ|ANRxQwq~<3(;^VWGjISvt&y{G@0$6P}fo72NM*GqZ%JCKOju&q&@CY+HI* znb>{Lkm*X3tQ-4D0&7@$UqMbT-E((oiKB^)O#mfeGZgmz{d@ZULjB6;_c9wsM@JWU z8X6k9QpLv)k6Xg8dU$$XqNY}wZwb#YHB=L*G3@P05nY|GlhiF3npk|uXB9doGnRSq zx{RxCZ_j0uXhm70g|40y8ynj>-c$fC#Cvb0;b3DtRB^ocF}A^17v}xY-2TdwK}rmW~>%&3{mohL*@~(Ak>!CJER!vfLnbz?7Gqv%p>Jezpal z5kW25QvA5p|G9}Fe0k5uM@+TP8{SH2{`A2I#o5!NUAXw9wl=w;LW9mkew(+v77@Z7 zl*rBVcl7pJtp3OvF{ymFrM1t1qLJ`<3-{As>1=^A?@d)&?n&|7AJj&ZQ&i*&yn~{p zrM-Li?ntQ(Wr~RFoZtBgZD$<&{C8PeeuY0sLCBF9FSlnD5TMZZ?i645&i8W0sW7VZ zjp2Vkd%XWsLGkB!Ij3wSO+iZ@vI5kuvgv%r^v6CXnrWr&(pO|xwMRF$&0@my^z>X< zUQVit@lq-p&iroK*3%RB)Yd$}R!zwC&ArUxmE9*ViI?0Dw@nTsN>X_Ah&~}9VTmJa>H%4Rd3R#e>(|#!n!51D=_Mp+V&wx;QmF0h>>ldrB~|f3 z4LhzoKaoV;i=zs{(AlycN7q7vUmrd3bq!HtVGL{Q2yNm046YsXIw%`eYVj;DLKuLel3!Z^;9}9x@@mf;&Ysr(*H|0}ap|F}_ZLT~xS+Ds$#Y-5*0t2ly z+gomt>KTYdKy^8rHQ@&ajuZJOuGzw>O?m-=xT3nVM8;GPbbt7QN<~FQx9o||#<)@0 zlPf6r1VKjSWTu@ns4DF}J?4Lo_g7p*&@nKCpC0oeR}5umaZ1@Fa;f13c5!*RpfV8- zj`5H8_ZM|ryApWOU>j;zmV0M!)}GiQe^5(3DSCxwiW^^6RxIP#bQ;%3znBHn(@EEm zP*AiK8dRy~4~qSsaF&^hrm08&f${JKnGD^H8<{P%vBF(~j&ssO1$q`fHEtVYP5~K* zhaOaXma0ol1G9@ELJl*irzZz8+5K0t38?sjzkQR2BB5RA3WYZ|&F?G$#*G};FMvwm ziH9tIoY`z+K>4Js_wUVuAGV2O7B8@gmVRU@EKXU#p4TQLJQZ_VkP{OZ53Obt_rLHS z`xBO#xjDsZU?FqBi(gvbMv5Qf5)v*=R64_&I6IstDtj{OG@i=g?(PotO>0RkA|ir3 zFRSAH``?`hZZaGdiRNp(Qy46Z&FfH1`=Ftfvppg!GwQR0H2aF zew-uwyCv)**V19_)7NGuoEDx$W?C+1c>@)WkEsOh^ykNG`u|z2zZN^c|JtmR^7H7r|?`JYlq|eUI%zAbgqE(QySAGz)@1qXy zn>TMl6sw#T@wQcphBiv9`mti=WlT+P-nbW*@a(mf2S=0NHIHT-j{Y!6!*FKAcgakgVMD+qb){A5ek7&%>YAmI?N~Wgo zcRW2cn(1bEEqajRsjg0R0|a9PI>5APsK^vyFz=GUn{yP~X{^ zKhRX|?u8>HC>S3cj5EIr``u}Mgd0||@x*Uh-$S}-pWSdrF{uY9PhfpkAFt&*;XK4q zTA=lW_DXjBc9~_v?KBDB88QwgzR&M*dn#vi}8jCHn1Kxo8F@ zs5p-nJ7O2}TnF=C8xecKERmO&1HL0&(69*DfhiK*Vy9-k&jb(UEx=%kn1?(txe!7cXt0O&N0ob_!_0CkjW@o%{nif)MU{A|dcpfB zvJ5gJ@jYVLk-SH#*J>}p;-_O~ex;NofR;t{=h02HJ~^N#Sq`u$pny)8!Ewmc6hhA0 z*4>>2*u!OOs%AZ5k)HU5Ffj*$6-Ag?Sv!TSn{2($Z+oHa)r!z(;MHN;R9F`-6uWOt z@hneQINqQZb^8X8Oi)meK{;7YUS6I+ll3psEH-JvdJ`SJb8xT(BU$?godgvQ0D9u9 zD=Vz~g{*i(dN#JOsTyxy(>CI{`FW+DI{Rq}7_L@0cW~kS>*TCk=zAxHEIEGtN(4`{ z$g7df*Y^U*md#{t)v<*GMXhG^qCy;-$*+ZWQF-!sQZ5RN}j)m6I3xx zf*R&|vvQdx_342QA+3adQ|v_;$BYcO^^rT$(wKyVgo>$Rl|C2m6Q!%wRN&l%y#fW2 z%YAc#z8{-_>f70$6D5xRFBU3>UaPkN>0RbA#nCR*pUp3-eKhjPB+HJGkufMa`P%%? zfdP$lV+WNQLnBke8pFs8rpx$P_*hbAl8H>&jXPZze^+v)&Dol8T~;N#0596q!wboK zaQG$nu$M_~_dR>w&|GsU+FKz#jzr-+*}freI6wmm#}cc>8X#tfkCLEyQ}Lh zX6E(<9&zsjQvlpyRQw_9>ra0D`sK0mE(rJxk^E#26pfIHgZw@?kcz*2VdYWE{Ek%8 zAN~DM@e00Wlf*{F#hGuCd{YXrjRJJ2rA6U=uujLx+1sV5Q`pz1>KuRF?oC;R^Kx$* zBOf0bD=RBHIyw$6F7vPxH9h@J)RYD%y79X?!BTCqtbwbOveMFAPmf&;pYCg75z#0D z*yOCiV+<@Bm=_PTP2+3I{s)bxqU_AK-1FVU6xA6^k{HL}XiE6ZeXN1HR05ye0V34ZA9R z&2?TGH8}-^riKOphca$%0%c`od#nA~%1TSXwe+U=zmduy!ksWvr1A{*d%J zbbxL0aC33M$oD>;pSHG+t9%WPKL-a#&fpqJ%~M!Y%->lbT0&XfTN@0eH1t68C!`iJ zwzpS-Tk@O_7j$rTW-Sg=&X&sVk9}J>XszIru)DjfmaFklN5{lW(_Oh#BUb}Kg04Tc z;y4UK3JTa&i7m^Yj6RQ#kKb|D%myU5Gi>DNIQQ)p$+*0dlG*l50|N1+f(U`Xb-%AB1HrfJ~ub#G4l-D<9IcD^pgpO-{}tagKXvI!NFKr+NUKGuGfGSd2iLk*Vo^c zI9|B{@Z!FL!hF?M?R)^Gq4Dp{$#R1r!=mM#R@!WsvX44nKHNK#G&M8(p8J52K`HTD zW~78};dzi|X)hj8!}RgFQI>kbX=-rdjgvYciWR&t9NdJb2nf}FVq|W1pJ+yDpB|;F zr$$2HrUW>^}-M2zLZrK&^0}ELGr>@1J9*ZX@zQ{40&G>7-an z6k(|V3AAI?F1!ha0#5HAUo3h<*ppK^w9%$D><(vyXv(y!meBO6T;w0X%Kqc3sAb=E5>irO_swL-)H^S*$aU;sA;1k* zOfVYLin@huZ#$&=oq0yrSOClTxMxw3!u;UFgqviXz&ABB&A;GkEhZ(U8_op(=g-m< zM7#4f{ubmFG|bEV)@01g%xn)o`NNI@`Q6ahaN>+J^&-T?ssT`@%@ zHuphxqEGL@Z29@=vLyUI&t1w}WB7kT#};eP)8_g+c~x{+MEo?Z$4Z#tNG{mfm|8^u z>KZ7E=fC~VvB^%)3I{x6R#%xuCVeF?surOe7g$(m_g%G!*wAW(x%7Yo4E3kw(*=dCn@;p2X#M?@MmEXu~ z&Po+8xt#y`eYKVAnwW<}WnAtnsd{m*J>#ir&xNI>N4B;EWcu6lOH1Zrd6EPrvPf1;n0@ zvQj>~3}7ZpJ%3R8-aV?ccv;PB=n~FL_^Yd{H*ejFij6hHj{%MVIt8zJ*X5<&v|gxL zi1^0M&CRA;5)4JN!6U~B3O=IJArcSpmP9DTpUk_d1nj5uH$`A6{TwQouRYn!1gwb^ zJ0l|_I2lK4pNfjQtuqaCaqaBvAS4dx-ml%=@U(2#pF@01i^+YW;+V;)sXd?$hZW7w z%?Y`!Uk<-2C~!c91*>#tPDbKnoj2Y3Ac6R3-(@GjbIrGTfA_A0hMbg)&bf~Y~-sl3;PH<=_ zZ;$ibH{2}1ULnfa4`9MSR3D7lbPVQe#{x8%7X#F)F5iZ1Owl;5DTeB!DE5iUJRg=o;>t6$+ z_tX(se;o!(ZE@Rzv%>oln3}wb}1AMlai1$0xVoSuS~eF zr-4v`)YMc{3yUw_zwM6qRv%Q78&skf7OrP-{yC!gi@)7{bkz-RVK)XeA0I8J=~Otp zJH1YEH(2)x5Dxf31m9;J-iPD5cxTm-@kGR(tjSkX7hV>A>PU!iFo39~2!0dx zJrx2tD7M?h>t5T~=!{w<=K7bORjO*TH4W=OZ%IzU1QkPb8{|F&DqAN2O5O#fY+|&& zx4E5e1^^pkR%B>-!bV0zPW76TklJ zV+89iz)4Nd${Gsz>pM(Lo?h`abdI~|=}eCrU*duq0V=loTn!YE4E5Z%Tqbu*hY%6% z`Sa%>-@2>~v@eJ;s-(WRpROGl8=IS*Z8$&sEg3RB=l~D_^TGv_$B(5zFV!iv)_k@9 zWW0>P&(F_Agc>$EBAUnM2?J4RrS-d}t*s4Y&2qeqT}AQ_-}mp|7jmok#PQJ19p-M|^6L7~n3X zARtwH?!E;W3bH@!&zX8OAdJl*)gY4wPJ!7%Th!_Pun~FQZ#eMMLHk))Soq{Pe-Fy? z5da%UC#ShsZNuC*z53KVJUlCd`IPoG`&yOpxp_!o{NS_GOsW6X1s4bwNU;W`tnoDU z8Dwf!pku3|ZV3xle)9(LKwet<3^XnCN9|K@ zv%~G#j>DaKoA+_UhTcl6aFMT8S+zc@0)dYK{xDwxA}tF@!19KMsToWmzYzIyXMdml z^Td~4iF_c4lZRe#I~{+1PaB!0f*QgKbe_XK{K}OpA)%q6JdeKNL~j{YxfM+ORFC-~ z>Ff&s`T%u{jcvVbH_jq$ae0{)PVNU#P|0O-tEK~v=>-L~kAOMH!ZbO@KiYZE-eJyl zIi_m!s{&e#;FL$^n&5WZjS%#X^4>ru)$NlL*fW}SDI#~hK*Px(J4I9Pk9;J1uhR^` zEC>cYhh7_FrHYAst7VfR&N zix@0yf*#w(KnlYQi#VNA|D61euZlDBJqlP@Fg-h&K2P+igCld%P+NxJ3eQ5>$=AHU z;0Ncy!TM;^_e|O1($Ym>E(ON~ZLrH0v>f=EcuDhS-GA9;WxuF-+8lR9)Qt@YH+&!= zNXQ^cH-N8%Xp{+^l~q;K2l_m+vaKQH4-}zPK-FgA=^h*$JT&|ld{M4)O|7mL119YV z$lo;;JQ$~80B#73vA-qJo&vDZHL7Wk{~Zf*=)6@I+TI1k=-}v>drUAPhROCXQXD0T{SGAhq`4x zx|y;G(3NQun3E4w4pdjN@E0!udU1alIn>8HZf-5-e*CqQ9muZf75{zhcGN|-4iZ}0 z$htbegk74++TthCqID z-QBY7HQoATRe6`^kNiVPgk&Kf4@*u~jSO@b-KVk|H&GP-QX@QmPrBb%RJ?ipx<5b- zFygkyZ>Wnv6_ zIv;h52I_H(r*g8;yS>dxz3;0o@-TEUNQtZT+Rt-bxg?_&V^HPB40@y%AfH$Yc3mc5 zVr<0)oOP$_R>OrU8H3j3fB?;)hRaMDmD{DLrxvw?vl}Bz<0)A8nI~FkI zVhWMZVoHCa`JFcnmHBAn{9Dodyi@)8E*P?)$Ii~rzX%UMEmfNYBP};K zS4c$Uk(s7z=GB_B@Oa1yp1<3V!V0tCEO>KiXZV3ovqpr5WlbR zn&X3`oGj^A+qP|}$->+3K{&KjsuPwFb5RI%mT*xC_T0ie${_#f=;-#|-lD#3vf|?6 z_3?6|t5>hq9xYvkT9qK;%7VZND8~%(z`f`g8CwrU`1#414%I0m*tO-rzGT9~dV%($ z!GV!hB}Qs?nmgd6I`8yXC+F$(`Jc2BlM8T>FB<$am{#_Wozmp5=PA$jewdTYl}m}iS6xe zu0TnYq@*O73<&ZUOROIJl9UD6Hi|Vy{lSBsy}kE-=VuH=XfSyopJ52EYhr+5#m-KE zjUA*b$S?^vheJpxaFhxvc#Y_(YBf7R95|-3fb0A+;KKM%WvVH{oWWLY0PM$S&#w}l z{xmwzn+i`6!}T9)e+9A=dct5;jY$1Rv~8e=^rE6w-#F_*z&rb0cfPY(wH0S0J~T80 z`0WxEmF~i|de965iD>Pd5)5m+cHqX|AfpMEkPDxdmKLA=)WiahNJ`Jb5w31Q*|&IM zNl98ToniK3Q==Jxv`gz%^x8!073Gy;Hjg)g=^HC=_RE{zI%54C*-|rnAGc~x2$?P) zXN~=C?d~tvI5@}|++Ulq$VylgT)Yt})~IJ+6Cj_(LpbA|9~OoWPM`Wa*B;=1K#;z; zZRi5xN&xp6m|e?B570H935VkqVW*q+)jRiMeTTdpqDqO~ zrE4+n2J1~$IKJSw8A1(;ZSNM~ZG{Y^qd6%Vp?$%uZ;YOD6`?*k*q8?k?`1%MBbYqM zc7#H(RlTbmFf0o7_IExgRK%9i>RZZ=DkDI2h1?y=KyKo%)lZGd#(Doj?#V= zEe7=v7Mf~i?lj{giqu22P`2m z@f}$86Iu^xRdD3*;_M>U0Qg)JU|5v^8C$vtUem3&{3xJEO^V4vQAM@K zAr~n*9A+CY)E=*~GN`0>!M=Lb^8@*5wF^*v0MM!UQ(Zf(6uN@_3G+)t6PUCtOI-;~ z(JB&F)$&@I-?==0EjUeM|HEE~$4YHL5^fqEjt9DslpU<+jao$AFkV7g!m$U^Ap+op zy${$zGWx!{+8}#LC+_bs-1haAfDDO*s>5d5DArnh=xuo}1qG05BEdDMG8!Kr?|&zS z4SS7g7HsR6IgE%D0bDug%NJgtUHnFLPM73x&2jw!>x*sIV^maDBId&Oe553tPmd$i z|K5_49rfWT6fvKGHks?U-rhnL>Xksy+RsP_Kv~InBa)@$p(T%F?tf-+$1WUq#~R zCYXjoLPBJoMWFkG$CUu4Nm8x|+`(OqA;5xi@KHc{vO(5gV*l{zH&K0$av^$c`$vpB z?i*vV6%|6xao3S6Wr+dR3rINrTgRDYJ@V9Z3kz&5Ekw`K!I%NlBLM_BP$%zKipYM-UqyLMiN%8AbwZnlP~U96=i%u;#C=txXnk zY)oFnMPv?i&>)rJrQuZkkKj6%II`>6AETaQ*55TJ@CTNa4nGLq{DcrYJA3zKyZ~f< zyORK+Q>XQh|Wujh381S1^VFn*duU_81>oVp%8KO+*msLZs5tEu7Rn zRHEq+>TP0T$6{x^f?}Q1V#p4K<6^04I|))S9;k>T7M(&oM{|FFG?16LN<=>Be9Qe9 z?oT$Lj1evxr>(7R1~esf>s8M)r%S>2&1>*Ltfe&vBF|=6{TA>q#`bcW->=4toS*%kDHOv7J$En?#WsoKg*o70D*qqPf8xxZp2CU!kTp^&Dr>}c{a1WZEp4pPm}`4T&mN7-xE|$uv`ERTt)af$pS^>g z0gFOW4(I##TK}ZVP9D)OShqz*MYTRYYygj~6Jif)WC1Xj+Ft9|W92m$N;8;leYn#g zxA?CJNr~-v*~CvGa9)4Zq$DPWWM?zNUT+;8tyJd^&3iZe6Bl9|Gxg6bOLd*&AAf(( zZcS+wIhH9=)(n8A9tgGN$R|4RWdsQ9QZ2NTa)yhr>jjyD%cO#S4I63Q4%D&9BY-iw zIQq932g!48&CNa6E#UY*?hc6#lA7nLTqAq4O+mO9FV0skr()opg{YBT2*1|^6z4LR z@$FZOpz?{N6n=9l(9*N7?Q%^ik%2g;T9usl0L^|bJAx4Ed3(hkEIjYgy~TPFRT@od zT@W|s;Qn!^~}f6uVpG|4wdo>nmM>q(?La9sVC6-?#Ay+`r|2TtQLM z6zKPDcH~4|MdQnz!o2MdGAa*1wdk#aI!_WyD?`6OuJC6+k5e8g_!e=TMiGWZ*+8!* zp8lSM%J!tW1ue!KjWS33pN!)mD`cKLq62h=0V4kB4@cwDbi6*N5*)_otW^3hwKrxQ zc2^IeJh({{&;{XbZr{6i=krA(#v5#j!BSUVrVSCN&UG-?UQb4mZ2sbLk1Y-PM<|X7 zZ7}9CJmvl;CD~2!I`)E^8ZnKs)|9Z#l;ltpTY8mbVubyo?IH^cq+SSIJon=wJB|=(w zcuCo!XItnf>l?Yn2^+fJGOAu^fXw;LwtRn{T=cQLxubInJ?{u`YvN_ zo!5Q@dJHZ;{!K2f*PzezgR~14tJPS^>V}{>SAC^3OvYI|&ZG0{yNCBNW^p54E|=d( zMrB;S$8pO(A8#hTldhgI)L&T_eY5Pwr>A%NoSnbi$@*ORqUL%?^xx?jz<_Kg@Yom} zZ-7q>%flcP+6?zx-o|S}f=F8BRVIZQ^#KebtqOu^lc#WSRDt;i{Kmu8!NtsTjtsOn>a+W!k!^7U%Yx5v`FIHllnloz#glH*|e{IVNQTb z+}H35rkg5hUpIUTgjDLs$EjHJ$DinFu>Nh#kY<0+ga_vLd2-D8*-{2wd99&gY4t$WUsvO|FIur0bozh0i;{#DP&duld-h(Kc}gAFsm=@lKMc_2}d&XhS+4N13Hcc{;-v)lUlf@#KuJb#lo@;bCuiJ1TbKE zu~^|BW>YpW)iVDvaQNZckrW*XIl1P|b%@EgFPvJJe*Na@_3YWR!^6XgGqIYzz2{Yr zlSO2Hy%TCAvT$U%Cwu7nJL%5WC3Oex8Usy8#C3aO7f^ zblyl0rAE6WfQj|IsEE9*Y*9#3bwHE^1qd$K>F{K$F7#z}qpYrOV*8Q3xC$p17cmHX z97eUEZ$9p*Jr>|3>Pdd~AX`q7N@<~?lt-#%mu?vI;~_IyS%aUYEy#6K$Zs{*0%LRT^>F08Vp)&j1)g9^PGA z`ZbtSPFENiv+3!Iwx8o$SS)`Qz@+4)xc0T?${xM)6&w|K<8p#ahoqgx_&G`(n@{5J z`>QaVQI}x4xL;4NAwN6oE6Js1i8at%$D_0RTRwtCvK?j?<|xhd>wG5{P6Y%64o^-f zalK(9czAfkNH~1X01(sSyr+Ebnz9{@)i_Tb+-B>#+qdyF3#+E3ECI8m?Rxr)K!2Ku zlKlsAil?!De|{Q%EKrK9W0Y3<+rpJGB(I{v$iwqlE^-Q(6Icy=!gaa@9{^b0+I;i< zvzfwxb^jd#nP=amafldC4y`f>^>3ZNzboy7(ddl#VyearTYL*2T_kU3Yg77m5G*(H zt?#T5Fbo=>%#jLC{Aa(7nwgpsU%7H0t~#m}`WzGtJ{;D!!)-v(B?M8m|03A|4C3pj zY$5%AhP($W0m~)y=zcvsGXi%wsm~9r(Y=I7`qV<}BrCplywg+r{m%qEhDekWR?UyX z>I)98uIx^SWsp^eA&Qr9aGDkNx^&5uR`6aW|0nnP-<%fv=v^=f{sxkOZ%0K(OMzGfI-v;g^TOG@0OE|Z_KpsgOMCS6 z^pIVUQX`A*gfVZ zaTDDCOpBT#v1iD`MM@k8BTVJerDyT++OLj&g9TUr3(V7+ z&xU7mPaEEi3t>$$teDMAPlfo?C}X+|Kq;Uon!>CH2?sO|(^RiDW)vjsI>1C|?1*L6 zffDfQ2;igc!ak_BM<9@n)IP034sa$0=*9rkBwok`W)p!=m0@4LI7j(wA65fg_#pTu z9=o`h_{x1K*z|-SNUvnkn%?~W7S$L8SrI6!rE)O2nu#YD{IYM|E8tY}R3i-ffxFL0q>t>ml{d{cxeArTaH)rGKHUVw~u( zXH3oo4GXn*w%apw#(fgKE&8fGsR*dZlw1-LK+>mPPo`p+CfM!l>f&?9HP`+dfAzCs z2~j^rrIn9Bh5%Xq(@%dJtOhao&&(J@qnNGFe-bZF?*R|B4Y+W~>*HS&A}-Lf*>qw{ zg!_3D71dyo_VgY^;gB8|z>9S5g2sEsqEGI<-QC@Ly#saU_sGcu&NTSA z{S0pX(vVPF-U$9WtBm>EG0|6?D^)@xM0H$U_G|!M{}WJ^!U;YBcxG_Qa62*-w_>Uo$3~=E&nJSB{&^lnx`}kGSbFA#n33RD`*)T z`+Vjfw-tEQepbYY);Bhmn4W(9u9TD~NCe^ie-oe8d%JRwKT^B`?%fQEzWO3QD6bu`~(SHR#Z+y&FsgGk(1u)CR=S2juk* z9BUuY0Kc`i@|ty!rO#|{G>1|iLGy?I^KBR(p((%fr(fN->`rH`Y-~coE*q5yBEAdx z4`gad=(a#MGc`4h`I?-RbQRL2hsVcMwBQ+m20{u=HtT7IL^977Oh?KiyGSj9kAAYK zW&eUR@5WjpYqnLZRbbSsr*O%oDw!!348CX=9Oo;{7$HAc@FlFR8p_O^+y3u zGg}+TWte8ASp(9p`R4*I9b0OH@pTD_+HWS~u*@KqslMg}El#(*cJaLT(?u@?sZ}xT>pYB=bWmjyS92RtRNh^;lUH2Zm&%hR^t&s&uSFH!J_5G(1{b0^I_$ zlr+YdS^u!*u3M05di(b6zh=YCEcR=_l(379b%d#K}_F3AURcOXMmn!4tHhpp&F%Kh1 zovPrH%>TVTJhv)Py*$5LQBk3eeP0Vg>E7N+Vo%0l$NCYD zfB0}$5&u{+lDKN!B12_~m^z zD7mL!Ndt+Y)&U{T=?4S#RcI(H$tGSJbTP$?B;%1yjF&+MqD2-yGORb;y-7|ffY+ie zBJ9Ry|BF*MCqaw3k3vbNy$Oo$J$;G0_>7T1w%Clb+utcg|17b6mu;IKSLQDG-qxGi zcFg~aGX~RqvIM9*gvhOx8ft096*Crj^g$0c)BfB=e`um4!*wf{upjz(g@s9oacf=Y zhf2!)dYs%@m{3oGGgXhFRei$xQt~@~%9WSTHFL+2+S+j>Qc&Y$HK-*uUX@}w{ynbD zwqepBNM7^6mKpFF1H^3a4&VXRPZswcT9_Ss`SK-CysLvlIxI_u7lsIHy@KyBi=Hgr zSxSnVtn)P4KuuOC+PHhvl(A=}Mp(**qrYH%!}5#ehEvLrp_lH7mDS*A)DZOsjN!z@ z$Kub{y0KN#U}}W}43Z9S2hkVGCj-&2VYNqbmstw5tiLPt=yP^-yc3&B=;&xFn=*eI zWja?zJ^yor>k;QDv3n-BV~Aj}%aRC2$3#S^5>-Ls`yXSXMb{TD@V|G(7S%1sqKwbb z9>JrNHn;`yms%F|XDmb`T|idb1c@+hWT$u7zZld_=x6S)z z_NR^#RU}eRbRW!FHVALh#ec>w{W5IY4~4^L!r5w6H$cT0L)Xo%F}pO8g1vsKmd?qw zfVlAuGD(*gK_-D?O})tgqBX+8!sP~$(b1%EW`M+dkd{82M_#b8;rP|}MV-n`r!!NQ z<=;yVzK^N=3}4OpteN$&rY7I;zq-fb{Kr~TVv10E$Fcic>-cR2BWj71t3P=9pbZYn z)txM-{Jcqe=-rKg>0*-u*FK@f9Z(jV^9UIV+Cjv`#I_F(IDT2qZYs0d*d+5hAI*YB^fd#VwxU_|A3As=@O(%sOm4PbRPqNfg4JM$0c;llf*V zGP9H_`|u$Skr)?QfmTa1(&~z|_YKOyKtciw+OHrhb(4XC!qfL>9e|OFjbja#*qzg= zAsQM?0lTpB9^9(rmdol_U;7RQ)^X}Nu6~YF$lef2SZ(7BeC`mh+tZY*oamA$I#J($ zD`{yHEAhl~`-z3hZhau1y_M4L(#(n_(MXcMVNuY0E9>WY#EIeqSwZ8jvNB;jrx6E# z7x`HdJfZ>&nBQK2A#EooR~OdgZCXDF<%{<%^2?-+zAh=j(yuX*opbf(__NqHTg~7T zDLQPazqv0sK=HC_sb|#V>vDf}K;V+C?GFAExm|%WK6~iZbF$Zkq1}Qb$1ysC3EZmr zvUeQZ+)?@3MOv1VAZO8kx=*SrEYz>@^A3i-+Rv+*y>9fZU(kkmsb0Ss^=H+IxY^7< z+bSejI0v6K{%~=|+?(1xTX7<3VQ%R|V@&`>`4EA_u506$SbiEBl1;cbGB^j;Y9O@$ zQj$LXw}iC zVN$mO<~r^4a>Co$9SxJ4B6bm1DykOdHb2ZP&s0{SEtJCwULXPiW<0vUAQdr=FLxOr&M0qH~J$o^3FKg;1pyGdH3}#&h5H>RNzkL_>!$n4%msUEwpoc5= zt060%-S!|30U_Ue>hP5?A_1ZP`WAwe54bFvkN4zn@a$fFlQ{g^<|tf_n~&iNCC9v+ zDTV4WgW_kk#Tjd7>S3%ae6AhMgSU#V5AYAqjWrSu4-xX&F8b#uk%v=RefsQ#rq5D` zfe3q|&<%q$pZ+%y0^*+2HQs{Y{V<4$U4wQ$B(aNlxKtl2Hr2_pS<)3IDVs+^|6ddyq8lU?3*0R>lMp83RfE&_?}sLBK^{^t7rk2j+i__$!c-bJ$Voi#>6$`i_c^i>UBead3ky(P}Oj*J|zqNvI0& zn!vVhhs#C6+_X>kE=dLA)6vtTb8;4u?6x*HbAutC>U(S@@MNSOi33A(4rB~*LEOl> zB5|j?qqFk{=mj8KK-plKxaj`p*wx9|`Pp;Bax8yw-Stnc2TM&@q9uH{Loo<;-gBe* z-@uDln3tA_SkY8on3JX;G-V=uKQG4;q0dD=6T*5DVTKaY&HCOZ^5UL=4&Ud_cTrL_ z;mKrFqEe*V{2ZG@6?}D9R(!5GIBL!>yl?5qr5r^fMQHan72+kpVFgw)?56Rd< zK(FqT)1o|tC^a6PY36IqE-p4h;0SGdcXu9Q=SZg{KNX5xh8wF`4?{<%zhhTSkT<$I zOz{`bFD_H&1vBQ$pUGnM$>j^lwXoQ!p4dsa

vDXsoE31U(nW@@Zpy?X&*fSVd~R zxQT{xy}c!sZN2?lD*pO?8NFB3st4n`PL4lJXL7n5)#9aYj9;VT@9S^lj=V?kF6v9j zJ*5&MezoY=*QCZqN=*9B}RLGqMV^wH%xf}2t z>jFC-6~3if-=hlQZhs04<;xB&{&A;CTZ_{^hTDCwgW~jE7L26?1Qs|_hMQ|*oD znVDqwG#Ey|h;|i-5D*p`Tbi{@3wn%kK~~nmMSXTeE8ng%{ z7a@_{zSWOtHg@ivT!`e{X7v^S$-{SLNOpov4f;vJ1c&Fu%&+P0U1R$XYdSh6#?_1QK8-)KHYHkjWIXxt&{$)Eu#P5LVTIaso4e0?3=<=jc z&()AIWDQY&G`6uM$Y0ana!U<(-i=IE}J1X#8HMeX=uUu63mS_DL5vh zAiiS0g%mFkbN-{L|MHNcy#uiAi)s!M+nX9Q%ua7C8_SF;i*iI**rY?ZCR#x2tEn%-cO9E}fbBz*qJcBx4 z1FO-`Sv-($$wE?W51xo?CzK&w{V~v}!3@HoyuN-iq%ZuKp*KyIK+C{SvqT&o_LL9p z-^`Ggt0lR5H6LO^+PFA4s`tV!t2M5x^qYqt2?ECKJnDsm^ zptU6Mn8`<3L4K+OqAN;0=l{|6!?OW>Et();{jbi>1TN=&ZTC;c2pQ5~E>osVMOtMn zL#CCYgrvc;G7Bk^DJ7zid5mZf%2X;tl&M&0FeMoZp;1!E`QCBf_q_Yv=bX({GZ?d9YjHmn=K5HiwmBc)38TGU{#WH5hmJSOgynuISd0Y%gS9nMCXOj>CHnN)7OEE#MW%kk~hjjetz#S!itrTH}7-YbTuyTLCGYroFh{r z#(vLRF8m&^ZfY)Br}o~dG-%ZrPnG}q5uK+15+az08X%}xA9S|e;CIo?*0vQcc3qJ2 zy*;$DiLSD?U+|H%IcU)8*RIznH1O$%{dZUO{zZSkM*cEPeegh)_8RzM{?qeeS^GYm zyL}?0NZjTqtY+P#ULO7a#Al-fT(58YJoSJc(G)TJe34*t1f%ug`Iok&`pL4f@d5)yy{2bo!@IfDq^jX%dvxpCs=RUDyN=sTPHgb;>46$*3Z^{A#26*NO1a#exW|ahZ{#rxC}c+geWq|G50jxZ zLZHLRw+v@+jw#j&=;Phi$nikDmtxpv+xJ4f4obxXNED}m@p_Q@?#^&~9#UfklmlKI zL|>x5*9&!@Irv{ox_7ZIyUSQ?Zp^Ey2%Q?bbzR*OO%%cZs+eHs2?H-esB zm1Q$myJ`H{&F^!6;dc$UY5qIoNPZEL&W5vn1XGi2wB_HVp#P6=NzSgD;fz-tT(OtA zxja(++y==D>DK>c2ZA{s&N&}db|_ZV*PC&9!^x8;WADiYm|}R+iJ6kC>+V_V%@sv! z)~~NEVp7z=k5e*j#4}NtaR?Ou)iW{FgjnIXZQHhzikQyZ`MnKQzZn@C=5qM*U3%{S zWs68s{4chM7AxPCdnh&!_KcX&=4%e*Rn@^?I}{ccqSu8i{p^{ZNTwmsosEh*3cmoS zi}0Jq@Q!c1c+vjg1fQ!{hu{n~-oUCiw^i99E@P8oPhj9M9-vAHq4x~D5N;!k6*)S` zrSHNVV;m{&6K=MYwJ}_@2HI)gbBf?3j4(-e&rXTDef3iTUnD2^A|or;Spw!3h!#LMKB*O_`}JFUm>f#G=@B4f3j2 z^Shn~PpEUvPpmCSAKm-S$HxMzk$R9n;psCTPT6M=ansoQXp~N3qLuzU1F3J#y==1Y+uAr*PTc$rzDV{lN z@WXoL`ifd=SEEN+>};MsKGia-3p5L7L ztxKPjo_djC95n4>`y=%~hoo3mMZ4J+MHaQZzcOxq&gvhXA59J{*El@osZqE?Rphff z_r~6Mn0Zg}n0wsZ#2pxI*s-+Sj~}P!8z-%-yHFfUzWy80Up?vmmE2i#eXiec zl5{aQ*1@v)(Dkg-x#hi7*Wb@S{Aj=c-2uxr=gm{u6&2NM&*=*zEp$uPB);vwqiFZr zqmSM$eskNx$nA>C1zXGaCO$vWF6d`ZgP9*bAujD%S-Ek)$;VVhM62*9kHKS8 zvu1m&%=5Ba`SW(SDj%m$k(M^wtz0$imzVcbe0i6){?oHd8hgdsje^3V&B`$5eGH-1 z2dOUNA;5<1Tt<1pQlq6tGd8`qjr?-B@4>su0dAdopBWtxZ_ra+b#F@#wT&sm2Muih zDEwuAo2hFLwtf6e!#KP+)-Iy+L@)1eMb^hMv+n)OTDH;dFkM`;8e6exUF)?9bz9Kb zH#XMem(!GPEB`FRgwkPU_Ydt~`7QsH*_j8g&s=Tt5DD??_Td+f>bZXE=vuu$Fz`WK zkwaR+&4qVKOcXtitJ-R4+=A~qhoQcmot^lo{3fz0#CG<-OF_FWSyn`u`Y!#Xs?dIK z_^7@WGat%L=NDHz4XP{enjKT>dUD;U$(Cxj?_TyC-Sfe>6ZyS9Cg^K+FiFU@NIHLQ zgtt<<)t~V@yi^W9d%DhcM&1P#i_8TkreRYwjP+XuMERtSJ!5_QPUZe@g_g&ArS$Ba z)IsT=?7BPUnHO8Al4UPvJ;sdU-0B}5zbBMeieA4SF?zHzs!j)tDr4f}&dqz$?{(8Y z3h}?9s*FcA7+-p~ht&9F>4%c3zu8~#HZPy}56DWvqnVFaPStF(P(yR!z?mf#3+s)W zY*24p$AkBm8unaecj!^b_#Uf9-xkhNYJsWZBW!$cjm3MSktQ@xM`C&p+WNieMWoea zzLuZN+w?5#e$Lo6@y4GAE+~Fh@xpcCwsvz|UB}l?dZqm^<6Fr1-aB_#7RO9!d+YYX z=!>Uq?9ZR;@$O*H2P?fF%%88)*;>Ao;*2m z!=WVC=IJ*rt-3x>#_li53fQ}UT5-(k1eYPB7JDb`4e`GD%;c)UxSXmpBiD~NZ#X@{ zwrSNeBdr$9SzNS0V6(UKzH`I$E^QoVIV>tVymeY`nc~APP2oZ zoa~+ZsLivqF#ob-%E?5}za1?-=Jc%2i9FMzEIWB*lQ0$S0ySRWruhX1Xu2z`b{KnJ zKihFc{U)aScU$+2Rs_;99%*O{-MUzMp}xqt85$&HDw z11(egTst+=(q)d-v}x)6P1=^!H{+V~(oev;47=vw;}2MjF| zz6}rQ*H-;rS=I9N@g}Dt?;WyR@!C;)!x$+mf}{0YEn1|zBIA5~yw~tqB?0bZZBp>S z`g(o+($8fhjy?L>qJzrYSOXh%uLTaC$rVeM_-*_rQ7P|Sw9D$5dnSDywKnY9inzBY zs(XDfu`Ju;5jkmA(Ee$Q^iFT7(<^11kYqE=T8+PcBj-xW6SagxDi<#<)igR^Fk;l| z)oC53ey{wL(__A^b9?W%Yljc((CdKR*g0$KtIQ0|G+Xa5RWnLoEQp4wXNi(h_zb&KkThxhNBk`^x_k(X&y#&stg^ zzm|-uho9{fi|Ph`9-eoKZ36#JI;r91`QiMu7d-}l%3Ai^W5v}!Uw$+2^!A)Q#=Mrb zwX3zo++W37`2L`lj~@s8HCN^S{R=z*v4S;P#0@2TwWGaRrm+%=If0SWFnLM?){8v1-T$+=ngY5h|#xG~jo$F|9d;qQ13s`(&euCf5{KDo^cv>Veseroq zfO0r?MTrh|V+a#g+$N)mW0aA0F?r@hVb#914k#hchR%GkLo?o<3m;b)BJnrt! z&DhGlzP0TwMm)l{+tT(Ab!z@5?Tl~J44_b^TH90h_QC(Ww2fGw&VtdMhY+YElr4Nl zUcG-m2JaquVf3|5H+`FZuljJN-wBa4T8!mX1!W<8UblYzCV&6D{R^+WL^uZ-xftzD zU$6m8;Y7@cU66rWm=xbJ-gSm9zD0`^^{BUw&N}Ha>({T(hmcB7i|5f_;6gM-zpn`1 zrBzg--Br9$rKQ50irKV1O)b>@hgZG4ME&^LBjML=>bZ-{@71PF8^Oa)PB>U&kPKY79-B^#-@kG}*@hi5e9!%N1Mrj%Az3>A>Azek3GYL%0chD8K*x(%Q-!}?#JL+B$+SzDb0j(1-tW3!Qmo)gUI;H~>97J>w62vd%RxgGRLz^2;pfQHYaB@Y`2D z-M7~^a=@1=D9Qb4gwg!oM(E^TUHKLRiCnHNpLXK+#hoKv|DOy+nNx6r+@YyrDEgO} z>h2%lPgU3Yt$;0HGu*>%Kl4+Qlrum#^dx4?1JvpMM}8sjR;#9c)QULb{mjAKA$ z#rGX0(@No-AxQgu8J1ke^k}CBq74f>c_{J0gKcy&obWq5@c?SLPL;t5>xTh1KG%29 z7wt86??;7oaq%Hq8*uv+Fp9UpH+{p8e+jQ-m|C01TlTU*pdc|n`nmvkUy^O z_;A>R?%=pz!ZWi&$b6FsG`>c|91CkL==yKR8?etXh8Q3CH;ptVZcTr6M~7AxqR4K{ zzX-r}1MCpOi82p%?+d#?PnkS!IipgvIO5TVy!+|~$ERIdu=GQgKOkm}q~4?4g$hl` zw=e}(A>neXK3|>wp`7+Z+}nYnWA8<+c-ZcO z5A0Fcoaaj6$ksg7~hQDId9R2ZU5!{06A8Q)%(h|Fj#;yEk2hbJrKXBLUgu%GXyaVqPP+ zTZ~cpl4s|^;BP%SMFXpcG|e1!MdLr#G(`XWaLug4ufa*syMC&T8;1bLI_pJby8KPF za=EaNT!2_xRdf9eAfQbFC#OVUmQpxo8luG~eP<=sk*yeXG+(ix@aNi5d2xU1tE#FV zTJfp@ICziwy%;U%WL7DZMbY=)1}Q?+RPdN<(LXP)20md3I~2SYq}d50yaPtd{76o% z-nt{pof^BOGoZgV@tcEU=bqP6Kv~$b{$3+3Opu=6X2u({^nG&?3!=_N{}qjYB+3n; z!V4JRsE=Gta7NXLYYKsOJ9qZ3tD+u&@wL5u2T*yiwA%d1#%bI&q!Ej$BhfBUF49ZAMQCx+XT_Eul z92x?sG0_(Pt{L}RO0{+-vug8DmvdNo;QR%ey=(K(lyPSswO-iTI>+@7xFXj{Ke(~A z#I#L+LJ>w5@`0izKb~}`&8n_|-oaHO(PZp1iV+hBNZqs9=!1rJdYUdumoCR~=`{;zluZ9yP+F;fV)Pn=yc;=`S z5!MtDiFK%$4iENxOt^>0^oE32Q+kDjMDbV{Eh}*PXt1+c9=|)ofGdh=3>_L|c7&Cc z+SMOlT8rTkif^Fs9r%NYaUI>Uudi>PnwrBjmhvh10O&7bR>jO!C3PvG#9o-dw1}ZS z(B()D0(SJX!Q62g+#ffcN-fxmR|?&L-ApsE5^`H5p#{&xIvjrl8YP4i!9m4(0QaBN z8R7C~)&X4>uECjHb_Pf}MBu|-Rl&4!(xgc?Bp(R5{lB!zM}t`NDzzZ2mBaB)P#`AT*hh&Ph#0Xi)?`m}lN zTv3!W(|h;iTvr8gTf8KgP)*L8y&?1xv(;@TUo?ph%ze+X*nqNZ1iA=#`Nx1-Wg5Z7 z)p$tk#%VoxYxqNjA%59X_3^>|spgF=U#!X*GMAKppqX{sG;Ml~zn}9Yy0cexWmi@R z@t(F}g8DGjqN8|)$@D98f6L$;ruMSvK~fEfDw}o2G6usDMqVFdv*tXX_#|H^hX1}F zLoH|Yz}|IBiTkAm&);Q5?k~A;;6^9YJc(;Obp6=B;o#sP?i+Zky(KgEoOW>waJ9Hb z;H7;VUEdc|dsbhhAOrBXR;zfQ?n7+5_jn!Of8C{%LMBjv%KIMg zZ2Ia1%tL{(q$&N_;Cys+KRb(T{Mlu4Mn2JgD~H}YEKnhwCs)Qp@>9W@2PfQO&TZ#3 z?>f4F$KH5P1 z*R=-B(-eYi&08R4~6_r>u?U9H)-fCNWJ&v3WsmbI(N4%q~eieBi)1e06Zq zGdmG?`7%pcoR;jBpRO$N`D_u0XvW=Mqy3#yO=o?uV1(yQ3;7(cqtiQ%XQ;E8@ z5b|I=Dl&M;`%WcUsUD%p$54Q%Y3($STH{|GNEmec1&i;C?6JCns}UY6{zVs{0m(Fx z69?=Qe(s~k*ek97H=R#Vg<>@}rOsE{w{AV{XnE`}!oue-GqAxjJ!7wpmzZpOqb#{e zn#5A|HQ_XwpkUa>pB@Tly4x@9u-=24M(9s^`tr3)7bT4rf~qI_`)R z2+kAy9%HPylHZF$kj+6U&KGPWOEi*r-Xyo5jqV;(7y|iV-qZ69)?c?jpx(AESH1sE zF`}5&wvoH2KKhWp@DWCO`iE2&+)JTcke`GZ`w-K!*FiTi1M27YgsSqbRpsPsly~B} z%EAEIo)X%(nk+`c`EN+|*N*&qC!(d>l@_e7NrAG#Ejj1;Z8`VYh8BzZm~9F?I7xJz z>mwq1u+%9RmT4!3=-HiBv`r6MOmU;6b8tKYeOE z6wZ~xK`|qb0X7ZhJV)y;0=g?6I5(r=?|Dd zcnObVTo$q9+-yW4eh4){GB7#X`@XzpqGz-;^uV)Ovkji8Q(!m{u=qGPftI#DNw5%* zNWdVl*IrfT4wVc3wawy$)91!z6xXlov#emm*A~O~%%q#-CU;_65plII%pzncu?SO` zjUA)NL)o{{dZuUQ8($?Vk+6cB2ZvJe^aQmLQ8mv2tC((6A4x3*kS&HvH7=tB6@-`4 zmQv89&WOfdIEZS%Gy%UF+nX!YJ#AhvWZ&99AmFsy6!NU zQ(3Ju50O$3_yli~B#c(1AC&qK3q__I2PsuBqmx?4hKCc{OTOMTWo?DL?ZvlfOEK3J z7>WWNM;NUfWYka(n_R2@@r^#C3Bb@BcDjg(S%-f89;QrI(eAmI!?+>T0m-Zb<8C3H z@Du>twEqVPU%Z;|oud1_4xfdPZnwJ9nIfGHcJjirhEc$?=(Cg#nK%8K+zZuX6OKsz z0ktu2wXm>=ugu>Md@aqUbmKUVZ9}_H?$peO|ZhsoI)!#l1jO~1|X|Qe0tgF8uB_M;uUVlmeLC>&#T+13rGNjyI@}?@} zZP}AUc|DZ11F`ow+AZX0C#FyXh$|s|s3@7VDH-smU?D{!??CEY;rfi5(QwXF@)C3WD!%YC6IS7f2wFQYhQxn8o6C6NX>SKj&Ca>OC zUOjl%!#Vmg6_cldvQt1gmEQ3~2{-I(%%>!D2E`P!2hRLqaH9=~%lB|pOxxBNUKEI! zj1L#kG+y>B%MuOBobH?eB5Mh;zZk2=-2D8JfS)$(gcM^zxpy*Lr#DJ>GC$8MT<`F6P#r}x(W%6VR15o_Cp<&=#37+dj6)evsZHF8{ zIl;isA#Q*E<~$dKNp#DwoG4r=lAkQigWfG|1%yvYfMWG1R!&Uh*pP6w5`+Y!ygqL4 zhx@wJJm5XoOgJfPOXO&onwiOi0!g$s-r?)~{Tq|~AaVKCZ@;Q3KD32bf3Bu*NahBo z%(&b%xK+)uQ^^RQ+=Bo$2yV&fF=Kdz)%M_ZG`CC$ZUA8<5}yUb73M5Zn1DF!25{Z2 zw;_}jZXCTtfnq_DAOlW-0!G6k07xUvJ_`SlBY;w+Ed-@XW@aP?j|?hhmr>zE@1{Y= z*;_1ax+=!MbWKcyWM>|O&{ED!v*yi*)2HL0;eaR8ycbv6u7R~q3v-tb<~>jeq_`9; zJuKSEWeneW7oH|pzlSePGYiAj-(&hVYDWwZ%ddirZeqa+1R}Fl(s&+q+ARzevh!55 z%_XO3o5sR}0|7K83Cs2v$|`44JGDeH*@11!DWuFKzUp41UU&Z37WeEPxW?67Lg@Vi zwPPHT8Z!5TJ*Q3BqX^hF=qDi?%;iQ_)-FEI66n)GMn!xE0QmF|!F~~>iK+-v$(D8| z`)DQEsN4x(?%wd14Qe)(3WxvzHjJW%aYY`@fIamA^8G!rODKet*9h9hrxO49p;-Ki z)hM6+q=E*wWwjJTSExD%+1w&lodd z0+tyjlCp81KBC*Oev>ve@TIPr?9U z_I&Nm44g2HOhho0ErF9~#(<|PaB>t}mO?_1YGT-6*6`AstxZTUK{&}WiLJ761UMM! z!!3zZM4C71%Z6L+u=Q#-n#nc8dWJvhdkYH+%!L{5%+|XU+`k0Lb$h-{1M}cn1O)0w zniy#`D6s4S1nIy}WnZ9&{SQLn8YGg-R@vPOuddoWeFESe2qs*VYIdMc@ zCRfSr2Ve``1kjm~FMFg0SH5XMoppD{e{-#LXg}I&^Y2;Nb}TeqR<4u@1({h2N2+<@ zi}M)iFxr=B&zBGpY%jQ&QJD%)8=Lr>X@@Q!xp>LD^X*^uDJLhnxc~G3#$a+Mfa9;m z2fjltFa^ZoxD4lV4-?QAxc2_syFCJ1a8P9h5=)No>sXh#BOvnBDM4;20lG&GwlrCT z?F(hsE9i(V+gn?0$KhUIeE;2uVe(H_8l$A|RyOWA0=<5^&D*H0Y;LYS7Jw=BwpX^g&bvc?jDjKIDfTNU~?kgxqNBWy>bk-ct?hv~Kz z(1<(925V{3aJKr-mdzosuhQ>^?c~J6BO@|}f5H2lNDrOzxdFo>tIiB@s4Y;Dbmo52 zEDE=#(Hi{dWTGZ}mif}s{W^jTqE|>nYq&8jnl@b%G&!<;qY=I?79Socol3>MnoR&Y zg9c5#ucY5UL9E)8$qYfKJ^PCdk>ZsbqEo< zmA^_1w-1|d(K_V#@!VIhbl%piRVv@aXokk}ICq_jdo%f*Q0`*v6wlONDnmh(O!Dxdhdy5KBq|O89uCTO#Pt!`D;bXyT{|yK$y>a$w8g zi#4VsiLahKeYym$wS3i*wS1g?f1fQk5)-Mbbf6wl;wb*1+Ip@18oVQyQuY3}4yN8U z#e}xs;zf(>nHaDRNo@@Pa5VBMzL5+hyl-fnQ(hIN1+niyO zuy*{JH1=n25TRG;8lC8q3v+ju1T3bE@M+RkDl*9&2&ovt%r zy!+wWlJGw0kd@+Jopd@&~Nk6I{;2~)@+v)mi`sn_PBOLI z*xpA&oBz5gG6GDNZ3ukTqHAb^!*lY`7=j0*hMT~Sh6HQ2sIOfdJ59Cq3m`v2k?U$T zi&4L>BxT&m^fd0X)aM)|B=z_gv<*51Vl$3F@bN9_ZCA5L_S0x}TQ81(1TqhB=15iS0Ty?ccM&oeg>JWQ`35N>f9chsXkJgH)V^7h8UyAo{YL~F9zmj z9t}Enl-^6bOP7t*W+^e#8Axqedlqm&_##^ln_3N&W>wqN#M#;Tcm0YqT5ApbsS@g* zR<&QUSXP8iSF5Xf@D;Ims+ZSK9qTri=08&>A-a01)o=m1UiIT3nvJyjZ2+=U1RSnu zWc=C;kUfVK)VO~Mc=CFQ_v>cWUMnlww^;V$meP0kTWzl{SiE<`3=B5E2~_w&A3##r}|jU2kTC3 zRtoU-9i4=Qp8bIRvj*(9u(GP7c=zFhFu`&gZ}9i`{|fSDF=K{*L4galJ=}TfM1|a&@4qK{xM0b-q8Q@$H8^_HP)$R|0=@mtJ$-c21Z7Hfq~5$sj8mSn3Zg2 zs{W;G}R>k}0E!TEn3;g0xP`TntnPv5lr4aI2walBunfBoY?)|qYv_PLpyoak~P z_{x>)%Vi%53hXb~Hp5$xS}y))^*3hKmEYedQJOK4u+0W~z#s1#sCqGMO`o&2&Se#z zeZ!6(RYI7ozPWQu-EiNl2{CX}d9XKyex-zgvmpA2ZqBNl8ikjeG;&CoYECr>DDr|75m!aTKlA*jBAuha5XL0$pQwj|97Y z`}dES9$WhL+2%3$zir>OtBbq4yTgF}BP>rP)_tfF_gs&zlnmby8{t6arxvYRwHj`7 zVM*n)ZBz{#P16Vw(}=J$eeyumGgR2!y_VO>r*Mb!iI`LtOH;6He%VQ*^2nB z(7d{J?_R2P@AmBgn)PmP7e0wL16f~{EVD-P+TZ`USgCle>>C8)bypn6FY9MEIIjUn z7eJwHWsMxtNptk?(#-1KwQTG4t%Ry`EJC{nfb`!w;pQ{PAUySF3q|JT zx_4P@J26QA0=zrnBhpRZI{CynzliLg%f0^CZ=$k+hDte)%wNBLUA)3L zy!utq-llVUgT$=CX!01x;Bn{hksT63!^795&b}d=ad6JpF)?W?rvFqVMSt!*HD~ST zj$OOfhm96``t(NMT)@;DB#2@FSf600Dj(ZN3ueTq_*(t=@k6t9>l?5ZRwc7Sdp(Nz zZrk2}`gCwfH7Pso#S7IPcht^%1oaHCoBp0r&~?I~H~Z;(YSvuCyN@4D$Bb!E@ZrPJ z^pc79$2B;v!4WWYFYUy%MC{o=S5$~U{Egh)4n?&OoETb#o9Ozxcg#o?ha+UO8lA~YQdE#~Z9%b=f^G#nir zSHR+ga?s@X$&)_e#*<6ldiEVWxQYKrc@>x!FOT}POJs0X3>>mVW6{R1>8h8W`GeBV z0*P2;*yd|N#2GyMwA65347RFLH8}nJyW#4_Bnyh9%LO~8&7ApS@?o_u&llfnYkB|C z`=u1%%l~nie0iux-}k_%LdO**QwO#tb|y7c!q8LX+=>um5jFhHcD+zAc988Isu2(eC!lIc}nEZbRDn8*$ zleoetxYGxQc(r3TeA4aIv17GuBh~4@hecYyul4@c?c2)dZC^MWcJJQs+SNb)R9h83 zBksoM;ydGKl?GP(`88Y|_gwZn_+GaUC@fsitQivgKzzD9-cB5Beg#=Ge?Q5>;;7%K zJ0q^Yu;Z%!TxxW1XHd``Y&HviXtiq9@KHD2jl`|yhie@gRQ)CKbqS4mv~ktDV-K^k zx-46^EE>~8*>rbfSwp{93y1J@bTB$N0fUu1622@7h2Y2AC~}5Qow^qcX7tjf=X*|#HZ3S9h(FU(P3?C05OWG81@!3#?vbXZ)wxYNH0x&P z<~9(>Mc{W{Ku1rn$&`qe)Qq8#k!Dk-sIvkqih8F}lO`V9=FXV|IZXCNDUO^w*P`9F z`rh8&gO&byU1HBrgzK!Mu!+nHIMlvb;8m)K(IvdR;z)da8zJ1{kng>Atr8QdW^{+c zr%u&!nL9V_=~F+BThZdllPB8%jh}zIX-E(e7V|)K@}vIxt1E4mvf?o;;-2a%&cf}EV{ir@K)QZt#Ef~+&@(6M9fCO+#cel|-R zzm`I+=0fTE%e7o%r{}EvrpN^?c=ztznj{CMK2hH;Q4Fvo(EY99!3hhm_1~W=(=8IM zg{`e0KXo)R(w|?lpdm%a@i{E3c~@AN%-K$Ggr%F5n|tH|mi(=glar|gl@uZi`M5l; zqWtt}y+(~2yZ0`!?WwMBVDM5(jI=qXbLaMecjV6PThK6G-fAQ_kpKb1Bd71~d*0-v zmP|b>_U_)bYvZ&9v2{H?JwIl>6M)9Y*`XC?98Lu3Mh*Y zOuRvX2mj$`Y8p7MqfYZe9baFaP0ts|E~>Mz$`L6DF}kd|&q=@3u^DM{(h zcP^j*d7tr)^SqzWmovuAxK&{9wXQXpSb%Svb3zI+~;InmXIt*g4xgeSH0exuerlJ6i#65pI62>sHRr z_D*6vJkS644{+N#TJl^!IsXbTf^Dz#zzKySG)2D9a;0;gqEIQd%5ryf-ICXSx$EnW zUTfOgDCT*IW1IH7;hA;9>uV3z<189ShPvxVx^D_kx~fI@;NKt+5vv06?SDT`!i1gn?}uMUUe-ju)ACgbo&Dbn zJ!VEDMShr<@Be?9{}0zDyNTJ)^I(0UuyU$pbd)Sip*8z%Qc87yilpb}=4MlSdk_v8 zXR+JXY%-zlzX#ZfqlQjNLL&P?%tgQW(VgrsjW7OE|NT*s@pL%*G6n{pMGxf_eCn@3 z_}3gowEq>s+z@+KOi4heEp=E>*frtp{hxN0RlT`d8RMnqxQl%s1Y-6!rc-rt)E$-v z(hWnj|GkX}jvDSGJz6p65WPZ!EY4@YYJ@t%X=Oi+Qgd)3uNsnUX}X3AW#Qrqjbc&F z=DhKslv!C>IWRbQZgw`xA~i7ZGBGhRUcZYN?ZL)$$HW9xm_qa%A1?gvY#T>b$eTCF z?FtAC+u#aJTqaVAF3&Q=?`Kck+1fJQp6?Q+i%06#ajG{-m_sK!w4{|6C;Bc*HI`Fe zUtd4J6qd}?)YQMM%&F$Y&C^rBW}LTmM=^qKW_`V{?Jb3aqht4=Tifu{3WFDaf5`9r z=`ATQ7knYYdUu7&pmVEi5uCqQrA7eVi?ij51 zsjaV%z|wM2Vz15mO(yp?d0s>v6Wgi`hrF}1AgrA4%J%Q(06}vH2L~Q6uZIsG($Lc4 zcNtjFS(f*8cXM9r>m<=D@VgU$3bFo0@kJb+%4ACb1A`SUG(7yz_QJQI#j(#ubMsx% zBBG+OHsO_(!j*Q@77N|6ehnQPFEMZ_Z`n|u9q-Kzq|0&{)x=ah8>3#miL?cWuC6W# zuS4G9uAg(OQBhGTCsh^}7Vt9WRirl!1V`s$%x-2?^tLb(W|C}e*UR?Qfhj6miuDPE5;ks6`FMFS)%4zM0 zfP_ZVpK95XV!w~_>2414_V%|LI=phBMZjK=Q&(0}`hC2&y3FbZ50#0JkFV8Rh#KF# zJ0@M`6%Kn=?!8asZEwgtS6IG#IW$^$NdyM9d=Nio;Zkc142p7Iq;s`llH8(8M4Wk6SA;6(<8Q-Byc}Y3k=XLDT@M1HNkqg0 zqKAFomI;t@UZ%#ElVjE@&?iWa_LBQIXwc8<=a*UB?teC9U}m1ryPwE)^CpK$g9O

M@w8EEc+P1?wJ+Son{`xtyY{{pUc~*ZoY{ZwT)Dp4-|Hr` zu5ZtlPvmOPLK^QIU5gVqlptQ^7(txN)gxqT9;x>Fqrn>rofvj=1?>B(Dlz;SZVv2P zvyEA9TQPEdG-0fSUtauS`Zv>fu~j%285y-%UPQ1#!}#U7at>QJkGQtOx2C$<)Ydjd zbz>f*t-U4e8WC}ng}d_{14CtRb)x>uq^heg#f2T_SnY^jidVABGCoyoRf?!i4A*Xp zvgg3ywk5BM<7;ihP>FpR#iGOJ0-McB@M!*&jOgDRv-3KO(ZW9K+w`gH?Ci{0-&k8q zwtacO~V?U8NMsSiQq)9H@P)P8QGI9DC#9=KZ25`yE9s?}z3i79%d@Crw>K_ceHfyv9oKUenm9XY;} z{zEK`8UxGD$)Zj{@RrnZq3hquDk^$6eI#6659;`M9W0id?RQv{r3n}NmVHyCBgB0D z2WqLgHTO#7if+Jrk#R=JwcoVgfAI!~EZxgJjG^n3=AFiv8<;O%xSQ2Uo9Z6TlQ0Gn zeN0nUQDJ0f50UiTFLvE9-v9eE-r~C1wQJX?Z`mld2I1#vXT4$Qa&mC!qCc3+8d(0_ zO{PLC`f_60xAhe+5ltwLRL9?{kC$}<%0`$e3H!FMHjlWiEEqg|D8JB6ov-WP9h|_LHYx=Db0VaCmA+2HVt$$xVuuzemVj=i3E#xW}cp&)WWu*@$nSB?}g@K z?;9(-66{O-T{jZ(rtVAjZ@dT+u++2+sJ?bTCU|82nl-VSKp(%~BWoh%8E2FBNkgrM zy7qUIk_|E3g$zY%lMLHz|B&K*$oRNE0lk!s)r>fF_^qw2ye}NunOJv|Ze=|vvv6~F z*D5luKXp3N`!s6uMbe#E{lgHOcaBE1+Xh^71f|}~x9YU3F6xxt?#fYvo@GoyMb+hh2@~(8*MGr>>>t?xW`e%gTlBuys(tad zP5|@o@YnX0=sFU%>+DL6r)R=5uL&+#-Cac6f|EZIEaryCmA9rQB;7DH{P=XBDaD|o zN1Me%kKf=;r}@9NbK|~x_3GNs%KiaUCU$oAyBm{G_Hzph=1Rx;dWG)~Hh#T*JIvwaIMs5x=IHuocE4-x>S`9CnuGLug<-0*JKD)`PVy_aj>!Zm^~2;INSF2 z>6bj?`Wl9rXFtk0pt1AGWIiAwzY|jaSCytES{84Sa&_jkIU-I0NM2h42IHxe-lGf#R0~u?oBUY+exL0FoleC^$%h}1lR7q7fhFX zO|0-ngd{3@Ptt*qZiENkV)RqsT#qTWV@Mp08Ka`rZLa;NFL>^+H_C0q-v7N2zZd`F z6+70y^&rU{UdAFIP#0Qqw6e0wf8NvEyS2H=TfQk|JDKoN{w+1ftXfFes7d>;Mw3Pw zi4bni_m8aY-zm^MronvrRX#s^qQc&Eb9aOXpV}`Nla$9c@Zh=}_dklFcH7ah)HE&( z*?@M_Qb_xL{>0q8?Nd>Mwbjhd?rtW)FyzV^nf7kNsR8cYMuZe2KR^Gdhq$;n zwUD*hQt{Txr=rJCo;=C45?~NBm@ch+7VjhKLsQrnN>X=f*CHHr_C8yVvqQIbV&YC~ z&;^Sp{@~r~G>E z?x>o;%V*x6;;t+48H&p4Lk^+GYnd3eiS2jpK6yOyu@64Q3r)AZ zTPp47Il04Cb^j0=Y+|+^=?uSAjHuk?U^gIrFLc5)^GOGDd;2FTBhNd80d40M7xVfY z&S0LNor$`xC#ToJ$lhI>hz6LYS>yZ^9UVRQev$E%+IdUMF81{P-{aJSb%%)AwR!yW zM^e5C6|8ax;{*IE(n-#z-&XvO;=(eqLZ)|9*4RUbZ?XhppaY@8h$v z&j8n@7RW-`x$w}@cU2!i8s#;&pA>p^X%)e%du=J^%UTGA8ES`g)4R$=S)l&Y&Xw78J?O_lI^4C;QKj4>mNW8@wl~95Sv> z`4h=3b*%m@d4dTGWiwTm`1PwC3eei}cnK4-R`)*X>Fdvz6m1;3oegj$3AcVPv|l8M zu%CDRQTmF(M!>E=V7}$}dGy}Se8VJ{iW ze-L-YTL8|K1$E}U`aSG%+Z!sr7H0{sT)Tyz<;v5qnZ(}ztSWs)V8eewU+ZjaHQG2= z#JuXc`o*?Tr(IM_$?#i4HXimtJH5Mz86~EvQsE~M#0Q-RSo|ZUr2A< zhNJF7jm8fRb~yJwaZY)tb|l$xQVVKIOxZuRZe-k^=oHT+z)?b{q@zQ21dD2%+CAe^ zGv$_+mZ4ucS{VvRF@H9yC8np>(AFjfKK|(Z^oWYCqoX6ZE1E5bW4huQ#fuj&c=lQ4 zzF^_u3BJIZHPNP69tN-^=@}<|aT*E`db&L0jo2uRdf;|!$&*p7`|Ja*EUTv+AgZz>l!zvlM7PI$8r+7?Tu<0dkcjQ zWo4jwKbZ-qo!C^sK^@spn%LMBl*sbdphu#z2do71Qf_1o#bm*Ruoy_Yqn5zy|Gn@b z?4RzCt4vGNjnb;|+;?5+?d4z?hdb5oe_H6zY6|;L|WVB*SR@25>`7xJ%qjbCW5291MESWak9O-OybgvUP zLAfEUAiH8?s^0Ud0fr6~?m(5p6NOMpv?f)a`oQ{nN!a}6Kgyq0RaIq9bo}^1{p{JQ z;6hwn+_q^S6YzI}JlwN#n`^?hU#F*2p`59+&7JJ+f7c&OWk5{}B07byZkbN@%H00* z!y`-mN&*7))B7mFhS}QPov+sMHlLEC|5b*=kb+|6eRafMz-+X|tZe1n6> zGX~!a2B#C^W4=;Zm%OJcs90B4lHoXefgQDrt))qpaJd-zxSX6EuX#7AjI3-PkXBg6Uiv=cD6Tm1mietk35j*NbT`s#>TV# zYsfWRzD${IURF}Vr}hmvei2o+xj=p<^LRCh&*2?u8&w-FVUAXVpwb^-cyi{>>rFJG zq!`p>p#P#>A)x7O^1n1}R0-EEXbz%;D15mSD6#~yTdAi?g*7%xf6^;d5xV&h_yYcL zDH*rnc*xarRSqnikKc!~^u4yRC+ok-;*_NvJTM=QsNcfZw7O2fb#rfS$9og4+>S>% zl?cPgUj-RyIg^dPsi4UqLvw4c1Aie)C6-_9n_j(#3zNcOLNTv?1&&@p)AmLqM*!Ki zr~RCtrcUEV-phSp`MN6n{5xKaYq0Ay1{>R4(9OV3Ndzv-U5Sd0h8>2KCxZ9i$NdHA z@uTa;RJrXhF*~(yaqmzMzcjreD}H{BnawFmj7!L*iL)0|LX8vecr)*wYU*zNh198M zd?;wi^Zs@>0hK(Ylk)0>ZvUXv3>!+}R?JwQPOx#k#~|S4I)R%%mxqgO5*ylh7++!~ z>-XM1{VO$RW<%B*O7r>i8$zjpfqL<}-6#iHav9201S)J5EiG9g^3U2tnfu`;14><8 z-Fai`1H2;e63MwM3A2Mt`nBY7+^?Q=D77ThmbXk>Tz^>pTuJSVpMG)aO9EQwk=!kc zsj0n^lE{+&Kq3$1&eeO0rwwIfCbGfxul}DzOjY_}6annzmf-OO+

3=F8P3CmPd=;f0r9;27?Z=0s+=_F^btb5t5w`zYn z4{Rgzr}Tbi@=0&Ai|zQk)DvMaGPZ>gyoT|k?}Ip%uq{n6A^nx6=4OA>)*wFTCC$0M z?~%!PXlTWc(ALKN(O+y|+4-wbCbW*PTj~=O9>tRGYPU2-xZSPWA`^0|0kBxk-+A-* zo%XP69WW?S#T69`JN?p@^PQ0*;^NnMih~LFZhGUAH;sOhd(y9Rr8I4Ty-&VYw!o)M zcxs?>-(`*cU>}>I6e+zB^aT+3Lg}Sb{J=meC@46bkJi}S-*0bgYjgAeAWgWlxN5l) z@_L3iR^RGxaO27yvyV6BWYc8^GBCaNsdPVC)M>(v{ntw|h=?S>qboLTy@CRQv^@HW z0+z1hm%b!R%*&?RhsV#xzu?nSe;Iy%^s0T+(^*Gpz)r8aRBCy3f`o=Pj3l3^r5t&N zonwf;2oyrU-a|-*Ly#ID;ImXT>)nrz3*GJ5oZRZtLO&;~iD=aDUL5XF?W`#}abye1 ztqMOIBapf3;5WyqupZ@C*F0EX z_T1q%#G09zY<`6iSN6c>mLDeeK2e6<%<3qv)S2$|Hd`Q3`*q+tj3(8d2i#IpQe4J$ z2|#FsMs7X-!RxZ3yE0Z}mz>6Jh%zxbJM+fIPR_p7ukaysVQQ0( zuFDDyIDE%IVxeNvWHHU8j2Yxo5CM!)<85fD+4^L4Poh9@XQvX1TF|Pg{OPdO;71JV zFjm(~L(7j=^}J_YH?L#sm%N`k6jS?cqx&FaWV-)gy>_#W0>;&P5Zqwmf4$n9urTw% zkMcdqqR}BCSSVwUWtMF958V&#>SIq{n>_y5@B~_v{kcShy;U=KWr`}xZ}BV*=d z!?cg4$~%cyg@5b^h4dAo#7CDLG_&#W=n6E>Lq)4Yh-A#-kY^~tz`^l4_QrjF7=<9b zq1~=_Tu2acV5IljL?b7!K6N3xnoeKke(qJ}oBAnc@kZ?em+G3j%uA`b_d=#4>~0&9 ziAnddA{+m82+j}c9W^ei$nVE<8=*I~wY_qfYagt%GbwQNq$?lL^o}r=mWGyU&A-IM(>*-dOD2Qgxap@uxrQ7 zN8RzkMGdpJ)o7=j$6HmCP47BmM!8s&+v3-{wl)VG8`npjVl!-iLLWx2g83DMN7VxQ zgVkge-?Y!kO<+bWA|fKKPt$6gms@_-x<06J=7{CIHwz#r2+jNzk*F+({G&(L=i0;O z04t$LxeXI$T7w1LHXniO<0zc=Exx$}Q}44J3rop|?>+VjT@AT4L>Scg&g*y?in8?{ z)z{t=$;`)qQ*iu$Cq6zuzdVOg7X0ac(d_*E<)sZ_Vww45SRjOp$gb7_s057u=PgeI zuNQ$+Z`)g5Z?OX7FctMb!aoGsW^RNl+zVibu|_BP=qpxYi7b}ZCTR#R<$oy7KYQ-K zDbCG@Uo;ziyg^-)UmnT=xe^D=EjDg$ZebbnmP|xqgl#%d@IU~h&0w%hWP=G7Rz^Rm zrAkS4VN3`_`jq5ti9|4QB zqh+?3mtoG2^XF{T<@NlOiYxEqQKmiVB%)ohzY<6c`^E1jVYp&+BA zv|1y&Y`@q?3!}XipstpRsf9%lsIlN)Wa;KM>>hv5;_aj#Gwt{D<|^>2qpYF~jCTzQ`vXjw}U+Y^h;&vMViz+S$>9<_dRFl9G}L zPYw?c=h+nl1E+OzQsVBjX#h_{{Vu`2+K=aln&^N8!^bF(suEfRd6Jw29C^P|^qq+h{l;_@Iv21g@Gi zt6IYCy_HcX;RIX?-c%{t-Wr#sm>~M)?h%FK$-xe>tyz-Yl+@b~w3 zUK{88MWaGxIof_yJfi}05|AkdVizGZ z%cJ_2%YHXmf*6_4p}!ezLHacvT<@;7r6D4G`8Q1i>AY6&f*9p{&~_%n`j!6caw$`j zeVJU)-4{Q&CWtz*f&~t=G3x<62}wXvkzJgz(|EBd*MrhP7>5q)lcGTcwBSc#fsBH= zTj)yfy&GwIV*9IRW^GLkByoh%0yPY!yVH~urUIIg0w&B-2^p* z9exv)o}L~U7)berM>m%U7TxRoXmO;-gdWrir1`-ZEZwWe(b8;dZ|8r~jt33m6`0SE zFMw{(2MzDV`edS~e_+r`u+!1Hc#Ph+qPi}(;OgWz`B;OR<+(oW@%>T(lXQ;}p^!6! z+0VrHOen1}v&Q$r2PUqprX~@aMv579(j{jxc=6bUFz6PI)LegoYdahR($Zbq zcCuN~QwShsq*+UNF0N zsjyALx#Px@%45j8G<6=J+P{8%WNRC)kkPeiEXg1@<*@VT?iE719>9QT>^j+aU^37B zt(@*F?(qKdHgu$abafS1OKUBQV~*y}vgLZnWpQyzL98G`%;hAOK%!*J>zbrQEqMm@|!~%Kgq8)n;M(fwHls>SYv5D zdX9hT%2JNax3rx`@ZfwGJg)2?@^bb^jfP*B30VU|By|OkvI!(aG^?RZY>>l7^6%Yn zMIW$ko~F-M^Z!|i{gInw&G*k(!XF}xxVYm6`X}wTuh1SsrbmKdjHD?oElsySf?gUC zh+q*hc4bQvl9J|TW+H#4V>8eJ*uCI&oL6c+D}(0o1W=UM?x12q;zA1wU5vKCgmA9C zIZM^>Bk`O~<)+T$L!wI-7RS{d9TCCX7*1Hyz~A_)Q&8(aD!y%wkBw1aVq$_4cL#6} zn%m}YG(;2xZL^y8JrVjDm#AtSm+9`(poH5d$`2w9Gjns%o|jTCwt~+M*0<&Ywcm8z z`t~5|kfF=L!b)&+%9Hmgv2I?J_zYM>yao6p4Ej^{ly@ppvD2nLID~!Yw z_%5xCbbYW#tULbh+XEboOicJ?S0vV9f6B?rQ!y|ysOgxQG0O(wA*cjqp-!$QL&N#; zGq{R4@viBGZvz!K>b7wl#0hzSdI^#h*v)0oswaOZ*3cL)!}K}18-=V8fx>gNwUIm$ zSdGUpsDh;VfwWkB4Y^teT1q?KU99M|m|4*KEg-)DL>SW#RN>#NtEw=9ouvF~UH3kS zH=KlLGPmIz^LDMP+O~I{g=1`-J}4V&6f2`f!0Hd(#_X>{R)?22#8{`w41YFPvWIA%Z$g5$CcRHfAlYS zg^GWDnUo~ObGj+ZD;$>R0ZPJsDj~G;va%-#o=uTVx^e$=TFgiA=Er~jye7cKfKz^W z=w{KE+y&4XVg^mnkzx9RUivC5>~0^O1P3;-?bjqT>qalOs5Aa9Ix%OHe_g_~r4!ea zPBBpr2JbYxhaLNO0^bw2lfRWu2hz|`;I$*Is~t-oE4tMC{;!1EvFGvGagCb&JUA-#37(YWZfeK2M+P(W38 zcFUB4Zm8db#YHG*oO}`XwbwBRT#HVQ3c_fr+t{(wK)8WnvyhYO^AY@VudOx;(i?iA zu2b&8NKl22&Nj3-klh}lFo(yhMR|IK)L#f8XcXVY;YLW2qLC0_+GOB)!K2iLcIP$5(q{sFNlaAGcphv?r>}F@c4LkX(_=8 zv%xp@{kJ$%t=d~PsXi7MlDRgnN!ZFHA%g}xE1!yerB6=@GDoc%OhrR#+lK%4qT?BqYtG(MJ%hJpem%^YdT9 z0__JllouTxu*AabSHwd;ny>Zr8~KZ8*L0?5&?O)AeHi~3a})R3SWCJr=%;i z=y%+4SS~`TL%%Z1{#gi0SsQK5wk;3m5PBc)@@YHE%u9n@0gEjF?F^hh)Y7k7VFAm& zOmK`vT_0ubI_-zk;omQE^v}nuID7rv;U)tP4eg$!CnkPWN$PQVrX$2|#rlXdRH38q+)cJhjf0$zvqfSWr2-a2={L|>R? zZc+-gST#49ZNDh)mM%1{5R}FO#rLU^EDUy zH#kj_C_r68;*2)WpF6EL{ru8QVRGA^_kM1ZRWQ9i{pc0O<|$+8>JAE%CCeSuyT)hj zIWde7M}*G&G3Fz{b9h_=mL1-t{md?rwQoo{WB{AZ8(Ln6kqT1N!al>R&I3R_U7+Sx zyKOO|?CQ3z;8JjBT94+7x(<|C?j`=(|0|J(HEcu9Z*qeDgWaj8C(YF^fgi)r(2@J{ zmX~%^BQcB0qbE;f)zt6+)3)^Vb98l_QXHk+nHxsD=0a^XCt2>iHK|GV`K<;gG%)w8aZa$5%x~JR9`~#(ih^Px_^K z9T>e1XkT|(946wMzZunC@A!FXAfL=@k8I@g2Z3M;9#&D&iFc=>;^G;=b*w8OYo#<~ zY6cq$EWW(AhVLBj&BIWPVb_x3#>`f%szIit4Qf86oC?5IQgOyVyYALGqB0dl9kVii68CT;$}_kO-;c5aB7ex$3C^qKUtqkxX^l-8b;41w(+U7`rc!L8oo0bKhZy z5Ys-rCdYU&n)QfZB$Ful1F9mK4)@?N!*GWzIqbvzha&F8Kgzq#Ti+%#97tm8u%-Iv z0A8eoSPP*2;h5=K*M44kLyP}5K2?EN;kTL|9vw-#G-^m41tR=mc{wp_4mJ@D&>+z(2DA>Y&58L-n&UZUa&|OUcz&1Zez16;AYr> zNAHVAuJD(i73QHh)!vPI$m;?}eksfb=2mC(g#7Z_B$0rM2WmZ*VxPgj5j%Ag$& zE;}zd*Q`mxF#bcrn)aYNiv1oI{SHs!Cn^=MIu;bYSK5>A7_;t}LA#XL;rFSlAFo3x zvS;Bn3afCSWD|Mm^4?CyZl4s5S`SZNVxQJfQ2#$bPb`QCcc57(NP51=Hemz#0HzcY znai&;>xv3|^(w2jAG$ZCq=(?i{@+%{=)2cIfmBP85WRZ@;_tjqk_00!@4z^N8Gslp zL;?c49U~2dHm~h2wvo?9Ng%;mo^16H6X%wjfp$EFvUa=bEQz=pE^j+b-4 zs4-7>`D%_v>s!3G#OalfX~o6GY0yvP6cwWr60F$!SMJ45-m?FF`}=1jRS0Sy0UXdN zJOLD||HXz15oh0$-|Q}-REVJK1?mk^3YvTQy2=Mq+c5U{VYERW0KwPG6J=~n3Zb1t z3+>=q0b>0I`L=Pe=AjE9$O8zl0D$4Ty1JAj>TmHpmf*c1k^}tkXOqShfyxkx=KlT& zgt@}lPEJl<0u!HvRjug{hm)j5ho~nVl)=}wwh{=k0cz1Md>ab z!X%Yc&YEsQHbgKe0uwmRZ1!)N!U&s@VbqSji$;~GO||z z0kSC#Y)CL$SXlU$?PMn;nDOdG=H}*(z}&WXb%n7(tf<&Q6P9i_-GD@8U`bhfOMn#| zO<$aMJS(aXN=>B)oSg|!4+%3{hm^(C05_WY7zz`^ftVx@j zn-e_>0fP-Uczd>oQU$<8gr{8dL-HT)+h(BY%48^n;cZNJcjK6tOgkUA4?68L!uSJe z35nA^B_4s-r;&WokcQ(2GtS)B_OlOMuI>WB3T?o6s%2-O|Bpp(`u|(D#{&b7O)zuY){kF^6xRz0)kK`i3;h2ev zkaZ?$ZggFyf&Rw5;}m)oQSlo>z75(F?mxD5j7a4mox~|3q7QZkM^=oAy1E`AorER? zy%oaOmI3#ri@jLO1?*7>K*^llq~4<<->CM>%6Lh}3N(YyU-=zo83^Vt}MZi|6`C}%& zlJ_P+ywU}IpMP>uzJKDa+jiMz6{L1Ba>1!yu)=eH;7=LS2}?>y7$F#+jDG3T(~(@Q z_kU?=X`$uefz}|%1u9Jr4C`bG_o(|O-a?f!6s+?Q({NrI@UNWqNrK!!cic@-!5$(~ zGi;OI^Gj1T81&wkiyFE=1dJ^`X-M{XAAK4*Kzic_rIg`x^ITc~ZR!=ATUn$KuC8v# z_1$p)_6BUnnT-uQw+5RDevgCovz{|Bo7r`92Xx{A1Y3%xbU-Qt3k-{b!a{s=m`i^^ z(+6!sQm1GO&KG=v7%)(Z_v@pd8Rg&9X@+VDJZTTLOv%W>PyL>$OcG8n-51HEh&n5e z0Y6)V_RCH2zQj%{jBJx>SfRtsR>C}!MyZsP6t9C{u86=RwK+94HQC^u1P;Js3kwAx z(As}f`5&K0FUZv8!mvj;_DG)2>$h)P0YpIu5_qvTzS!_Q}g76zh^iT#H1z=puBiGYbLg}wRe&->n*%W6q)Q7hFoDSp`F`Y)v7%k} z<|ze6kX>sFPKd@Y*P%>hwfBM?CjrE)%j>^t@#v+JLBT;gCjW!XZ2*SJM?>OnL_q|v zm=wpmR=rHC19W~+zst2-KG{}vJ1}~;@o?D8(o)gP%$N1Ec&)|pvSY}cCA_6YiZB;El*F|=Hx+FMZn2+a5gB!euiQzxq~uPrZk!Br`#sR{0WpN1(2<@J=? z$s!ZnyK?K%H*mlFRs(5*@tyQiUI|YQ&>EIlegnuAY?K8A&7Q?yH!bjQ=YZQ5c^7(j zJ6xE^i#19V;8p-*TirK`%r2Tge%uw_?oDj1zpThw60#vkADwIy{t5$+25YWEmi2Qo zcH|<6YfixDTjzQ@!&RH&c}!Tv#NI=JK+v4~)Pz>flk=ycLP63|$9M}}d>jaNA^L0s!{=NH%Z6qot&)TT^( z(iH(wrXk8otELRnka5YmG-2va_!eg}XT@=8!RqxJ% zdvU0)v{!AP@bXf1g_%AAkb&1KAlYD8`=YnF7by8X5U^t_Dk@<1$GjJOs+~Wh1^_D? z1!0uWf<+f@Mj&%3dLJ+69CdjdsM4yYxIXvN-qcx%+BU(8ZeKFHr)Oc`b3$L!}G%ohbt zMGj(Z0r-1*xczskz7_``zc=yH`B9Fx%WA%vptaD(4cE61gT8Jo#K-=q7q=uxx)+6_ zzVCAvh5H6tLmqV7+>?WioCj<`|CrId#HufIeRUG?J(mEX!wh6}6tt!=`M2bQKm^vL z$Fo#XCZSJ9&zw7_}-(9K&%*z~c77`a2EV4dRct!Ny}K*X)8|#E0#auf z;C6y__5sA*j8SX&i|Og%7VL6~lN|e6U;1qIR~Wce3A!m-HfAJtvixv(CPQ&m{JdLm zL}s2Ap1;@37~<-udTlG$tirH*mLP5zLV>u?iMx=M-3A_YO`*tlr&l;p*v@#L(CmEz zmX8mwJO2z}PeLfqTcJxz+T;m|%^mcunabCh*s-*Dk!R3Km1pMjJkkif^;s&IR+JKM zyh*p7qa$e&V0MEgU|j!g%O|tFKcNGhQ+%i~~fY1@R*w5CF$9m=wbW@qWKA?3&)18>kblsT42yqwSsl z-smxDS;&Z}W+nIO7Ut>kCuUzb!BiSt4r>+;Z4VK7Uj_uAS$!{{0x0njc>jcFT9UBo znm(lb_6I^|-e=J0(4`H#ZYD_4N*&%7b331CDP-nvCN-778|PYkxmatFc?ZJjdBxFD6A|*K@HQ%CC534)BXj5AB-c zO=R{~CR~-^_ZgWS9h4Ia0P65r4P5^ZA%z9GH0`y6uNY3#H8l@mf44K2DDk@9H#_*b z)-PTUdMRi2`Frd=T2%L5G(l`wnR#*u(sXI5l)U(B0IaV4^k@ed8j?Li4(CA7*3>le zF8+JJ zV?qZn&8eH)1TPK8eKdaY)B+ZgfSXjV27ws7?M$E~Px zcx917NoGT1TmBpo8j563K|^-jUDEo~pV|+|5}I<6X%c*Y@UxNl`&-Xd!0duPU& z8zAzkC2(Wlh7)od*LA{(RfVbq^E(qD3nJzudV~Qe19i9uYNgb9jbaO^N~zn{VIrm1EOupj1hw2GRVnyWXYZNW@U zE-fw9_A4zZ(E=&p9suzP3OSnsZ2?QpdsW3^iuXoel~uvB}8=$Or)qCyZudcyDP?7GV^lpN$>@u1&k=fKB$itJkW7>bIYv#3w2ex>jTFO?m=?Cth|56db**01@x5sQjpsfy*HaN zsn&POfkvgAa!GJYNEo6a1cb*q^i=H!y_`P<5z%cVix2h@P~7t8KjRQ)4J;ENxXCF> zS-IGmL-%vf-@%>3!$B@<$GEV%fJCa@Tt2sqB@ibR#To% z&UmA*H0WjD>{AhZwVFv$%wB9eRo4aa{zE7c6yjte{Q!)x?vw`-F)s@rHvdctZmv9v z(&`z-V=mlJPo*7|$ZnB(3u%{Y_wSG4jR7Wl1HDYE&_D=CEJ&Lc$GgkOj)$jM;1u_~ zaxp{~W)ViX-lv5my9QH$#b5tfxP5T134%|Fp>cGl1g!nS%}^xqUAl~W6tn!^K|)jh z&YijTR#ToEk|<#6 zfVhP>x3;=?(Y(Hkl8DL@-`2Vg$JeBLQl*jfIr{IlwH}CNEW_^EKOL-f#%5J#cK<8( zeOoG8q=Sspf2e;#-29Etk6TVV6w)z76Y3d*CU1J#e)atU z11*n%kMHV@8#houDE&Wu`ZP0y{5!PdyA{)bxO0K1LJ~ev1qBYDDilS6fF%JyvAa98 z`(SI*)DmvW^PqLKw`ac|o18q&Yi*KPO@5sWaHn$&R-yy68vQDJcn>}lk|L+4PhC6e z-}-YG@*Wk=REFAuR;^dvL~Vw2#-a{^54{~yo7TZj>a zDFlEqc+;Rf4Ui8oryzJ5S7~W`fw)WnOYz)abN{mn&)5Fq+#8^l66pGMslX)7-Nbv| z8l(HH7FH%md5giMK|G$cwCi5p-a0PxTl@Qepn?kwtBE^PoLEx=v`(&DmH~p#hg2sA zOx!()t$%{KWKs1OviG`xl5|TRx5a?^WIbM-{^QH@hjHO-txc5u@R&zHDTsm37C14Geld!f}M;kRx+5=%8Zh7u6v`k$&6Vz z$bV~lo8K!{;{S^NqfD_9NP+b00m{*Vd`~_c4D0Ui*WlPQFheZ|SxKYrBVry$_k@*Gb4^8m3@4*?^ zyxHyTZIucWg~c`bPF`M(`;Um5AgrwQz`!6MlvQI4Ow3Qfyl=qCSQp5eI9Jk3xD_A6 zQjLO!G6GmIwz9Iaw7k4$7gLo(85K4IkI5S5ba#7u`=1;#U!dm+>~>JH{Q?N z+xwq!d9si32==PYbOS9Y`CeXLLpIW`>yx_umQY;~wVkMOxdE&8E$p2BGy&Cv0?eakM^%kKs^) zE-1qnI)HE+)oIKYqa@{={i0_g7c(J-WWsdl~dEq1vnBL6H3^N;Bj`+LzXrpfe z{FZ$*j~_o?g7dpUKf(6lb>E&BTmT)YWnDB_oM;&rAKx4_aDe(rU<=%qPQDGH2t=&_ z@N){D`O|$|JiMNf)rVi(w9YH1bIaWYFf&$oU%3R4OA83l_9jhds>b8Sa8W605?#hH zpY{|WODx2Vtmoq5Vuy|lO(W>LqaVoYObRS?@w6_3g%5>cqb042!2xjDORqRo)zp}| zxe)>r6%!Lu z8`xx_)Uj$u+n;Z@%hHB~n%8j4g@a|f2;~MJP=W;)8>0>37x*ZW>j5j&4_ZdSG z%B==x^M1l1_8f87f~>5p({#@}KnoG#3wv|W{y`>qZ;+a&)6nQwYg7+%+1h02NsT!6 z;I5?`G39S8rYQ0~(Ar%uG~KnrU+8}7cgm+{V9b_^I|toT0TdxfRVF4T&g{f!vxX|J zFuKBD(g&@E&bXsCveCEW;e$^8PZ>Dqq|m4~4me7wMKAS_O1soy(>MP<8~`K=Bog<% z;6VWJJ2==f3)UZ;^)cf(QoZjc5_&Dzk>^`D_KDU0BNDq!HqWh=ZWX>qD8q&V)2+vD zkKbqjH~ZMcNp#Z>1+aAv#LrAfIk|awZ2xkdzDi6i102b}{E`N|PaI+~LLwyyx-+!_ z;q&LuISi|c2d9GbMBKNT0g}T`_u-3y4Bu<8do4A1)&?{;_gLHqD^H1kzE3>u!j?c4 zf6?1r&4EZZe27QgVLI}$I;Y470>R8=VPt#>AACaur%nNLVPRqMPBLBn&xfU)*fpNT zWo9xXvJdhl>kfQazroAhHrS3IQNBR^MRK%hjif`>PL`00iRJgs(6Z#%%LN)`3@%!b_Vw}ytVf5p3m^XVH5ukTK))5yQ&yn;WpIblgn)d3-j zz%)M=KgJCNT7jHv3bwzW)Yb{4oG1k>@StgVmr&ftd9e}npvf^oPcg^MTaCw2soJ1dP%S{2=rvq~rAB3qExL;mjVQ}q?5zY%8txkVCJ{eE? z>@ws)&iBxEr@voyl}TuKqtlMbzh^qZU*&PHbs$}7n@vs%OnwbP>adxHza98AB1FJ} zfy+7x1|iz+%nY0v6avJ5*EI=I>J}DW6&BtEvCjf@y&$v{9e`DsK>EO&0;+%x2aD8q z#ID`4Nds=H|L~zsh5|kqRELIqm>3v?@DxDEdJQHzjFEIm)4+$=@addb{*kn-gu_l! zCu;)mssZo@;3{?W_irSgn2(8)z`3P2HW@LGLA-?zW!Qpn$QDTEkDoqOZuB{;a$Y6| zb0Y&nT>ZX&ok|Jf6!%Jq{f!!PewB3TE=o)frMlUGlZm$aoyB3FYj*`hPjBL23dD96Z_}5 zfrq2Byj0t4Yt?{ z6apv2Dmo)2jbMxELgC&6#sC+9A}xBqT;6mL;d|Jhb%3l z_ot)WmP7mZAU3qoFCR3d?}LYOwctxvex4H^=6z=rliA4Zi*&2u@Rf3X?dG&kzQ4Y? zy;nLn&e!}f)u`&byfCsz!+mkmf(JY5B}=l%-tJYjEO4uxlt2IPEwrOs=P#<7Q!39G zYEJ;KZv;nxu-I`!P+|M}&54I={X1W8Ct!7NcaQ-W>;+{&g} z1dHnH&EO`+4_Mh?AMLvW_v6Ts%JEiKbpp#5YxN~vU+BP(p}fT>%Yry-Rv4%3_1pda zqb2An>*i-#!!C8ZsIZAVdUPO7cWkkQmuJtlqGSbX#xj*N()U9+b8(1xrLACW9aZBtt{Z`EhaX=T6?h{=v!T}t(j#u zkA~+~pxMuj<~2}I5L&0rpfd0ricLoOyr*EdtIPwiF^1pDuUUM${MeHaz|e4A0IYZP z#XjRd*K)wXr+jWm^qUZs$;-g{0cq)bW+&Ji=@uI}II7XCK|3YIn!XKv{%c?yPeOKd zG?oI!1Z$=iwTLuQy9%O+0=k4>v+^!BG9&zW$e}PWFy$@j-M`}JFV-I)oqSh2zc#3P zl$dt4_27Mx6{}m`r34%rS}U;2L3Uo}QU0C9-OmA&hsDOyj<@_O+YrMY;}5L|7tTDO zR;CNPUYFwV!ZMOOv~Ff<$_^P<<_xiBz&;`LH-sVLIs|9_#wN=7BSA^ z%sci*`|OS=aNUO5ef%X|=}aHACWBP-TgC>&_$4PMBx4+k_5yNRl)dZF5hB_bR4m+M zGQ{eKu-Z`;HO!_)#M0j0o>FX8W_2NaOX_wd*NYD8DN-_qZlf92J<2#_LlD!;F30^} zG{utt;fo+KlLl`O9Ow$tYLv3R*lS>i%!!bGkyfSP{96xWL2QG^0IthV6Td>zz(vBO zg%H~T-ku-Y24wHLWr3AK^cm=>Hz%pC#E+^0>%o5djHbE(Bl%4TSfL$eqhA_-eGzr&8+RrIJ;uFZ>On#e^Pk$wXnH zRNBNOX%ON6|58xT{^xeue=Mk@3nYC1%-J7&>U8j^qhlrxnlzAf!$#x?SbFS_8t-l| zqatw5?}HLs_u+#%sY-p&s2xGg)G?EgXW`(GG18Hj?&|J-aND+R_W@QofkT)1HYFy; z=J^-UMoGNnFpJSF7}hs^xcg|vOOH`^4mjdhfj zDL5#>KbWkvI-sx}&*nM`6l4tq5Z*uw@yV-|a8(G^?c&0@wDU^Uq&fEK)Cl zzQ})xBoMMZj$%2!k_eqrA%X#u;twZouIG@P*ajBEq^fSG?S*|NB1zA`{^3GSY;(<7xUVJ=gpT-mZ}eohibB|;5K_m zP&?`_tfHz`s}AT#P=;(#X|LaLsx)kzhK43}9nYt_y6Z?mxLMF97&+>tNt0t0AZ|gs z=*iK!dgtWroK>Bs6{^?QZ4(`dRSS6jX0E$%o%u6aVVPBcGN5@-)S~=gPGv(|Y3n9$ zVAK0#IPI})R?%7E8OU^pZ{(+%`KHQ|8xnat=SSz$k>&4hl>B6@^ebxB-r+brl|!?5 z-lY8aLo-dCL?+KD#&JH~c<&Vn`&mjA#t<*AUj81c^rr{NVrE+mv<6}0PaPVmp`v>$&auv6EM2ET>zuK4%mzOa1 z(hr`3%Od{Z$57erxX-9b9a{|yI~SFRYEz8#>`8ifNRckOmK8b^GTXVH8JwCB812+( ze^}lAl;KbCRFB@L0kKPl&Q31bse|0tXX3LQI@z^jp1pnh93t;MATfXrS|O#8jVgf< z_o}PwclfKPH4opDa0T2A%QoBzX_-m;eT{^l@4FiGY~+1^zu@oPh5XPwyDj%{N@GuN z?;f&<;CTap$<)GLfL}-VvSGUBhco^%RNLjc6^t z_%YADZk^oYO)>#!EAC6x9uBa9qHTk=D7r`j3#9I29QL!~w4LU_X;Z zY+Jn=o@sh$BZWEnK#L5sw}(ji^X$1Ahhh5H5}tDCS3mupfIj)tsZs%Mt9GbZ*@#3r zomsVW#P~+<^vtuDpPDYF?R#_Tlt|R8AO`+PZh)>qK@3=Ye1KbE1x5s``E1ARuuB2H zfK5&fHo4>6`K$j2e<)VHU^6!NJ-@|29UI<512l*HcU87G{3^AcerjwC z2O;g_yE@o2Rt7Kb@}8o78^3X=#!O2k}n0wS60!k&>DY+89iDely(zE<>g zG*LCAvA>+Z&$aiu-D$7w{A$IvIC)Vr63*ja?loSi0f#_?h!kB9jtNd_J6h7~hThH_ z5*gC9>ghSs_3>l#3BP|TDpYl(_F1`l{gIy13v7~y?<_8S_mgA`Lf-@c`qe$Ls6wvq zPnXGh4oWI19*m1kVE)DsRDEB7pDM>nc%n@1Wc-Wjr*{JmDLm}|ovm^w)V+UwYra;w zTd4EV1U2Vbjh1Ye+6Ut6$4}f#@^U}^`pw|29AdRQ1z+JWkSu|H`=!&w&kvRYXa3#3 z$rnB94RD_T3P{dMq5Vx=^E`SP1mh~YGr_PfTjTb#axSL-% z$+`8Kk0tn(eti18L-vRC+3%ZJz1|0ZWxn!)+2YREsQzu)2CH68-ed95HaH{8J`1bQ?(z0H* zjp47K)^x-Q9(Y!>QLIq#K=w`fR&MsB5A_~K+4S({^*>a%7LP}*jSUy@KM|7kU`Slh zDGZj+h7Ad0=e&@s5@k|?66jI>N-Rn=39%;nD=X~TPE&{ZUow-ebWRa57D-^)uN5Ui zb#kq^s9}BhV>up?{uPx$m(*=nw=WdBbd@luso71dGzOaZitm=LMJS^blz6-yT7GGbC2L3(+JExb2t8@|$G`A@BR2oEpS` zJ~rnC(gAt*&i0Ou-o8E+=%53`JQb~KQ1g4DyM+Q~Z%Sh>(iZzM+X%nH=$dypb~9iq z*9xK7L$F$wdOe_z7eL2U&DUz&1H(vJCI$5IHGW7vN zdIaF@2xQ`Qot+k>0fd@9<=jDl z=p#6tMsN-pAe`1zW-#PrwN*pc76ov59+_VYkhWI*vk{K#Rv;wt_2C>_z`%7HZGYs1 zDuw<4I2_(1GimeBEzt7;_3*+-cZuKq#|UnjNJP^M7jSt<)LRXr|Apnqv!`U%I9c9H z2L|YbW@87>ty<4d1z$cqeLx5sw|1OP-sIo0>47^DCq6*O>;ahJU9=4Yc25;Sqsa#K zCG0-nF3(w8A!4dk=( zYZJ6;PgtV&)Ql}4q?e!zF{$ge_Q;Y zO|xh|{%F~I9j8?ztP)ANXa2+?Jkt8s<*c^7Mn-HX4Pay&NLaq_g!#2afg%xA2$r%} zPQ~GO3JssjVA6tu&k)#%su{YA`r1SRB4(0vCuJ*#U4tR%x)Hr5$O4q{CLKxmGwC6t z24BYfg0pAcaouT`=T9idN|*X7Ye1wjj9$57MH5B>xXnUVs++g)U)_9p_TzhI72K)j zZ>x^4GVV*US#i7$C7;q#eBSmy!vQ-v5VY4oq%gFb@n`jF>$&nL_WhJ;kU z-ZGtN4b#$|5_XaBAG$Lx&%<{n4lsyX&Z9=UPeKPs8c`&4_%0L}Xp?>SV2#r6cey^= zCX?Xc+(!U;>Nac;`9(W{`>{F4@wO~|JZ2}C^gHb0*JEeyqcPy$PIj_w+BT zKOSElqar+xk)xm1P+%5zMEJY^|Hg(?m9p2LVb8tU=V}`kK@~sbRxId4T~Juz*v)QT2q(a~N&k zgP@=L-{(2tP`!cIWQZnMdG~3{jBn)#z&@#QHgDd8zwoz1h^QJ`VX4hFT>{M!)> z;ub~7=a=z?{P7~_q=+06U_E5nCq6tGj{Eh$HF@67DKE`h3C=>F4onqvIRa=H*zKHt z{YQRaz($flUY5$CK125ccqB6aZOxsMhhK6+!2_`f194&@@tgR^F8=CXbQRHFdR6_K zrRe^b861e7#N&PVPw-tnc%JyLxS}3&xvGgJuy^Q*sjMBMX-!6p`jz#Pb%X4L8^u3H^y|n&2BuhvaV= z>wXGV!stRul=gFlEC2G^85>{=Qn$UPo?brkN;RrjTq+=@E8oXZbk$!=A@hk25z7ZdpAM?Y`KfHex zuW+DpUeRgy@_SI#ub%}`&WY}??Mr+=ysxYKs$_Pv@wlDF9JIIE*UMVsPEebI91psi zK{WQv8VFkN#K$*(B#hvtbXP-Ny>Do!sw1yw^aRyT9)&0Vv78Gm+(ANv6D2`H+qSiO z+1UK)6uR`eqT;TWuI_drnvPqhBU#S+9y9ZmZL8zsdFqT8O*_84A3pJIs)5(St!*0s z;YWKq+LQ7gwSKp?eIWV#iHc~`mas|F$g%m?Tg;tVszVd+9xjU6y8ZdNvG=uglU7~B z;^grwwb_fCotLbwE%38w*P%L=&u04;en%nV3;jp`oc^>REIh3g;kkXkwYESAkAEZX z?aTj~R-ao;L~+{I*5+6zE-t><`T1IXU5AjU=s|(GbB}-8MZ~2F3fAg|kAI)!TlooW z$@Y#5MMb`~Rn_J?IuTE19h$4w>*z!-JblahAi=$RHc&x+-dG>98>fdC}+BHW*bbzl*|si)pSuUQ6RcD(6_3-gTjbE=_19tM0PnU#B9=qpIUP6ZFmM1hmr7@?UQZlGFRc=R>0QuOBu;1iK{- zH5tg|;g|I3`0OntsUjlYDSB1B6}LE7-ppEGQ8C3@DI8fd)n;#$Ai%$;M4{%|@qxw1 zkL%3K9PHCw;$OcmAh$ZNGl{sPYXB|P6}r4!iiQTuojZ4JDo0D+rm|I3rzdVvjN5VS ziK39YU)=7LZyWTaSy`v+%L6)oDJDcU-HOwX_?cB5DjXTQ_$0SfNPv2*`@Qf&Tbr~H zjOYf))ToIq>)!a$>FxJasMVF!_x|*_y}jjVXozi`VRqb2<*(HY8d1YX9?3_A;Hvr zY>B#jiHDjtH#l@wbJz;r5zWf_qr+$zQC1yUDg6HE&|IXB*VpXq)c!CgfqL*#RR$P! zbQT89s?*=Ri`W-Mojo&5XXEW%)sT2-)^0AcGfhEHdtUNt)cNfjL!?TxuI#<4m69L5 zHY7P^>*82p3*Eh^?nAsve`JcJxw(B9U570Ly+Oo;Ena%#7mJ>(EZ3apo?a0VO+r^f z7rh^E;pbm)50&JK7Tk1C;=IC~u6Eri+D$Tdca#n{%b%B!y)_kC`C7rx*wZU0y0y99 zP)Lzo}^%MtVIv%qfAMYek}Qi@+sdnqM8lPGd-I-k>csm=ae_1wF zAvAaSCv8uglLc3@dLv`2hl1KbME=CzQR#YrT zltfhzNAGs-6rMfrS~%6FRIFf@)|z%>dSb)eTxCDjLw|5x!n8tOedMpy*N(BDCI@?>?+Z6@mYq&44-|*xD#vT=;K#A>oV^0{S{&iU2m$vqTqFN=MMv0Hy_ozsWkU{ z;&Ju+-DWdCkMH*NRN7lN-!*2PXjxWv*G|h;Biw#z8i2|Ge6e#M@z=Jo---Y6XScuT z?yrfujEP&$yILMgw11*-yzt(=*AI0(6UtN!5~^!ENOi8}6gr#L&=A#Rby82e>1+-2 z3S#g`&fX@6KZSD2_XN(W-r50MMF8-~W5`Eb!#DX0okV{d2wF49Ag~L$WKh@6Plt~Q z1R&h>p|Ps-w~6}s>HEVem|8`AHNUtWV_W*lSFqf?hS^xX5LQop@8(4=17NcrTn7;t z#Sr^IRFhS!^+^uUq06GY2Qd1?k01SLa}YZ#^!g#(u0@PO-q8LxC2nT{8(fv#_Y#WfZ| zSiKIRx+HCOm`5zbD+Hy^5hw~Wc6;bE)YR42{e5Bzn6NidhRTdF+ZPofp?bq;5}jfi zbSN(aZwBLj0Lf$3>VxE!V6iF%$vL&~2??zLVH98jnNDT~xiA3ycG$FH zdLK4>_(o*DoapZp8amvHg-Koro|8Q=RyR1c0g!?{oDs5@zc+2|iZ~_@ato*V0?27q zC>TZcla~`?ZkU&mRRg4SmLiDVW1A0eX^}yNyA14G%Zouo{#}mhM1qB6D zcx6J-_V*5!2BGA?{qW%y+$>JRZWprU{itQ|1N^8}feaYneP3O}`xdI?zn7%XhsPQ` z0vzfXY_JHJfNF~*=;#xa0u0DFlrN3v@fjeIMtU>X(sNBN#UzRWI<)gi*AdC?1XOTM zY5PEE1dHz-QjYsZnHQmvgl=7GX@#g23*%M{iFQ8Q7rK5skcQAlxs1F4hOSm*ZUsQa zYUmyQuEKB^T-9V27Fj<`AVEX{VmJiUE7&G8!5n zR~-d+m+(B$pUQ(L*03y`vs4tW;HRxny%B^4N~lW&8+hVqh%PCJq(tmb9KYgZ>|JNa zEdOr60q~Qrd%poq0Bv@nD#1#vwomj?N9mi7L<$;lY>dWK9S+i(iE~uLGW;0>fkP>A zNqGN0hSXi(zv}_%YIJ%^Se`E@s<@5NtAsL{X-RcN>YS8_!IJJvpES zH#>hw)kqf;P%43s(3r}DTa4pc;GxzLScx>|#Jvp$6QDx(!fCS{-fIv+0c}zRb0Nbl zPYA-65Jo9+g6v~+=&E2^)R*@Ud4YWpC)TNNog5^@#qT1+E(k^9$vW)^WW?3Q{ZQVy z!eh9BxKJU&62$-z7~&QIe#^TIeKM4x9^KBs;9%LmOXP;g0lFUi8=`ALBM)LVjFu@* zKUo5dhgdBlRfmcUZYnw}Shw*bpF4)`%blI>*AZ7q+yTXJhtIrhqVK#Ypx>*;s@SB- ze4_u=)&Y545W4^`stLS&bX=Q0`hxF3eE1Nr13*`tM8}C+VikRJa-+jIxE{ch&|e8a zWp4m6B}mVv@J@gDa`JjotJKb&AKH6KAdnuf`PyH*C!|Msw=T)w2Q# zCUtWSZ@qAH70u0&4~yroBN7m*yM$G7Fg!PK$wWF&*8bUUAH3bd6T43O#<05cCnWyU z)6nGcS6}Nd5sF1aEKkvB_6Ly4RY$1wAj7=?vQqFX8`dXK`7{65KnzgAP0h{I3Ku{j zh*j`(y)}s-rb&H-8rz42Psn!r0iFrS%X3kn8@RRIWj|m*c&5s@Mv-GlaND+_K!gE6(QulGUR6~I zRrl8fxfV)PG;8?`@SxYDfi4XercgYEJy56guQTi&z^g`sI0aHb92*{k^NA{S5L{br zmQy5)rih0N@sk4>52!xk7%!R+(8M)IS(uyG1;~fiWEY$|bH)}ShA3GuLjslouhD%W z%v`|aJuqUtizAho<$z)(SlwS6G;k*Tx#rUKR0)4B@pq$s^sfOFrAEZuHB*94Nn+bJ zcA2~um+r2v^~x)#+2b%NQXS72GiNq}Mnd=r2u2vwbpfFpeBVJbg@o{Twr*|wyVRAb zFj|51X<#Qz`ZWL0KcSd-2MPrR#o*kRlu*Xb5=@v_ny)lBcN+E*tJm)+#qtL@PlcUX z<;5+)yBYZqRyyIDocLG}jRXkB744Xk0x+x+#8>1a#H4sBik4OUGgpG-NMKtZcz)87 zBw}E%fG$tNCo3!48tac1O9cWZP@V(emP5#?3j!$dn+cv~SEItfkhjpZ)nbL!0VL#t zY#;B8Xp}MTDFVy33G7Gsy>JX)gLhMz2)&vxlkGLgOpz>r?WiNnw6WRg>EF|>P{Gp$ zBS8nzj~*l@3rNGRx^i%EKuxELqX&_DyUpbe;fL?9WRfAK1oT4R3g2<8DP9=^TkkS? z#-*kTBKF!~(L~w?RJ8@U5Ia z+}siuO8C*4KNsAOW_3F&eTBM;Lig(Eld$ zq9`CX_5S01xFkVv?qrvdk%6_e9C0abad7@fsJww#l^;Qf>Z_j3sJ1d%IfL>C~LTP9YWll zGs+S6C($0j?n|(QL{iBigMe5Dt^o4GAK>V2Ju{^1ySOmhwR&HmLMnDYQrM z=#aq^@G~$9?6MWWGO!k_;iPrP>ADJjeV(68tX6 zU?v>voEv3v@kqjvT98cv$sjy}gK^9xHxK_r-wb&b1J*rZCxXYg?(fC>>whL1xW~N{ zB%8*cPUj?M<>|tW$q|bo1dzM-;nKEP72m;nfNqY5qz~Xf7?e8zJ=g`oNWt-d&BRJxuzqeTW1-*!;Kh^v3PJ?m zY!{BxYqc_TJ)0lCEW<7hL0Lva$Qno>_RBpx0!krzQ`QhoK!$S}NjZ7FXkFNjp2F1) zTvUjpXfuF0FM0IDD=_`j)>(|BpMh82kGcZ86#08musE8xG~~*zFy()Cv}H(}62VK9 z#XIcbMf2|H&U0NfPj@S@#sPC`k#-G z;cV7njqMjjcVD+WbO_zV%~+~2k7&ruGxGbwtMaPYPhbEU>Kzi>rJs>PUX@g(31TUa zXk6g!ha4gkZxHlIXl9{(=ClpijIGB?;14@^8vGW=vxUTuWO2FRi0^d!;*VHHOr@bGM+NhP z$R8lXsST4xmZ?VW?r}U`A;|C6c=ynIPQc)%4>}El>j>GHHzn8a<^2wWSeN z7&o>ws82vcUS56z$xz<;*^|iEhz1`@ojng)5#rdfmbKB&glKjp9<;EiXl*+`1ICQR z2(y+VA8#r=>tY*#+VmI-DB=Z9IK;?CWx#nwJ_hecSyUhQkhPQC7%mK_vB8J65b5MM z=?VFhQ5QJNL8+q+zvR@GRg1@xkG3Z{f8kr33OgcldLZ8bH9`w3lM_b@&O;fG7b>*+ zcTG9_?^--N;W;vow)~L6CKX!SW|+u2wFDwpTAKS-&Fhy7T@x(hq+^(<7fVoJl|uy%nP9B3l;=CLHyFhnimw8nG>CS+Yiu#DfN z4Q4ztLF6cGsYFpaM8+5*lUb_BvGs{L!!A2q+IC!;*ST{Fa<%7;zuv_t6l7G*NCgN1 z9i@IOW$s0q}1>*^#{`r9uxK=3=H?21T5(UDpZ z{Ub>mkc~D)n$lWJleiFj8L-b*She6#t456lp?MPE9_VErJ2nfEM2PH?jyz$cf#g&A zcTrnkmXar72qxipz*li%$T+o#faP}W`gQ!awZzH^>rV={Cx`*6820%H6NUm$2m*X8 zy9e8e+oa3|AC4TPIN!mxBveA zn-(fjBsipC#a&L~+#SbJ*^DAaJ4)mgu%jA0d`PjD7VX3#a-)GHUzq?Ygv{AOGl)!} zL(c)kh6rTCj}VPMd4A@(&LR1hOpU-BK>jAXwB{Yjd#Nx){n3OO0QmM7=vm-EAlfCw zEDU9d<6kEB4dNiG}k)g^4q(>UF215jl< zvc)bxg*uRtOZqa}8W`HFhM?exbC{o>pKFY4Ad;&gFCa!MXl15?Qbz_^3Y0WC$f9DF z!ps0Ttu=J}EfV9G42$Oypnm*@L6J91ph%#@Qw6-X9)bSYXzmpzY7u3+yGZw8?M%EF zjUFD3N41NN8Vne%3OZdnpOG1_OmOl*K_z06vmSsQ*|7QR^YNt!X+$m$T`TLtoz zxZUTsL1MPN2Xz_2hLAUnL-q~RZ&@5w_5&GLU_g$(vt0mi2I8p)6u~h1IaV8r__V?X zxBwD+0-z6lSOTTk4QL~gaYYcrHh&c6=f403RQZpn+r>}K#X+RG{VC+!2GP$}Bd>nm zlPLZ8F&_Jg%!L8z{0;J@4mb*euuQ6cNc!QPriX)Y7!L8+M9J7^h^Qw*_m2E)7Kw67 zltI<%zP%q&^Wzzx0lr`)ehvr55xiXJ7Wv;O!oA!YWgWD(7ZEjpz!2t(Cvt0MiK^~p% z;b+uo@2S5a;Q>hw2%Y@+TeV|o$P;TuK%_8!s9IfpPs`HoEszA-pMK|OH>`D!TcrBE zyZjWh@c}C4JsMk?qTDsZ9wdiFG+qCaX*%uCK33(bz(3{`YvEAfDf@ofbyNM<0w<@Q zkXuIAgJ?I^IOjX`(OjTh+Y=={QTF3kxx4Sa!}KgGj(vJ~W`}UXobU9H>1HXHgwN;o z#mFIx6Gx?Az5-)qiFgOW6~>Kg;8tPe^(GhdQq+W z_3hF6+!xj%%Bj2<&_y!i7Yaq(_`zFFr{ zR{b?8GE`tCFhV0{(jD*>r|$u==&<@hihn`D&XDuef5y(1sA_A|-@1Jpy3Pv#t!x3z z5t-Jr)fWOaFX;-E!>J<|r;d?{$wpz}m53R{E{n(k!R+P}5TGXCilKSPF|J>|y23eT zpW1H!{fCw(i^I+uxgpIuZf;NJz?&b7&U4_I0kcQ?*M)E;>(u` zM#jc{R*Ul-U|=#_QzQQdnzc2^)v?!AL9>ND<|*)4$xWG8P&C!LY^=sXh zwl)Dcu7m6^g|f%el81P+KuN^~pAN{zOIPxG`@^sB?P```t`)du9yuK7ps%ihhaC#SPJ~X^_npVET1zb_0(A`Wg9Cz6T2Zn5;K750UI@x4J@OUAEiN(+73bem%bm>b)Z`*|lR>Ct z>EKmhPbT`zaKSB>Kc>F%!-wmjd6EZ*c}S<=zX@NKQvjX2ihV3PQ&}5jO3D3y*4?*n zf)Lw~YrSwCq_3;5Cmv`JBd7>PCM73RBL^)7m_>^V0ETn~-L7@B#)8QSdxaBdbk)=v zuBr)Kzy?2b=+OB4l0R#)Mk-+RMU!ekmuhegx+?U>HWIwBXJq6$IA$ns$^ik*KHoUP zPoBV+YdD9uB5=Y3fk%awjf3Ms`H}tmS8MC&=$o4plc7>TVMv!TF{lb6QK*L=e4D)X zg>LD?CgGZ!0K;8Ewg!E#v#gw4FMb9)g5V_Y+S>zhgdxeIroh!BJAr3vYU(mFtec_! zfgAed{ngZ3_>rcS^Dh1*YAEjM>FFJC#D$|7G0UeY@7Y6ToO6iI%E}5dgd<3@+A#&( zNG$s1W?=#H?C0MwGBWlI4_`wC&cA&-2R={WvBN&o2a!oCry5uT4-$!*-=!!l%#AYkNLSD(z&W(ML|pp z0J47AZ^506{$_Spv%HLjAGk9byZOcGep2M&!KD-wtb>McE21@-t~EdJ1xFcHK;iTd zbCbE1WQaCQC%n~o^o6Y{n*@?2j=H#nDlH7_k%P}jtaW2(Mtw~U9QKN?bYr#^!V2*| z0rJ(@)s^+F>6+V$Wqi!cj&CG)C+Cna^O<5MU*_mY2Uav0SxZds6U}s|xXHcgKcD!a z(c%N_A@IhHtC5kcA3l5ti-`%qJ3RtQ?-xv~z%~sc7`CIMqqi=P{;qLF@>0a(Zr!^7 zeIqSJPEJl!M@QA%d|mPU$Y!I12l+Q|W&qz0g&j?BNJ#JJ&jCPCuvUq5-dmckk#*^N zLt%^>iUun{K~>rds7Lt3#aCr!W@_%+x7Wv~XuhNyIVjBatx;}c(z6;mvt3lLqj9-(@3#rUr(F?#Be5adjO>nPdZZhIaHb zC`XW8k4SMcF;SrN6z8RB%qu5f>{VS;LyMI7V7K}ZieNPlk7xK=EOC%HU!k6OgoYc% zKQAwDC*%HDDJld=b4B{(8@5mKJEO_GiWf*Vok@ICLnuug@mS zs$_#fCL0W(Mg(oq^2IB3oD&I52qv513kOLL&@e#NLPLT3>Z;-4;Ss_9>(}WA1_${i zCD)+HyPA|ll=OJi=<2;($?v|I5erW3n;kYGd}(pIQBm$ccp#TxU|?w(f+MRRkit0_ zEFZD4q5c~OFrp2{p}y!Kzn|0(Q(U^``4G~p2J(d8rA&JP-T31Qsl>nrD~^UjdH{H> z=)Dn7S{NH)o>9=}g!4CM`R_?AJ?<$+txYV9+}jw@Lo5e=$ak4ENyvEuZxSr~q{ok0 z1O){}L`7d|z;v5}B;_I|?d@c`0aP?CEzMkUUDLs(JBioC(ygqdY1lox9w!@4_C`cO z#F2r40X__Iotv9Olu-je0+Kf>g%@X&u)Z2t=70WFmWVlXGc19Q1h!;}W5vkDWNd z2tWX+-bSoj6uMq#9dds#f?On?C-!1#ey)180NV{YkwXz_eCg)gRFjvANmk9WRpO+W$v(v@#0 zZE0b{SnBcF*_D*()~Yr3v{wzy^ORKGEBcO^(l#XP8 zH>DJi2~NuUk4|{Q$RR2wCgtVJ_2^j`exDupz3lh1oEMCZw91sb-Pg%B(G2C{xyN>R?~o07>s`enk3?B{m}*8hBA**&(JZFq;&3VULDmI%8kNIKkeUA>Gkb|MIX|DIHXiKNfwRfpXq|0$K$ zC_TTzWS*mT-c5j_xG7vywwOajL3)M4i{U|>$RyDpP@(lUsKj`alL{7O;l8L9hH=zAPq{e^LFR4Tww3u5DcXlpPbxU=xou;{bIYg z0iggTo|5!QYwK6r&uk}My~A#-qkCt|eBF5Qm!yV7Tg}hx}ig2A_Bu2<1s1PrKClsYE zh=@nIo0Buf@tqEbnA*KHSY6c0K#_3-^Zxn(KqaBzJFuW!IBk0@_`t~y-8#R~$5QU% zOI2tA$4m-}(SkKIDjE{h{8$vpR(gI7zGQhc87{>(HLt5nn?kc;>9}G>DNt$^78d3Y z4MiDJb{tMP?x1!;+#q?|wQF?XAEA1^DRJLu_Gvl?bVg(Z^$}<1Rd|GG;*pksrD^ub zvv|k)t-HjEbKSb@D6y|kPP#I) zvTl6+`gH}sZQjBKU_)1sC82%8JUBRL1LUvl-Ma(GI6Y1e7Ni#yk^g`o%ATK}-v^GI z4QgHT18i(;ZhwE^Tn36%khchslXO6&AkCELefVKi4P>SRPBQ__%n^Wx!bbS*7UVj8 zZ2jbGckCE_rjZz&8Ti0%*di?>Q;8_M*TKO7sfI7$|ZQ?xR;lU2RQRqh^sx9m2FtZ&E+5U+Mr+d6{O0k2BEwBJsE>z=OjxLhLKl>Qa59BuzJ7^M>e)dCWDCVju<2D?Eox5J>W31m< z^N{(W_sf-i7Dk6y##uo(S&4HL^ra@wHT3i<9v(Bcvp_05?S64sc{Agnss!@6E8Ex- zcmMm4g$1{{x%seswd zHWp=MWGEjxv>xw(KXO9jZC+FO;X}pVT%c`S#VW>Fq+t9G$dXesGp~K7`lHS>9DsZV zt1t+A5mhBONl-B?2nFoFu57zK#qWZeK;zHDv=cS$lFo}SPCJ#%%=9H;n$vQWlI1W* z11(|kt(e}!-yaT>$O~Mt3@C2zz(C8v!Qtqcmy#$O_`)@Fp(#N&E3jh+Cst-T_VNyf zpTSSkd9hZ{;Q*dMW+0%X#9JN8Ta7}CY3dU;6F0`|~MTKQh@i61pI{@%A{kBs=Ph!=*X3sndH<|8oboKSR>HK zt?AiA%dDa-6iF&gR1c#OAKdq8eBuBa28;o7POo^qMgpcn+tSif+SvHW@Oax%p5bcv zkMy8i0SH7zL3@b?oz-CO?W<9ov~}*RZiOQNa@; zz70~cvZGJT-7Ph|s1#!7ZeubKX(^m>N(i5sDMO`9(nK*a13#P#*5H)k?=Qly#3VZB z%+AT;|A>Z>yYB~kB}`jR>FO#*M#}F+MmBfFqJ`16rb^-6W#u~aXrM>{9H<0}a2dkS zjI1mWpWq8CTvlG*+Ntz13WP9Yq#r?GB7Ut*9k5I)Dnh-S7*=a%18gBVCujdcE6T`h z)puOqzEw6%i1pYbs5m$}GJ|T<2NDQ7gkJD7RfU(yb$IJLer0mgKL6_x7{#{d(0Fp|)nxqkqW}e6fl|3y|{0`SW|Jsk^5?D=8K7hS9$AJcbiRz^CjC>a@VXDMnIOGlwUT>Jul8%zrv*keUPW zS;{}v?%9(f@1GAh8iIGjfj~I&ePLk%SQ?=LhkU!tG(I_bQBB|#nk}8JM_HJk2I+Rv zFfqHEAW8U%CgEw!lcuauIjpbGjI$H&@v_erW=j@BfZI??f%_M}GzRF|!^p=x{1R{- zvO4iTbTkbPZUlXbG7@4$KPh+}gizX> znl8c_h`78`C}+>kO6*p|Zzl<4yor&~ath2HVT@bU3caNA>fp;q(Jh&E9-ZEGFt*M4@7d?e&>YbdNq)zv# zO@GD7LGl8;6p)1u0OA5<_7|Ymtw^CH7{`q`lO<23mvrC=s>hl)Z}!565Ks6Lph{FkBg|MPn&}_m zEr2nY=K#jE+Tv4t4Gkl!(5mAa>n>S?B!aTTYf1#|d(62;$ba+Z&4}P(6hL=iLALm_ zT8S8`0ly&fWt~#BmW|`teTHEd%BbQSQCa|i zT`%vdw%~>QJ2*HPARs-3v}6B)je1_qT|hB&P?DdO+1;Mpbu+o^(b3;E24m%M#fc|p zPt9!ye27}=OLs}h{Pe|()DS%)?_i=FfkV^j{nmg)s)7ZW_0I}1tI#@g>``lpCqN|_ zF{UriJ$k0YFEGNUure(0i#1gfT V`ysJimxBLk?cJ}IqjKcp{{z>QSPTFF literal 0 HcmV?d00001 diff --git a/docs/relaxation_005.png b/docs/relaxation_005.png new file mode 100644 index 0000000000000000000000000000000000000000..26c62fba2864073c801334396f56f5fa9cec811e GIT binary patch literal 17845 zcmeHvc{rBq+wMb2OGT|T%225!QO3yBD9Ml^BtwHSQ-)-In`fk=3`t}RMM#-SMVTs7 z5*o}xiHZ#SysY*6ec$@_{*Ghsee6H?ap+j9-sgRu`?>GyzOM5;uk&_RM@wx6*Fr9a zVP>dr+pNnl>@0?1`!ID1{zc~X`xg91-ffGKo1T-Eo5x-kOGb0Ao3p)>o4xHmp~IFg zuC`8&QsV2xrNo46+}xa96(l4a{(XVClZ&-Pahs7IZt{ooHe*+Y;n_=n*b-FYZ5d|E z67|g+^p8aJG5g*V|GP^{8AMa75PQnRfjN>tM7_w{PD*h zNqchA6&1gDid|qo!ih^_k_?i=0StjjC3leS+KjoUwe16%GSKR>@2fBnd3j(z*~EopbAU0dIw^|zR&qvqMZqoboM zS)L`WE-&ip49CXC6dAt4;qYe@KUb@|o!YCizvO(Ifkof{|6yIO}U^Y+O5_M9&`R{iqwm11H$@JgpH&(SiA zn}qQ6UVr54O?Gy6x0aGwb5`xz@x85FuQ}gWvskp6!ng36%)wflLKfS(z(B*AB!f8u z0;$h0@`VQ&bll^Zj`2oV8i&a`gy9anf`VzX4(~)16vFyL)#%GY+NO^VYeq*$hbeld ziC#ri&*Utd4Q?XTyi zP1JH$Gh8;&FwN}Yk#DzNhOAD;7!w>CvhewzCWUxJo$tuE;;y&%V#LjI6Hd+G6Q##n z&z$(~!qC#&mzJt^VKPHXTXp-I@-i(;=NhD$HM&Wg?4LFtw?B7&o`k5d@MbZ?GN zF%dyQL3-hZibw8t8kJ0;*Bse9Yu2o;hU~Odvpm`Zwpb>+rrexPqhI_HlMqvm;g-f; z-6`4Cw>9RO=6M;EhszndxkC>mJ%ENA3NBM@#^ANYNZ$6AQ)xWoIOVwJ2DfyY@)SUX^gGHpg>sF6O_s|e=(xzii$9a?!dK$9z z#<fV@D{h`sSswx@J{sZMVluUxFW7K%cqg2fCb<*z7lpk1x5aCb_#@uDN=)w&J12L5YHq^tc_@T^d`@&s`mymgZ!(c`_qZ zDZG4n*G0LeSG|pomeKO>8Xp^N{kZe4+{`r7M{%!S={$S(>_u~Pv)iJjBCLXMuQu@{ z>cwkeC%tp8YwVb6fi-mRe6y^f>F5sUoIU5xoO!i0P;rTqlT+0p`_qGR=Lh9VwYtYY z2dYr;s*Da?_VM+V@#x)i^2CYxm{mTAx_Uys$l`02c-P|CT z+f-bvrmU=7XWHA-W7;7&wSQ@CqgZV-e(pTUA4@h&t7WlGx)Kz06K}doQE|@rQLn4Hpg`O_|Bg%R%S89?+H)5!=;ye!?ogYA zoUv@#GTXOz_wIh^mMGkL-TKDsFZCJnyLWA?f5>2uzjZ?azOeq#rxVAH9lP)S(-A4X zyV0Y$Mo(MGQem#krIcwx40AZ!wrcrcSB=Iz2{XF$eV5klnU0O`+{9WWO`@&eHM)t-FPysuu;A{27k}c8+t;pLi!v56kv3$v0xR5{>H4VA>*L9J)oJD` z%T}yNc5Sb~-qMX!aNnVJe1kpPBt~c3v*O}|$jZAjtS$<7=Ct3a!a!O&J8jo3*b#$Q z(3#3F@3Q&m(W45^A6PyWdDO8*Cxm025wmMz<|>D2VsSpL?- zk7VrMu1PV;*19TcAjv;tXeK3QUgvo2s9ny^cO$go6_u0*YfYSNs}pwSK9F)ehtj3W zHg~~-#2ZT9U07XF(}(vd7XWg7=R*U9~Bz;;Yn$idGZ8 z(kYCMk3U#;ZS6t@w}dxu-taD3bO$A&v&p+phJOafWEvrR%gd{)y540bx0PLAsy zN4M|TQH>%S^YyEN;CX>R@&Hw8@5(nVNBp{VWK zx4*##O~rFHf>F|M%QgGxH8nMzx*UCz)+mUFU&U_^)@b{^r`sL$RGk zBEnQYTcr48?RBp1a}K2Orc^2W!0cU31|rfcFf z!(Vo~>5c_`p7{DC3S(uT2U`OcB_fPZo;n2#p$V{))M+Dff~s%f-S6#{tB^qu-XSP| z1D#ca?_Db=%HOGtv`(xI>pgn)b##KXZYU-OFVpBMl_=0hU~3j{TwF|Xd`iqL*9ePW z`{MEn_wmu6t3*Z5^`BPUKvNKCdEkJ}n^<+)?ZKBX*JK_v+_Gg$=TT09HT*MVAJf-8 zMa0FmCQX_CYW%nVxOTAg-Y1i3FWtCtR-0s9 zsp^a!c`QO8K1Wzy-uO5tPpxaE(h5}T6*rD-JXn`%fT`A0J6=v0M^${Cd)F0YxHTN9zS*?d)*ipf5z zP{{w#XDI!lTj#CpWp`pzv*}#15haD>G^Hd91hN( zyYTtz*D-1`hdym4kc1E)#yu!0RNZ4WP)hqS_m1hKU4(+Jt}@h*-pG-%Cr1|xA@{q|u>MdbSU(}I3RQ9k`=6%`ewUE6j5>1dQ!D_nj65LW> zuwX&hn!U%Sa4$*#QbJBQy>#i)Lu^A$++z_gvG7L5?0Ow@+NvUArFxjOZSa$#B7^h; z>P0VD?;p!!9471CI)Vsv|N6R@KzEeia3ZGHT48QbGR1tua946#b%DP>(tI+uJlC{o zdY6}L(ir$Dxi;Jr(~z<%d$m7MDGtB}m2J0H{N;Ym1}b0n%Mj9&IJv688Z-CFtP>A zYw_a61Q2?2+6Ag!GclBPc(-FdC(t->rTUvyX}P!NnH|}{eY(hgjgTO{0#~G<->(f+ zzWhcWY`-EB%`t7R$eJ}MUqa0m7{5-!9iw|2SMR?6>f7gHgA6OpEnBzhj_75Zkn4{>UITOkZLDx;&NoFRLv<+em>9tkut~zuPo6vxR^R{p!t1i@Qmw7e(&RsE z{T0r}h`jO}8?r`iumfxp)r~!)JlwHVY3$c$?5LrISYjOu-=B>hT~+ac{{r2uFRu=N zj~chf680V9{@||}rEJQ5dK2!wmY;+9x*ka=Lf-XX5Zr&bDvFn%Uvp@Z<17xH;Hu7Q zH9_B4uz+g;?94Cz#Kc6ePiI$1Tb0eH6bjV#?(W{>sMGce3w12s<})Bob}0YDbp>O$ zAN4*gbz8)!%2wP^O8(K)a1aEr|LfOR;ZFI9mCC<&Y&ky{FD{~EZ_cQp5+DsG1DnOg zFiiSKH-(xz#!{F)Bu?Go;qEkL>l0WIrk#^z8h+gY6ZOE((#^(oxud)z#Hy zm7hOzq}QuZO`*Te`cGJ-@dlYDX!@?Y9*D(jC>@*g5Rl zQ2&4#9vVtC%kwf8UuBm202$h~u@w?jhE@4ON`Q+OZvacsJ96X!s>K0?xjG4N$BYXZ z*2v>@F{+`s|MqR$bdW_+xDaVBM;!v0rV`{CO*Nz-f+wIb(aSVKwgnT?tDOQl#mI7$85bg0ghA!sOiE0Hd0#NkFe!h5hcHe*gY?xESAiEc zf5u&ziLWnFRyLy~3J$bP-T!w(v$XH98%ka>=bDQJCmGhFpO}o5LPDyX+>3&+%*tcG z_RkPddXihE_%Y>2-_feSEsiB@a0Y;W{i`7iOY$6y?^p>f|AH#iMqG9qnpg>w9 ze!k$8vTTdJwcfU%|glz&sJDVV7fitEp z-gHVtM#ccy_+6GmxLxfXTZM%zlZhdQ&`S;0nTHCGj`sQ20dlvtw_C59!)l;1$1(}I zb}a!~z^-6vuxrihlFyu%F#Z!|Hv0>0b8ucn#*DmQpU%g9W_}$^86h&UE**3zvaOP6j! z^8;b{bRyB3*Vb&9z)c2;x-RkwVp36(1fj zNr;mcpziG1v#$Y}#ni*(UE@&q9Asy*7EyfcX$Rc^BCaF3V#Wf=r%2)Q6M?-CycGri za%gC%@~;n*NCUmZw5$PC6VlVw4IV?%-yRGNF8-l=_d>17LUIH`gJbXCm!`q3(2CGO z)*bj+Fy81U%;cPy=f=)-JUKay${`2>lHtJE@4n%xb?TFH~No{f{or9VUtzGSNU8XHIlkV;IO6T z0H%A(&Ye4xOdn-++A#eL@`(L%fNlg2sf5C|Pfq+noE0*arR;o`V$o&HEBJ~0Ef$O6 zS3IJFZCvv{$5qCnkg2-Iw5-KjzkLeg6azTAQdV{sAm3|X*=kfRd_F;?d0j#*ZENos zgCvIU+rPgi-BLq7QtPGQggPto6vRX3K*`LDf+}W?*(TbG-%iw~nkJu{vnniLN}&*T z(aj(Q-(f<9t!@e=V#vF;bwGCbnCHuenZ3D&qTcJrmqgI;#2wcqcW2pOS8(gFz#j5B z25>BLpshSS9wn?B<4!U!$dAxk(aNJb7ZD>O{071jia3;#9Ux;|+}yRbDJBL8d8D}( zY8i-3CK&|e%?5gQaO_IGI2&Ls(Ve$Wd_2JPF9o`1u{%PK<(fXd8W`Ik_sAjNZ_no8 zPO|*dRF$94!YvAcVybU#nZ~c=r7vSw{VL0$LByZ&n}^Bg5+X1(_B{$;*tKupEesr3 zjj$$knwtzITCQtYx4}NF`mU5<;fn%FyPa~soyyJ2o3Ub&jt=iN_72PmWM(LMg$XEh zwjgu_%W%aYh^rl>8U&Jv1=kL?`>5@cnKgEe58b;OA7#^<5p4xDqC||u$92<3k7eZUsN`qHue~2PMjQ;*f*w5hh_BohrUW=i&sUOlL z%!ZRec}Y^CaEUb^T&(dbS9^3WavB6e`uC{{SqD?p7LvJ zHz85f)|vY|AOo_CH}e*n6BUChxf4|; zDd?l)J3R0jD?EU-dl2I$av1%T3ChSH>DQn*Te)(j*N3B=1AYGECQuX#XxcCNxN?6W z^_|)z*h#cwYtzirAaz?_&%qt$itkB)C|Q%Jr`DJE^G0vMxL*nw8@P|$l|_up)~#Dl zq4?4zw_{@yz<2*j0VRhps}@kS@x>KHeKo_RcW&Hx3}G*omMx|+M^s>vaej`UH zYWoKUq_53qT(nRUH*VS_rEPf~dAkmvn>)$b2>kC-bRhJe;Z+;Iq#c)&j z*B?#*$|7A{xbwr~<4H#MZpE74m@Ikt%UdyX*Dr7Hm901-W^|XuKJ{kd5P)zEv9D*( z692)zbV?RTut*?<6rb?)>E=j9PhFJ2^4wIX=KOaV*4iOM*i5E5E?ZE#vhAu9q5;hk z)B*+G;cjMXoGg{Hbg}XXdA->yw60hhW20nJ_W+v&Y`<{I1(iQyf%p2qf3Lc&5h{J; zs|C=x9;7XUC}rRD+RWkp5&Rk3WR8F(n0d4OuBf+d*b+ zUIZ^gnhB!67K{z1U6<*^Z42b-lTL9@7|0l#qHP?w_9iaaF=xxzrw+QYvb(m^vnF z7mzylqIE&7E=-A2TSa6tH@`v$Zfp1I=Fy3S%v$?Akile|VUJXk90aNTfPC=Jh8Qn7 zubzS>Th4W$PD7!L=@*t@-gBdMgjNip-mAh8)om~kQJ`>S@l=Fbm5_xFbgeC+4!DM9-Yxv|hItV0SY zIRlohY~^7c!U(xB?_boeT&z|i%Xlq>xjpciX1e^cDx0#kz z7;)1!=QW#m(>ATtYv@b-gIdM+}+QwXN*M`wft-P7C;t zeCxjPU`k;wM81{M()x!E9qRx2Q;xrQYQwxjK&WR=pOPY38Y)qTa-O-jXo}LW56A1u zoBq3=OmJ)Cz92cH@ouWVM2FA=F^JtZi*#8i49=+|f45d5c8^1^B zt>;8{-AN$m4a(q}I=<(x-pzVbf5%5Y1HwTgPkIhp%fIAgO+%Q>n*#NvY;vHQvFTYEwfBm*am!icY$AC{!kkq;gkI&L$qDD9so<- z9!xDtih7b0BBnEr7gMHvz$#IeBJuzlsgFP(KxeGul9~XBl&Uh(4r;=Hf?lT1U`0eC z_Da8B3&X{0GOrL?_fy~njx$xA`p`Y8a)R90B7b-dyjDZhvKpR)MmSHS>V)mu0eLz} zFFpWWM6IDoIu-!fLVQ38UJ#e0oj<4|!jh0{shNZ@hN8z(AwVs6Xt2wGWIDn%!ks7Q zndulAU2`y(o38qCZ?`MM_Q497<0e|X)H4C!s6yVTiPshcz!Xvg1pFWebQy!%hdD~X zzUJcLF$AB58pm2x1QsnwAUIhZzqy24Pi%!j`f_N^huB|e9pH^hf zO5LZZg_}W2x4JJOdzSY-JhPF2ONu@Ad!syQTC~Yhe=-cY+Hc6xd&;O1S`t9 zKsD5-^CbM5<$?wnWjOSEUDhq4Z75^=Mwn>FYcw)x1kcf@;hjG}0adG{vQnD_(m(+v zdVfXg0hk!&`{V!?C*pGoXuSgmgptl1us*zYz}ymf1HoQDdsDFGI$x^^)*!_XemKqp z{LMT^3;gCQ$P_4H$9YNH0i=ttD!aB=LPB7edCM1gjN!T+eF`0s*w|Pbz}SWB58r|J1UceRig|$TjtL8tSyN1QyeO@A;v>5lcvIRA0 zpik(vO!frcP}kP3LnloJTM02t$~G?4D-V-_qRe8)I^I;x@fu8e=+T#o2df90d37!$ z1syGFs5PpOiEMLSfLb8}J>u_XFmtp!UHT{~q%0vAFHdLzh5R7JCD~{UP&+d3>yv5eVj5_FkTeFqZ>_M9;kAJ# zToS4ku`ZgzxGB#BEdVdzNaD%QXaKwzK!4;#J~`@E|4%JhMnoE-Y*3mHcKyGc9N@Qq zFAVb=Cb*UBnE@tfMFUX40M_*WgXGe?D2KJ9bJ~<9JJhzPU5t~bigM-0UVV z4WzM8h~WvZv>bRoYkVKR9}uSEpAU62KEt{)39t>i@D&xN z#2Sn1vf0b)A#5u#fZ#;L(0n4=+?)5)3|VAin>iN~BE$;VO)y>}0T2s$6-c2V#kU5q8o7?CM;!htLMKHAseak={j{wdHH@4|} z*}sFBgJb2|wLAG0++HEs008T#I!~Ti=%9{HE|CfM?p^8=O^UW~rSG9)pd!`X@yFnGmh-=1- z8bfp6W$IpIL+yj_4yL_;Q3i9R>WH`KL5N(weS@5MVcGf(}-x%#tR6D8)0KT+1!wgNJNfdrl-5Jy+@yh`t2np+qP`p3{p=O&j2{M)25LB(cg_+k0wvG-~oU) zJ&jOt1HkO*D<(15tbj$v(Ly>f zpP$1&t0V+2G31NPBj5I^>jLV?AO#H#4K2``!VHx{;pAPoFzLaAbx67JUQXutT0qKw zTEWc!%gMUfJtwZPJ>C>=M z1PY`;V=XOR)y~tOF=63?i>tMIxERe+`}*`Oah5%s1{mWNf^8@|P51v7otU5IivZY3 z)P_oPj(6oP9+eRt2sh<}QKkPfd%DMWS2|dKXSXp9Ayo;y+W`1jN#f#Bc54(!(zqz6 z0g%~|#s!ZIkjKL~YhW=|p!(8|K=Xjwa&5(cj!5E;FtQntKZGU#f*kxjIxvX50!4)$ z#oT1w9i6*ICn#dQhZY)XfQSu*RG?Owl9R9KBRm(34(shhhMhy5+Th2IxeX84QX8D) zUG(`V%kipaHL*|OI!F8qYA`9IV3;XDH+o~pU-LO;mK39K{LTB(V#%kaaA;l{xCu0TG6ZA#^SSXg1WT$NS0v z)9Gx}!RKwTV(Oy%D%EVa2A);i1Dz#C=L`U2%WS|o6dSKE_ln7M3Q6^EtWa`@S5-*x z!Qq}TvJak}z2YTg5U33ksRO&1QpZWylURHIOaJ?O#d>ne(DH2r-k48$ckoNS-aPR= zI`!$6nLa}<2;>UNZDf0~D1ove;ok9T16_cShjff8!y?;D|Fypx;MIECFIrs^J^Gs7 zrCXl=y8+IS?Iq|m@qcjjgD76Xu}HB7&{|-?S;IG-u~>z72!tz2ZNr8Q|LT8ZIYfno zU_D}3GmxBHj*<-)WPmRv6E)b3+@ zUKKZ0$o|a6IP3AMe&9jZMPj0r0iKsVA_HlyraP@bTtZ^(9UD{jNp6-iAL-YybpVQL z1nU?0`GUU6Hl%&)?|*|N0*P!q_Y52=eMtA&9Uv8?y5*1lFj0R4w3`4iyQJv2o-G^0 zF^yy90}gb`bdXH^hC5db4G-Iqw1XXlIcG)|V>}*rj5D^vEKC3u9SpF6R3z5xNO6UN z&zt5r)2hSi1ShNxBu2oC4I%#ihtrs0TsTY$?`HnfX?!p(FOC9~oW^iWrbaVQvJUq( zrGSP)gCLrP)bR!e4=WTaCI_Clw{PIYs7^9ih0iBw)?WqPf{$1A?Kz}insQ~|;SL}) zB0B#GpH7%QPCh{zp}GM_!GZN2@GAAZ&(RAeyhvUJIIcWr%|iA%&VGh{HF~nMm+yFG z;*{rJYL1TozrbqFwdrUupT{NL0RQAVhrkU71yot=0)N=dHW zI{E(&Cr1UAy(^8f6~&@kY^ZPMPAhwZvu2M zx`6#rG?38+IW?Hd3SjX~)mzMyGpJ1$7s=~_o{l!wzkO>&o=cyhev(?z2TaA|MR|1L z2VA$4xzzq2y{fMv1#uA2@y1udLzah@UOnH*Fd`!&tP(wHPEbn>cWZ=GBy7D$Dm0sG zJ#|MsJre<2a`$uMe9Q^ECC|BL(H=8mgM;sCsS=9bv zwhRD!Wi4LBwmJ2m-K)P*eehrTo@uznEUDYPb*m`2DN?*1Fny+dy`<8}*CJpUSe1BH z4?G07#71{*@lG+z+r4z_1s!zfv76&zcx(hpknhi9V+tdqnT^1N(Tt87Pyg{2JynaW3c8aWVibd2;fp`UIm2)w(+P?OUzZ9 z2#ezam;iDN8EUZOI(i@V?LsBV7+nYpA+_7cQ?RZXajwHm3x+;QAxPFWVOx;G;a{Hv zsVq|VQr)nTO-zUo1cnWv-GR(KNYts&rw?t$4c^OgS+LE7oD23HsqDKOobL^!pqd<4 zYa&jnY|o}`Xm|aWtqnDw+B|6O#E-CnOKfB-i~naupQx*F=OVJvl7ba?9hZeN?>{Q~ z4Mk(@Q&LVL1v0!-A|_qqA<8*EROwGGn17e^Kk(@i-a?-aGQ-2HMefZ63>@u#l-g75 z*LWzx(1PHU_=b~HE*$Mln;r#AkO`2G9Qp+UN?r-DiG#mh!D$e@U2>eykF3H2j@f}EJN;qBRA4g7CvVvjM)Re{!X=Zb#kt& zlmWt^q{&N~;59vujPyIDK{n3Wle*|SHg5tR=;U1s{JMH|Puzr%+u#2(LUa4}m+512 z;hLxoc6MEw1x}ZiY>_M&J8UH-DT&1AQe}+f1W~Xh%ev7q8&U3hptiJB143}HaA~?5 zB5l$2!GVFY+(u!6rDG*uB9*s}^nKO_@AJIyYA|qCwu1M1|GrDp#Ed{dgYN)KTduzx z9J~)O($X(N(eq940dhRSVOsi)M_q1|ibRMp-aotoI8n9~u-Vc{p#dgxu?*-$1)cVA zo2Qq-pwS*j|4=DOpM_VTLxYPEgH8(F-QD4qS(xzp)Q0g2fJc3WW8*^^*Te7b+tycX-MslgMa6Zg6%F-w z@7^t|hcaTd{t@KpvU;e^mg`|beqTl(*;}`lUB4{PH*40Vo-Y`Xq%|xcVLe|^`mV`8 z!dUFBi!btp%6sDkk-hb49>E*(-opc(_ST#;7G9C}hB9Ms?fv76Eshva{O;1#)y>LK z+&a?#c>mLJU*4ADGv+E|Kgax66qrkxK0KhF{^`@F{eAK0R*j@Hf%+)s%KkLt&nX3MBq_6zz{BP3`n%W!u zF8oSqel$LQ<4bS$;g5Ikgf9xrUU0f78Zo(2M5H553TV@q+mOf_vO5^7ZfdRuXTy5A z8}2!Kc0W3tBH;IHZx(A@&CHQ)yl=SKK4kTW_YLd;e;t7d?&+~=FFy0d%5~qgUv^K;_fmIof>dt9SFy!&c+jZ(FMG z#PW@eR-COjKfhnAY;0KL_hCo57iNL8a^$@;ilautsZuZoO*oNyP=|Q%2phzgk?537Q~@+v@v}?oPJwCQ$mq)(ne!N?@Hqs>iF37^j}kN`B@ykiwfxUQ z{w-n{jYp8Rh)(B{@B6>M5LQgCTG z^Z4mWHArtH;MXMV+=ONm$^3&aSEU{B>@%uWX}5>lQORpS2YLcd`Y*(!p-UXJ30+5IMFu9P$6V@Glv(Z^x0@FlWQ17W`{DT!_So_s_hMQ|dXsf(vR62_8W=?vX7xLW2>tsuJ8{Yp zr&5y9?FdtFPZCZ9Vx)_eN4{<%ucY(CCr-E(oyDEIdUq_0kakF?3#F_sz$0Ha9HRqc z+fWnqb&4($*TFPiD zSX~k~p5(gYE1nF}DB$z;u~;a9XY9S;D>)SfzHKtu8!C=a{~0O?HHYx0j$~_~e#mE< ze|ATOI$EZzLcbpP`#_E|h&2et#~%;=;1cRz4X$HXEkcbRU>5_N%SqqUeBV}&jx_%6 zE2zx<0+ofjQIG=q6&$1Az^Oy-2RNTAMr>;DT!+dPG&Fw4w-*as<1XP%=Sg6VG7TnI zE%Ap^hnWz_5)wolk1uit^7TA&U~~@P>&ong)n^AQHL}xd$w~n~7PRI|@)?JFb|a6I zl@=j1H7@ET`}?vpvzFe0bg;X-E-f3aq41$Y2=KD&5bjK{`!e9BJO~AzsOw#rJ@&3~ z|2SAs$(|)vtDFs2bz^^jf4Z4>k4!hZU$wwXtIf^L58|Z2btyo^Y%+pE)iqHW`FecL z{P{M>ibdPCv}BQ0=1U$p;|>O8a6i1=T{ak zC*isrvMd=L?$A*RoH)pY88ih=uCQsQXGXJ_^dC7+fR4K$l#Ah9Z89ELTP)}w(dw1m z;E*@)Mq?LDQxl({uGgXiHvRVMJt(Isus+wK1crfv?CgfEF_T(|t8g6I_0(XcJlb=Q zK7JlW&u(J0`DhN1>5Pm!Aq52mq<61cy!dfpRGfvgQSEr{9eEToE+snf^}qf56#i8y zC$q-s{0{tyaaxgKtuCeM)w!Oo=q!z*;UIm5n{lCYodX&#$O)Wen3jrmgH=v1w3@2x zQr5!iB)`t$VJ1#M36o8N&d(qdgs@+O;{hs2Co*NIFrB;8*~pa0qum)qUNHzhNtki+ zgW;g2uzFf<|2Z-m)45;lK9XWS#xlXbfybPJ zHu%V^C$sMD7>AAxdU+TtoBf;Evv?yS=NPUXJba}4VJqB5YwYgmw41L!Oci1}LfPjp zTqvpzH{K^uEiTgD)AYD)n1t?GtJ~e&8EzoZAKE9Dq<1D?pDjvln?7|<6Jbo`o;SU_JO2maP z8X8Q9QKq1ZS>@yt0sh3M8sG}LcAXpSm6cnB9{zuaQ~r;CzewBoq~*rPjE`J-F%36m O)VFADPTgp6?0*29tEx2s literal 0 HcmV?d00001 diff --git a/docs/rsc/backward_euler.py b/docs/rsc/backward_euler.py new file mode 100644 index 00000000..04f32fff --- /dev/null +++ b/docs/rsc/backward_euler.py @@ -0,0 +1,120 @@ +import numpy as np +import matplotlib.pyplot as plt + + +START_Y = 0.0 +TARGET_Y = 1.0 +C_0 = 0.0 +C_1 = 0.075 +OMEGA = 2. * np.pi +DT_INC = 0.1 +DDRDDT_TOL = 1e-6 + + +def relax_constant(i, n): + return C_0 / n + + +def relax_tanh(i, n): + x = (i + 1) / n + return C_1 * (1 / n) * np.tanh(x) + + +def relax_bell(i, n): + x = (i + 1) / n + if x > 0.5: + x = 1. - x + return C_1 * (1 / n) * np.tanh(x) + + +def relax_all(i, n): + x = (i + 1) / n + return relax_constant(i, n) + relax_tanh(i, n) + + +def relax(y0, y1, i, n, backend=relax_all): + f = backend(i, n) + return (1. - f) * y0 + f * y1 + + +def oraculus(iters, backend=relax_all): + x = np.arange(0, iters + 1) + y = [START_Y, ] + f = [0.0, ] + for i in range(iters - 1): + y.append(relax(y[-1], TARGET_Y, i, iters, backend=backend)) + f.append(backend(i, iters)) + y.append(TARGET_Y) + f.append(1.0) + return x, np.asarray(y), np.asarray(f) + + +def oraculus_plot(N=(10, 100, 1000)): + fig, (ax1, ax2) = plt.subplots(2, 1) + for n, c in zip(N, ('k', 'r', 'b')): + x, y, f = oraculus(n) + ax1.plot(x / n, y, color=c, + label=f'M = {n}, C_0 = {C_0}, C_1 = {C_1}') + ax2.plot(x[1:-1] / n, 1 - f[1:-1], color=c, + label=f'M = {n}, C_0 = {C_0}, C_1 = {C_1}') + + ax1.set_ylabel(r'$\mathrm{d} r / \mathrm{d} t$') + ax1.set_xlim(0.0, 1.0) + ax1.set_ylim(0.0, 1.0) + ax2.set_xlabel(r'$m / M$') + ax2.set_ylabel('$1 - f$') + ax2.set_xlim(0.0, 1.0) + ax1.grid() + ax2.grid() + ax1.legend(loc='best') + plt.show() + + +def ode2(iters, r0=1, backend=relax_all): + dt_0 = dt = 2. / OMEGA * iters + while True: + r = r0 + ddrddt = -OMEGA**2 * r + sol = -OMEGA**2 * r / (1. + 0.5 * OMEGA**2 * dt**2) + for i in range(iters): + r = r0 + 0.5 * dt**2 * ddrddt + ddrddt_new = -OMEGA**2 * r + if i < iters - 1: + ddrddt = relax(ddrddt, ddrddt_new, i, iters, backend=backend) + else: + ddrddt = ddrddt_new + if np.abs(ddrddt - sol) < DDRDDT_TOL: + break + if ddrddt > 0 or -0.5 * dt**2 * ddrddt > 2. * r0: + return dt - DT_INC * dt_0 + dt += DT_INC * dt_0 + return dt + + +def ode2_plot(N=range(5, 101, 2)): + global C_0, C_1 + c0, c1 = C_0, C_1 + dts = [] + for n in N: + C_0 = max(np.polyval([-0.01, 0.1], [n])[0], 0) + if n >= 10: + C_1 = max(1 / np.polyval([0.051, 0, 10.0], [n])[0], 0) + else: + C_1 = 0.07 + dt = ode2(n) + dts.append(dt) + dts = np.asarray(dts) * OMEGA / 2 / N + plt.plot(N, dts, 'k-') + plt.plot([N[0], N[-1]], [1.0, 1.0], 'k--') + plt.xlabel(r'$M$') + plt.ylabel(r'$\frac{\Delta t \omega}{2 N}$') + plt.grid() + # for x, y, c0p, c1p in zip(N, dts, c0s, c1s): + # plt.text(x, y, f'{c0p:.3f},{c1p:.3f}') + plt.show() + C_0, C_1 = c0, c1 + + +if __name__ == '__main__': + # oraculus_plot() + ode2_plot() diff --git a/docs/rsc/midpoint.py b/docs/rsc/midpoint.py new file mode 100644 index 00000000..e0bcdeba --- /dev/null +++ b/docs/rsc/midpoint.py @@ -0,0 +1,107 @@ +import numpy as np +import matplotlib.pyplot as plt + + +START_Y = 0.0 +TARGET_Y = 1.0 +C_0 = 0.0 +C_1 = 0.075 +OMEGA = 2. * np.pi +DT_INC = 0.1 +DDRDDT_TOL = 1e-3 + + +def relax_constant(i, n): + return C_0 / n + + +def relax_tanh(i, n): + x = (i + 1) / n + return C_1 * (1 / n) * np.tanh(x) + + +def relax_bell(i, n): + x = (i + 1) / n + if x > 0.5: + x = 1. - x + return C_1 * (1 / n) * np.tanh(x) + + +def relax_all(i, n): + x = (i + 1) / n + return relax_constant(i, n) + relax_tanh(i, n) + + +def relax(y0, y1, i, n, backend=relax_all): + f = backend(i, n) + return (1. - f) * y0 + f * y1 + + +def ode2(iters, r0=1, backend=relax_all): + dt_0 = dt = 2. / OMEGA * iters + while True: + r = r0 + ddrddt_0 = ddrddt = -OMEGA**2 * r0 + sol = -OMEGA**2 * (1. - 0.25 * OMEGA**2 * dt**2) * r0 / (1. + 0.25 * OMEGA**2 * dt**2) + for i in range(iters): + r = r0 + 0.25 * dt**2 * (ddrddt_0 + ddrddt) + ddrddt_new = -OMEGA**2 * r + if i < iters - 1: + ddrddt = relax(ddrddt, ddrddt_new, i, iters, backend=backend) + else: + ddrddt = ddrddt_new + if np.abs(ddrddt - sol) > DDRDDT_TOL: + return dt - DT_INC * dt_0 + dt += DT_INC * dt_0 + return dt + + +def ode2_plot(N=range(2, 50, 1)): + global C_0, C_1 + c0, c1 = C_0, C_1 + dts, c0s, c1s = [], [], [] + for n in N: + print(n) + best_dt, best_c0, best_c1 = 0.0, 0.0, 0.0 + # for C_0 in np.arange(0, 0.1, 0.001): + # for C_1 in np.arange(0.01, 0.5, 0.01): + # dt = ode2(n) + # if dt > best_dt: + # best_dt = dt + # best_c0 = C_0 + # best_c1 = C_1 + # dts.append(best_dt) + # c0s.append(best_c0) + # c1s.append(best_c1) + if n >= 14: + C_0 = 0.01 + C_1 = 0.02 + else: + C_0 = max(np.polyval([-0.011, 0.154], [n])[0], 0) + C_1 = 0.08 + dt = ode2(n) + dts.append(dt) + c0s.append(C_0) + c1s.append(C_1) + dts = np.asarray(dts) * OMEGA / 2 / N + plt.plot(N, dts, 'k-') + plt.plot([N[0], N[-1]], [1.0, 1.0], 'k--') + plt.xlabel(r'$M$') + plt.ylabel(r'$\frac{\Delta t \omega}{2 N}$') + plt.grid() + plt.show() + + plt.plot(N, c0s, 'k-') + plt.grid() + plt.show() + + plt.plot(N, c1s, 'k-') + plt.grid() + plt.show() + + C_0, C_1 = c0, c1 + + +if __name__ == '__main__': + # oraculus_plot() + ode2_plot() diff --git a/docs/tschemes.rst b/docs/tschemes.rst new file mode 100644 index 00000000..cc48abe4 --- /dev/null +++ b/docs/tschemes.rst @@ -0,0 +1,314 @@ +Time Schemes +============ +.. _tschemes: + +MoorDyn 2 is deployed with several time schemes, with different features, +strengths and weaknesses. + +They can be deivided into 2 main categories: Explicit and implicit ones. + +Explicit: +--------- + +The explicit time schemes are the ones formulated in a way that the derivatives +can be evaluated with the information already available, in contrast to the +implicit ones in which the derivative is required to evaluate the derivative +itself, as it is discussed below. + +In general the explicit time schemes are simpler. Unfortunately that simplicity +is usually coming at the cost of a more unstable behavior. + +The available explicit schemes are: + +Euler +^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + euler tscheme 1st order Euler scheme + +The simplest scheme, in which the state variables :math:`r` are updated +according to the expression: + +.. math:: + r(t_{n+1}) = r(t_n) + \Delta t \frac{\mathrm{d} r}{\mathrm{d} t}(t_n) + +It has a 1st order convergence, with a relatively good stability region. + +Local-time-step Euler +^^^^^^^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + leuler tscheme 1st order Euler scheme (with local time step) + +It is a variation of the conventional explicit Euler scheme, in which the system +subentities derivatives are not computed each time step, but the operation can +be delayed depending on the CFL factor. + +This time scheme can be of use when several relatively less relevant entities +are enforcing the usage of very small time steps (see +:ref:`Troubleshooting `) + +Heun +^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + heun tscheme 1st order Heun scheme + +A slight variation of the Euler method, which increases the order applying a +predictor-corrector. The performance can be expected to be rather similar to +the Euler scheme. + +Runge-Kutta +^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + rk2 tscheme 2nd order Runge-Kutta + +Runge-Kutta schemes are probably the most popular explicit schemes. Please, +check the +`Wikipedia entry `_. + +The Runge-Kutta methods are increasing the convergence order and the stability +region. However, to this end they are including more time derivatives +computation within each time step. Anyway, in general the time step enlargement +compensates the extra derivatives. + +In MoorDyn the 2nd, 3rd and 4th order variants are available. Just replace the +the integer suffix of the option, i.e. rk\ *N* with *N* 2, 3 or 4. + +Adams-Bashforth +^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + ab2 tscheme 2nd order Adams-Bashforth + +The Adams-Bashforth methods are the explicit counterpart of the Runge-Kutta one, +in the sense that they try to increase the convergence order without adding +more time derivatives within each time step. Please check the +`Wikipedia entry `_. + +Unfortunately, that comes at the cost of reduced stability regions, i.e. the +time step shall be decreased to compensate this. + +In MoorDyn the 2nd, 3rd, 4th and 5th order Adams-Bashforth methods are +available. Just replace the the integer suffix of the option, i.e. ab\ *N* with +*N* 2, 3, 4 or 5. + +Local-time-step Adams-Bashforth +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + lab2 tscheme 2nd order Adams-Bashforth (with local time step) + +Similarly to the Euler scheme, the Adams-Bashforth schemes have a variant with +local-time-steps, which can be of use when there are entities relatively less +important which are enforcing small time steps. + +Implicit: +--------- + +The implicit time schemes are the ones formulated in a way that the derivatives +depends on theirselves. The backward Euler method is very illustrative. In such +scheme the state variables :math:`r` are updated according to the expression: + +.. math:: + r(t_{n+1}) = r(t_n) + \Delta t \frac{\mathrm{d} r}{\mathrm{d} t}(t_{n+1}) + +so to evaluate the derivative on :math:`t_{n+1}` we need to know +:math:`r(t_{n+1})`, which depends on the derivative itself. + +On MoorDyn this problem is addressed by means of a semi-implicit scheme, i.e. +an iterative process in which the time derivatives are progressively improved. + +The implicit time schemes enjoy a way better stability. Even more, the Newmark +scheme is unconditionally stable. Then, what is the catch? Well, they can turn +unstable on the internal iterative process. The half good news is that, by +construstion, relaxation can be applied on the internal iterative process. + +Hereby an arbitrarily large time step can be considered, provided that a +sufficiently large number of substeps are configured. See +:ref:`the relaxation process ` below. + +Semi-implicit relaxation +------------------------ +.. _relaxation: + +All the implicit time schemes are solved as semi-implicit iterative process with +relaxation. Relaxation is the process of mixing the last acceleration prediction +with the previous one, + +.. math:: + \frac{\mathrm{d} r}{\mathrm{d} t}(t, m + 1) = + (1 - f) * \frac{\mathrm{d} r}{\mathrm{d} t}(t, m) + + f * \frac{\mathrm{d} r}{\mathrm{d} t}(t, \frac{\mathrm{d} r}{\mathrm{d} t}(t, m)) + +In the expression above, :math:`1 - f` is the so-called relaxation factor. In +MoorDyn, for the sake of consistency, a relaxation factor :math:`1 - f > 0` is +considered for all the internal steps except the last one, in which no +relaxation is considered. + +Hereby, if the iterative process has not reached a +sufficiently close derivative by the last step, the simulation will become +unstable. +However, if the relaxation factor is not small enough, the internal process is +becoming unstable on its own. +So the questionmark is, what is the optimal relaxation factor? + +Simple oraculus example +^^^^^^^^^^^^^^^^^^^^^^^ + +There is probably not an answer for the question above. +However we can investigate a bit about +different alternatives. To illustrate the process, we start with a simple +example in which we have an oraculus which is always providing us with the exact +solution (so no relaxation would be required at all). We are not interested on +the results, which are obviously correct as long as the last step is never +considering relaxation, but on the way the solution is approximating to the +final answer. + +One possible relaxation factor would be a constant one: + +.. math:: + f = C_0 * (1 / M) + +with :math:`M` the number of internal iterations and :math:`C_0` an arbitrary +constant. If :math:`C_0` is too small (0.5 for instance), the acceleration would +never get sufficiently close to the final one, so a big jump would be required +on the last internal iteration: + +.. figure:: relaxation_001.png + :alt: Constant small relaxation factor + +Relatively large relaxation factors would be required to avoid that, + +.. figure:: relaxation_002.png + :alt: Constant large relaxation factor + +making the algorithm prone to stability issues. Optimally we want something that +give us small relaxation factors at the beginning, where the solution is more +prone to get unstable, growing afterwards to get as close as possible to the +final solution. + +To this end we can draft a different relaxation factor: + +.. math:: + f = C_1 * \mathrm{tanh}(m / M) + +with :math:`C_1` another arbitrary constant. Again, if :math:`C_1` is too small +jumps at the end will be observed: + +.. figure:: relaxation_003.png + :alt: tanh small relaxation factor + +so a relatively large one shall be used: + +.. figure:: relaxation_004.png + :alt: tanh large relaxation factor + +Effectively, the new relaxation factor start with larger relaxations, while at +some point the relaxation becomes smaller than the one obtained by the +constant approach. + +However, the relaxations at the beginning might be too large, rendering +the iterative process slugish. Maybe a combination of both algorithms would +outperform each of them separately: + +.. math:: + f = C_0 * (1 / M) + C_1 * \mathrm{tanh}(m / M) + +Spring example +^^^^^^^^^^^^^^ + +To test that, let's move to a bit more complex example. Let's consider the +following differential equation: + +.. math:: + \frac{\mathrm{d}^2 r}{\mathrm{d} t^2}(t) = -\omega^2 r(t) + +With the initial condition :math:`r(t=0) = r_0`, +:math:`\mathrm{d}r / \mathrm{d}t (t=0) = 0`. The initial value problem has then +the following solution: + +.. math:: + r(t) = r_0 \mathrm{cos}(\omega t) + +It should be noticed that this differential problem is just a simplification +of the spring problem that has to be faced internally by MoorDyn to solve the +lines axial stiffness (see :ref:`Troubleshooting `). + +For simplicity let's consider :math:`\omega = 2 \pi`, so the solution has a +period :math:`T = 1`. +It shall be noticed that the time step on MoorDyn is enforced by the line +segments natural period (as it is documented on the +:ref:`Troubleshooting section `), which is in general lower +than the physical scales of the line itself that the user is interested on. +We are hereby interested on knowing which set of constants is more proficient +keeping the stability, i.e. which one can iterate a larger time step without +turning unstable. + +To this end, let's consider just the first step of a backward Euler's iterator, +with a time step :math:`\Delta t`: + +.. math:: + r(\Delta t) = r_0 + + \frac{1}{2} \Delta t^2 \frac{\mathrm{d}^2 r}{\mathrm{d} t^2}(\Delta t) + +with + +.. math:: + \frac{\mathrm{d}^2 r}{\mathrm{d} t^2}(\Delta t) = -\omega^2 r(\Delta t) + +Thus, combining both equations and rearraging the terms we can get that the +position at the end of the first time step will be + +.. math:: + r(\Delta t) = \frac{r_0}{1 + \frac{1}{2} (\omega \Delta t)^2} + +and therefore :math:`r(\Delta t) < r_0`, i.e. it is unconditionally stable, +provided that we can find an algorithm that is able to converge. After a +numerical investigation we can determine that the optimal constants are: + +.. math:: + C_0 = \left\lbrace \substack{ + 0.1 - 0.01 * M \, \, \mathrm{if} \, \, M < 10 \\ + 0.07 \, \, \mathrm{if} \, \, M \be 10 + } \right. + +.. math:: + C_1 = \left\lbrace \substack{ + 0 \, \, \mathrm{if} \, \, M < 10 \\ + \frac{1}{10.0 + 0.051 * M^2} \, \, \mathrm{if} \, \, M \be 10 + } \right. + +i.e. the :math:`\mathrm{tanh}` relaxation factor is aidded by a constant one +for a small number of iterations. +With such a set of constants the resulting speedup can be plotted: + +.. figure:: relaxation_005.png + :alt: Backward's Euler speedup + +As expected, the larger the number of iterations, the better the speedup. diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index b9b43f5b..5e41099a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -328,6 +328,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) } // boost drag coefficients to speed static equilibrium convergence + // This is actually useless on the current implementation for (auto obj : LineList) obj->scaleDrag(ICDfac); for (auto obj : PointList) @@ -361,7 +362,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) t_integrator.AddPoint(obj); for (auto obj : LineList) t_integrator.AddLine(obj); - t_integrator.SetCFL(cfl); + t_integrator.SetCFL((std::min)(cfl, 1.0)); t_integrator.Init(); while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt // Integrate one ICD timestep (ICdt) diff --git a/source/Time.cpp b/source/Time.cpp index 762a984f..9076467c 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -497,12 +497,30 @@ ABScheme::Step(real& dt) TimeSchemeBase::Step(dt); } +template +ImplicitSchemeBase::ImplicitSchemeBase(moordyn::Log* log, + WavesRef waves, + unsigned int iters) + : TimeSchemeBase(log, waves) + , _iters(iters) + , _c0(0.5) + , _c1(0.0) +{ +} + +template +real +ImplicitSchemeBase::Relax(const unsigned int& iter) +{ + const real x = (iter + 1) / _iters; + return c0() / _iters + c1() * tanh(x); +} + ImplicitEulerScheme::ImplicitEulerScheme(moordyn::Log* log, moordyn::WavesRef waves, unsigned int iters, real dt_factor) - : TimeSchemeBase(log, waves) - , _iters(iters) + : ImplicitSchemeBase(log, waves, iters) , _dt_factor(dt_factor) { stringstream s; @@ -514,10 +532,18 @@ void ImplicitEulerScheme::Step(real& dt) { t += _dt_factor * dt; + rd[1] = rd[0]; // We use rd[1] just as a tmp storage to compute relaxation for (unsigned int i = 0; i < _iters; i++) { r[1] = r[0] + rd[0] * (_dt_factor * dt); Update(_dt_factor * dt, 1); CalcStateDeriv(0); + + if (i < _iters - 1) { + // We cannot relax on the last step + const real relax = Relax(i); + rd[0].Mix(rd[1], relax); + rd[1] = rd[0]; + } } // Apply @@ -630,7 +656,7 @@ create_time_scheme(const std::string& name, } else if (str::startswith(str::lower(name), "beuler")) { try { unsigned int iters = std::stoi(name.substr(6)); - out = new ImplicitEulerScheme(log, waves, iters, 1.0); + out = new BackwardEulerScheme(log, waves, iters); } catch (std::invalid_argument) { stringstream s; s << "Invalid Backward Euler name format '" << name << "'"; @@ -639,7 +665,7 @@ create_time_scheme(const std::string& name, } else if (str::startswith(str::lower(name), "midpoint")) { try { unsigned int iters = std::stoi(name.substr(8)); - out = new ImplicitEulerScheme(log, waves, iters, 0.5); + out = new MidpointScheme(log, waves, iters); } catch (std::invalid_argument) { stringstream s; s << "Invalid Midpoint name format '" << name << "'"; diff --git a/source/Time.hpp b/source/Time.hpp index b12abd5e..aa3c22a2 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -838,7 +838,7 @@ class EulerScheme : public TimeSchemeBase<1, 1> virtual void Step(real& dt); }; -/** @class TimeSchemeBase Time.hpp +/** @class LocalTimeSchemeBase Time.hpp * @brief A generic abstract integration scheme * * This class can be later overloaded to implement a plethora of time schemes @@ -1134,6 +1134,74 @@ class ABScheme : public LocalTimeSchemeBase<1, 5> } }; +/** @class ImplicitSchemeBase Time.hpp + * @brief A generic abstract implicit scheme + * + * This class can be later overloaded to implement a plethora of time schemes + */ +template +class ImplicitSchemeBase : public TimeSchemeBase +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + * @param dt_factor The inner evaluation point factor. 0.5 for the midpoint + * method, 1.0 for the backward Euler method + */ + ImplicitSchemeBase(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10); + + /// @brief Destructor + virtual ~ImplicitSchemeBase() {} + + protected: + /** @brief Get the number of subiterations + * @return The number of iterations + */ + inline unsigned int iters() const { return _iters; } + + /** @brief Get the constant relaxation part coefficient + * @return The constant relaxation part coefficient + */ + inline real c0() const { return _c0; } + + /** @brief Set the constant relaxation part coefficient + * @param c The constant relaxation part coefficient + */ + inline void c0(const real c) { _c0 = c; } + + /** @brief Get the tanh relaxation part coefficient + * @return The tanh relaxation part coefficient + */ + inline real c1() const { return _c1; } + + /** @brief Set the tanh relaxation part coefficient + * @param c The tanh relaxation part coefficient + */ + inline void c1(const real c) { _c1 = c; } + + /** @brief Compute the relaxation factor + * + * This method is responsible of avoiding overshooting when computing the + * derivatives + * @param iter The current iteration + */ + real Relax(const unsigned int& iter); + + private: + /// The number of iterations + unsigned int _iters; + + /// The constant relaxation part coefficient + real _c0; + + /// The tanh relaxation part coefficient + real _c1; +}; + /** @class ImplicitEulerScheme Time.hpp * @brief Implicit 1st order Euler time scheme * @@ -1141,7 +1209,7 @@ class ABScheme : public LocalTimeSchemeBase<1, 5> * evaluated somewhere inside the time step. Obviously, since that point depends * on the derivative itself, a fixed point problem shall be solved */ -class ImplicitEulerScheme : public TimeSchemeBase<2, 1> +class ImplicitEulerScheme : public ImplicitSchemeBase<2, 2> { public: /** @brief Costructor @@ -1157,7 +1225,7 @@ class ImplicitEulerScheme : public TimeSchemeBase<2, 1> real dt_factor = 0.5); /// @brief Destructor - ~ImplicitEulerScheme() {} + virtual ~ImplicitEulerScheme() {} /** @brief Run a time step * @@ -1173,6 +1241,76 @@ class ImplicitEulerScheme : public TimeSchemeBase<2, 1> real _dt_factor; }; +/** @class BackwardEulerScheme Time.hpp + * @brief Implicit 1st order Backward Euler time scheme + * + * The implicit 1st order Backward Euler method is an implicit method where the + * derivative is evaluated at the end of the time step. + * + * It is quite popular due to its dissipative properties + */ +class BackwardEulerScheme : public ImplicitEulerScheme +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + */ + BackwardEulerScheme(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10) + : ImplicitEulerScheme(log, waves, iters, 1.0) + { + if (iters < 10) { + c0(0.1 - 0.01 * iters); + c1(0.07); + } + else { + c0(0.0); + c1(1.0 / (10.0 + 0.051 * iters * iters)); + } + } + + /// @brief Destructor + ~BackwardEulerScheme() {} +}; + +/** @class MidpointScheme Time.hpp + * @brief Implicit 1st order Midpoint time scheme + * + * The implicit 1st order Midpoint method is an implicit method where the + * derivative is evaluated at the middle of the time step. + * + * It is quite popular due to its energy conservation properties. + */ +class MidpointScheme : public ImplicitEulerScheme +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + */ + MidpointScheme(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10) + : ImplicitEulerScheme(log, waves, iters, 0.5) + { + if (iters < 14) { + c0(0.154 - 0.011 * iters); + c1(0.08); + } + else { + c0(0.0); + c1(0.015); + } + } + + /// @brief Destructor + ~MidpointScheme() {} +}; + /** @class ImplicitNewmarkScheme Time.hpp * @brief Implicit Newmark Scheme * diff --git a/tests/Mooring/time_schemes.txt b/tests/Mooring/time_schemes.txt index cef4aea0..a3b25ac9 100644 --- a/tests/Mooring/time_schemes.txt +++ b/tests/Mooring/time_schemes.txt @@ -18,7 +18,7 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 2 writeLog Write a log file @DT@ dtM time step to use in mooring integration (s) @TSCHEME@ tScheme The time integration Scheme (-) -1.0 cfl CFL to determine the simulation timestep +1000.0 cfl CFL to determine the simulation timestep 1000.0 WtrDnsty water density (kg/m^3) 500 WtrDpth water depth (m) 1.0 dtIC time interval for analyzing convergence during IC gen (s) diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index f9e1cf2c..54bf1658 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -57,17 +57,18 @@ static std::vector schemes({ "Euler", "AB2", "AB3", "AB4", - "BEuler2", - "BEuler3", - "BEuler4", "BEuler5", - "Midpoint2", - "Midpoint3", - "Midpoint4", + "BEuler10", + "BEuler15", + "BEuler20", "Midpoint5", + "Midpoint10", + "Midpoint15", + "Midpoint20", "ACA5", "ACA10", - "ACA15" }); + "ACA15", + "ACA20" }); static std::vector dts({ "1.5E-4", "1.8E-4", "2.6E-4", @@ -75,16 +76,17 @@ static std::vector dts({ "1.5E-4", "1.5E-4", "1.1E-4", "1.0E-4", - "1.8E-4", - "1.8E-4", - "1.9E-4", - "1.9E-4", - "2.8E-4", - "2.8E-4", - "2.8E-4", - "2.8E-4", + "1.0", + "1.0", + "1.0", + "1.0", + "1.0", + "1.0", + "1.0", + "1.0", "2.0E-4", "2.0E-3", + "2.4E-3", "2.4E-3" }); using namespace std; From cf8b66f6461f3dc360eaf163d4f9328e2ccc28b8 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 21 Feb 2024 15:08:26 +0100 Subject: [PATCH 054/145] Fixed the wrong number of iterations --- source/Time.cpp | 4 ++-- source/Time.hpp | 2 -- tests/time_schemes.cpp | 16 ++++++++-------- 3 files changed, 10 insertions(+), 12 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index 9076467c..a3d896a0 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -533,12 +533,12 @@ ImplicitEulerScheme::Step(real& dt) { t += _dt_factor * dt; rd[1] = rd[0]; // We use rd[1] just as a tmp storage to compute relaxation - for (unsigned int i = 0; i < _iters; i++) { + for (unsigned int i = 0; i < iters(); i++) { r[1] = r[0] + rd[0] * (_dt_factor * dt); Update(_dt_factor * dt, 1); CalcStateDeriv(0); - if (i < _iters - 1) { + if (i < iters() - 1) { // We cannot relax on the last step const real relax = Relax(i); rd[0].Mix(rd[1], relax); diff --git a/source/Time.hpp b/source/Time.hpp index aa3c22a2..a52cec63 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1235,8 +1235,6 @@ class ImplicitEulerScheme : public ImplicitSchemeBase<2, 2> virtual void Step(real& dt); private: - /// The number of iterations - unsigned int _iters; /// The evaluation point real _dt_factor; }; diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index 54bf1658..223ea957 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -76,14 +76,14 @@ static std::vector dts({ "1.5E-4", "1.5E-4", "1.1E-4", "1.0E-4", - "1.0", - "1.0", - "1.0", - "1.0", - "1.0", - "1.0", - "1.0", - "1.0", + "1.9E-4", + "2.0E-4", + "2.0E-4", + "2.0E-4", + "2.8E-4", + "3.4E-4", + "3.6E-4", + "3.8E-4", "2.0E-4", "2.0E-3", "2.4E-3", From ba0883e507ea770c1907b8dfe1bbe1c1e6fc591a Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 22 Feb 2024 14:28:15 +0100 Subject: [PATCH 055/145] Added API entries to modify the time step related variables --- source/MoorDyn2.cpp | 75 +++++++++++++++++++++++++++++++++++++++++++-- source/MoorDyn2.h | 51 ++++++++++++++++++++++++++++++ source/MoorDyn2.hpp | 55 +++++++++++++++++++++++++++++++++ source/Time.cpp | 8 ----- source/Time.hpp | 35 +++++++++++++++++---- 5 files changed, 208 insertions(+), 16 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 5e41099a..fa44a161 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -34,7 +34,6 @@ #include "Misc.hpp" #include "MoorDyn2.hpp" #include "Rod.hpp" -#include #ifdef LINUX #include @@ -415,7 +414,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // restore drag coefficients to normal values and restart time counter of // each object _t_integrator->SetTime(0.0); - _t_integrator->FromStationary(t_integrator); + _t_integrator->SetState(t_integrator.GetState()); for (auto obj : LineList) { obj->scaleDrag(1.0 / ICDfac); obj->setTime(0.0); @@ -2505,6 +2504,78 @@ MoorDyn_GetFASTtens(MoorDyn system, return MOORDYN_SUCCESS; } +int DECLDIR +MoorDyn_GetDt(MoorDyn system, double* dt) +{ + CHECK_SYSTEM(system); + *dt = ((moordyn::MoorDyn*)system)->GetDt(); + return MOORDYN_SUCCESS; +} + +int DECLDIR +MoorDyn_SetDt(MoorDyn system, double dt) +{ + CHECK_SYSTEM(system); + moordyn::real casted = (moordyn::real)dt; + ((moordyn::MoorDyn*)system)->SetDt(casted); + return MOORDYN_SUCCESS; +} + +int DECLDIR +MoorDyn_GetCFL(MoorDyn system, double* cfl) +{ + CHECK_SYSTEM(system); + *cfl = ((moordyn::MoorDyn*)system)->GetCFL(); + return MOORDYN_SUCCESS; +} + +int DECLDIR +MoorDyn_SetCFL(MoorDyn system, double cfl) +{ + CHECK_SYSTEM(system); + moordyn::real casted = (moordyn::real)cfl; + ((moordyn::MoorDyn*)system)->SetCFL(casted); + return MOORDYN_SUCCESS; +} + +int DECLDIR +MoorDyn_GetTimeScheme(MoorDyn system, char* name, size_t* name_len) +{ + CHECK_SYSTEM(system); + moordyn::TimeScheme* tscheme = ((moordyn::MoorDyn*)system)->GetTimeScheme(); + std::string out = tscheme->GetName(); + if (name_len) + *name_len = out.size() + 1; + if (name) { + strncpy(name, out.c_str(), out.size()); + name[out.size()] = '\0'; + } + return MOORDYN_SUCCESS; +} + +int DECLDIR +MoorDyn_SetTimeScheme(MoorDyn system, const char* name) +{ + CHECK_SYSTEM(system); + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + moordyn::MoorDyn* sys = (moordyn::MoorDyn*)system; + moordyn::TimeScheme* tscheme; + try { + tscheme = create_time_scheme(name, sys->GetLogger(), sys->GetWaves()); + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + cerr << "Error (" << err << ") at " << __FUNC_NAME__ << "():" << endl + << err_msg << endl; + return err; + } + tscheme->SetState(sys->GetTimeScheme()->GetState()); + sys->SetTimeScheme(tscheme); + + return MOORDYN_SUCCESS; +} + int DECLDIR MoorDyn_Serialize(MoorDyn system, size_t* size, uint64_t* data) { diff --git a/source/MoorDyn2.h b/source/MoorDyn2.h index c51deaaa..62edd093 100644 --- a/source/MoorDyn2.h +++ b/source/MoorDyn2.h @@ -415,6 +415,57 @@ extern "C" float AnchHTen[], float AnchVTen[]); + /** @brief Get the current model time step + * @param system The Moordyn system + * @param dt The output time step + * @return MOORDYN_SUCESS if the data is correctly got, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_GetDt(MoorDyn system, double* dt); + + /** @brief Set the model time step + * @param system The Moordyn system + * @param dt The new time step + * @return MOORDYN_SUCESS if the data is correctly set, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_SetDt(MoorDyn system, double dt); + + /** @brief Get the current model Courant–Friedrichs–Lewy factor + * @param system The Moordyn system + * @param cfl The output Courant–Friedrichs–Lewy factor + * @return MOORDYN_SUCESS if the data is correctly got, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_GetCFL(MoorDyn system, double* cfl); + + /** @brief Set the model Courant–Friedrichs–Lewy factor + * @param system The Moordyn system + * @param cfl The new Courant–Friedrichs–Lewy factor + * @return MOORDYN_SUCESS if the data is correctly set, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_SetCFL(MoorDyn system, double cfl); + + /** @brief Get the current time scheme name + * @param system The Moordyn system + * @param name The output name. Can be NULL. + * @param name_len The output number of bytes written. Can be NULL. + * @return MOORDYN_SUCESS if the data is correctly got, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_GetTimeScheme(MoorDyn system, + char* name, + size_t* name_len); + + /** @brief Set the time scheme by its name + * @param system The Moordyn system + * @param name The new time scheme name. + * @return MOORDYN_SUCESS if the data is correctly got, an error code + * otherwise (see @ref moordyn_errors) + */ + int DECLDIR MoorDyn_SetTimeScheme(MoorDyn system, const char* name); + /** @brief Serialize the system to bytes * * Typically you want to call this function twice. A first call to know the diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index 90431205..a8a1f582 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -46,6 +46,7 @@ #include "Rod.hpp" #include "Body.hpp" #include "Seafloor.hpp" +#include #ifdef USE_VTK #include @@ -315,6 +316,60 @@ class MoorDyn final : public io::IO void saveVTK(const char* filename) const; #endif + /** @brief Get the model time step + * @return The model time step + */ + inline real GetDt() const { return dtM0; } + + /** @brief Set the model time step + * @param dt The model time step + * @note The CFL will be changed accordingly + */ + inline void SetDt(real dt) { + this->dtM0 = dt; + this->cfl = 0.0; + for (auto obj : LineList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : PointList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : RodList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + for (auto obj : BodyList) + cfl = (std::max)(cfl, obj->dt2cfl(dtM0)); + } + + /** @brief Get the model Courant–Friedrichs–Lewy factor + * @return The CFL + */ + inline real GetCFL() const { return cfl; } + + /** @brief Set the model Courant–Friedrichs–Lewy factor + * @param cfl The CFL + * @note The time step will be changed accordingly + */ + inline void SetCFL(real cfl) { + this->cfl = cfl; + this->dtM0 = (std::numeric_limits::max)(); + for (auto obj : LineList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : PointList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : RodList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + for (auto obj : BodyList) + dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); + } + + /** @brief Get the current time integrator + * @return The time integrator + */ + inline TimeScheme* GetTimeScheme() const { return _t_integrator; } + + /** @brief Set the current time integrator + * @return The time integrator + */ + inline void SetTimeScheme(TimeScheme* tscheme) { _t_integrator = tscheme; } + protected: /** @brief Read the input file, setting up all the required objects and * their relationships diff --git a/source/Time.cpp b/source/Time.cpp index a3d896a0..d1aa416f 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -149,14 +149,6 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) ground->setDependentStates(); // NOTE: (not likely needed) } -template -void -TimeSchemeBase::FromStationary(const StationaryScheme& state) -{ - r[0] = state.r[0]; -} - - StationaryScheme::StationaryScheme(moordyn::Log* log, moordyn::WavesRef waves) : TimeSchemeBase(log, waves) , _error(0.0) diff --git a/source/Time.hpp b/source/Time.hpp index a52cec63..b207d56f 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -46,8 +46,6 @@ namespace moordyn { -class StationaryScheme; - /** @class TimeScheme Time.hpp * @brief Time scheme abstraction * @@ -255,10 +253,21 @@ class TimeScheme : public io::IO */ virtual void Step(real& dt) { t_local += dt; }; + /** @brief Get the state variable + * @param i The index of the state variable to take + * @return The state variable + */ + inline virtual MoorDynState GetState(unsigned int i=0) + { + return MoorDynState(); + } + /** @brief Resume the simulation from the stationary solution * @param state The stationary solution + * @param i The index of the state variable to take */ - virtual void FromStationary(const StationaryScheme& state) {}; + inline virtual void SetState(const MoorDynState& state, unsigned int i=0) + {}; protected: /** @brief Costructor @@ -562,10 +571,23 @@ class TimeSchemeBase : public TimeScheme */ virtual void Step(real& dt) { TimeScheme::Step(dt); }; + /** @brief Get the state variable + * @param i The index of the state variable to take + * @return The state variable + */ + inline MoorDynState GetState(unsigned int i=0) + { + return r[i]; + } + /** @brief Resume the simulation from the stationary solution * @param state The stationary solution + * @param i The index of the state variable to take */ - virtual void FromStationary(const StationaryScheme& state); + inline virtual void SetState(const MoorDynState& state, unsigned int i=0) + { + r[i] = state; + } /** @brief Produce the packed data to be saved * @@ -863,10 +885,11 @@ class LocalTimeSchemeBase : public TimeSchemeBase /** @brief Resume the simulation from the stationary solution * @param state The stationary solution + * @param i The index of the state variable to take */ - inline void FromStationary(const StationaryScheme& state) + inline void SetState(const MoorDynState& state, unsigned int i=0) { - TimeSchemeBase::FromStationary(state); + TimeSchemeBase::SetState(state, i); ComputeDt(); } From 681aadaf173410fd44066355ddd3debd32ec4723 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 22 Feb 2024 14:40:51 +0100 Subject: [PATCH 056/145] Added a midpoint implicit test to optimize it --- tests/CMakeLists.txt | 1 + tests/Mooring/midpoint/WD0600_Chain.txt | 28 ++++ tests/midpoint.cpp | 200 ++++++++++++++++++++++++ 3 files changed, 229 insertions(+) create mode 100644 tests/Mooring/midpoint/WD0600_Chain.txt create mode 100644 tests/midpoint.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index e0e8fd68..bb748a47 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -46,6 +46,7 @@ set(CATCH2_TESTS polyester quasi_static_chain local_euler + midpoint ) function(make_executable test_name, extension) diff --git a/tests/Mooring/midpoint/WD0600_Chain.txt b/tests/Mooring/midpoint/WD0600_Chain.txt new file mode 100644 index 00000000..1a7b6307 --- /dev/null +++ b/tests/Mooring/midpoint/WD0600_Chain.txt @@ -0,0 +1,28 @@ +--------------------- MoorDyn Input File ------------------------------------ +MoorDyn input file of the mooring system for FD validation cases +----------------------- 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.252 390 1.674e9 -1.0 0 1.37 1.0 0.64 0.0 +---------------------- POINT PROPERTIES -------------------------------- +ID Type X Y Z Mass Volume CdA Ca +(#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) +1 Fixed 1500 0.0 -600.0 0 0 0 0 +2 Vessel 0.0 0.0 0.0 0 0 0 0 +---------------------- LINES ---------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs +(#) (name) (#) (#) (m) (-) (-) +1 chain 1 2 1700 170 - +---------------------- OPTIONS ----------------------------------------- +2 writeLog Write a log file +0.1 cfl CFL to determine the simulation timestep +1.0e5 kBot bottom stiffness (Pa/m) +1.0e4 cBot bottom damping (Pa-s/m) +1025.0 WtrDnsty water density (kg/m^3) +600 WtrDpth water depth (m) +1.0 dtIC time interval for analyzing convergence during IC gen (s) +100.0 TmaxIC max time for ic gen (s) +1.0e-2 threshIC threshold for IC convergence (-) +0.5 FrictionCoefficient Coulomb friction between the line and the seabed (-) +midpoint10 tScheme Time scheme to apply +------------------------- need this line -------------------------------------- diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp new file mode 100644 index 00000000..1f538780 --- /dev/null +++ b/tests/midpoint.cpp @@ -0,0 +1,200 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file quasi_static_chain.cpp + * Validation against Orcaflex + */ + +#include "MoorDyn2.h" +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; + +/// Time step in the moton files +#define DT 0.1 +/// List of available depths +#define DEPTH "0600" +/// List of available motions +#define MOTION "ZZP1_A2" +/// List of static tensions at the fairlead predicted by quasi-static codes +#define STATIC_FAIR_TENSION 5232.6 +/// List of static tensions at the anchor predicted by quasi-static codes +#define STATIC_ANCHOR_TENSION 3244.2 +/// Allowed relative error in the static tension value +#define MAX_STATIC_ERROR 0.1 +/// Allowed relative error in the variable tension value +#define MAX_DYNAMIC_ERROR 0.15 + +/** @brief Parse a line of a tabulated file + * @param line The line of text + * @return The vector of values + */ +vector +parse_tab_line(const char* line) +{ + vector fields; + const char del = '\t'; + stringstream sstream(line); + string word; + while (std::getline(sstream, word, del)) { + fields.push_back(stod(word.c_str())); + } + return fields; +} + +/** @brief Read a tabulated file + * @param filepath The tabulated file path + * @return 2D array, where the first dimension is the file line and the second + * is the field + */ +vector> +read_tab_file(const char* filepath) +{ + vector> data; + fstream f; + f.open(filepath, ios::in); + if (!f.is_open()) + return data; + string line; + while (getline(f, line)) { + data.push_back(parse_tab_line(line.c_str())); + } + f.close(); + + return data; +} + +TEST_CASE("Validation") +{ + stringstream lines_file, motion_file, ref_file; + lines_file << "Mooring/WD" << DEPTH << "_Chain" + << ".txt"; + motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; + ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION + << ".txt"; + auto motion_data = read_tab_file(motion_file.str().c_str()); + auto ref_data = read_tab_file(ref_file.str().c_str()); + + MoorDyn system = MoorDyn_Create(lines_file.str().c_str()); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + // Set the fairlead points, as they are in the config file + std::fill(x, x + 3, 0.0); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Compute the static tension + int num_lines = 1; + float fh, fv, ah, av; + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair0 = sqrt(fh * fh + fv * fv); + const double ffair_ref0 = 1.e3 * STATIC_FAIR_TENSION; + const double fanch0 = sqrt(ah * ah + av * av); + const double fanch_ref0 = 1.e3 * STATIC_ANCHOR_TENSION; + const double efair0 = (ffair0 - ffair_ref0) / ffair_ref0; + const double eanch0 = (fanch0 - fanch_ref0) / fanch_ref0; + REQUIRE(efair0 <= MAX_STATIC_ERROR); + REQUIRE(eanch0 <= MAX_STATIC_ERROR); + + // Change the time step + REQUIRE(MoorDyn_SetCFL(system, 0.14) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + // Start integrating. The integration have a first chunk of initialization + // motion to get something more periodic. In that chunk of the simulation + // we are not checking for errors + double ef_time = 0.0; + double ef_value = 0.0; + double ef_ref = 0.0; + double ea_time = 0.0; + double ea_value = 0.0; + double ea_ref = 0.0; + unsigned int i_ref = 0; // To track the line in the ref values file + double f[3]; + double t_ref0 = motion_data[0][0]; + for (unsigned int i = 0; i < motion_data.size() - 1; i++) { + double t_ref = motion_data[i][0]; + double t = t_ref - t_ref0; + double dt = DT; + for (unsigned int j = 0; j < 3; j++) { + x[j] = motion_data[i][j + 1]; + dx[j] = (motion_data[i + 1][j + 1] - x[j]) / dt; + } + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + if (t_ref < 0.0) + continue; + + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair = sqrt(fh * fh + fv * fv) - ffair0; + const double ffair_ref = 1.e3 * ref_data[i_ref][3] - ffair_ref0; + const double fanch = sqrt(ah * ah + av * av) - fanch0; + const double fanch_ref = 2.0 * (1.e3 * ref_data[i_ref][4] - fanch_ref0); + if (fabs(ffair - ffair_ref) > ef_value) { + ef_time = t; + ef_value = fabs(ffair - ffair_ref); + } + if (fabs(ffair_ref) > ef_ref) + ef_ref = fabs(ffair_ref); + if (fabs(fanch - fanch_ref) > ea_value) { + ea_time = t; + ea_value = fabs(fanch - fanch_ref); + } + if (fabs(fanch_ref) > ea_ref) + ea_ref = fabs(fanch_ref); + + i_ref++; + } + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); + + ef_value = ef_value / (2.0 * ef_ref); + const double max_rel_err = MAX_DYNAMIC_ERROR; + REQUIRE(ef_value <= max_rel_err); + ea_value = ea_value / (2.0 * ea_ref); + // For the time being we better ignore these errors + // REQUIRE(ea_value <= max_rel_err); +} From 7b1288738dbd66f2a66ed8895f1420dc76920bf1 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 22 Feb 2024 14:51:55 +0100 Subject: [PATCH 057/145] Some fixes --- source/Time.hpp | 10 ++-------- tests/midpoint.cpp | 6 +++--- 2 files changed, 5 insertions(+), 11 deletions(-) diff --git a/source/Time.hpp b/source/Time.hpp index b207d56f..405ebae5 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1318,14 +1318,8 @@ class MidpointScheme : public ImplicitEulerScheme unsigned int iters = 10) : ImplicitEulerScheme(log, waves, iters, 0.5) { - if (iters < 14) { - c0(0.154 - 0.011 * iters); - c1(0.08); - } - else { - c0(0.0); - c1(0.015); - } + c0(1.0); + c1(1.0); } /// @brief Destructor diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp index 1f538780..2c0cce97 100644 --- a/tests/midpoint.cpp +++ b/tests/midpoint.cpp @@ -49,7 +49,7 @@ using namespace std; /// List of available depths #define DEPTH "0600" /// List of available motions -#define MOTION "ZZP1_A2" +#define MOTION "ZZP1_A1" /// List of static tensions at the fairlead predicted by quasi-static codes #define STATIC_FAIR_TENSION 5232.6 /// List of static tensions at the anchor predicted by quasi-static codes @@ -101,7 +101,7 @@ read_tab_file(const char* filepath) TEST_CASE("Validation") { stringstream lines_file, motion_file, ref_file; - lines_file << "Mooring/WD" << DEPTH << "_Chain" + lines_file << "Mooring/midpoint/WD" << DEPTH << "_Chain" << ".txt"; motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION @@ -137,7 +137,7 @@ TEST_CASE("Validation") REQUIRE(eanch0 <= MAX_STATIC_ERROR); // Change the time step - REQUIRE(MoorDyn_SetCFL(system, 0.14) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.16) == MOORDYN_SUCCESS); double dtM; REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); std::cout << "New time step = " << dtM << " s" << std::endl; From 78a72656d195947080e94f213f13a5ec15fba9f6 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 23 Feb 2024 09:41:40 +0100 Subject: [PATCH 058/145] Optimized the time steps at the OrcaFlex validation --- source/MoorDyn2.cpp | 3 +- source/MoorDyn2.hpp | 15 +- source/Time.cpp | 44 ++---- source/Time.hpp | 76 +-------- tests/CMakeLists.txt | 2 + tests/Mooring/midpoint/WD0600_Chain.txt | 28 ---- tests/aca.cpp | 200 ++++++++++++++++++++++++ tests/beuler.cpp | 200 ++++++++++++++++++++++++ tests/midpoint.cpp | 14 +- 9 files changed, 438 insertions(+), 144 deletions(-) delete mode 100644 tests/Mooring/midpoint/WD0600_Chain.txt create mode 100644 tests/aca.cpp create mode 100644 tests/beuler.cpp diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index fa44a161..a94d3da6 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -2570,8 +2570,9 @@ MoorDyn_SetTimeScheme(MoorDyn system, const char* name) << err_msg << endl; return err; } - tscheme->SetState(sys->GetTimeScheme()->GetState()); + auto state = sys->GetTimeScheme()->GetState(); sys->SetTimeScheme(tscheme); + tscheme->SetState(state); return MOORDYN_SUCCESS; } diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index a8a1f582..88e4bb08 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -368,7 +368,20 @@ class MoorDyn final : public io::IO /** @brief Set the current time integrator * @return The time integrator */ - inline void SetTimeScheme(TimeScheme* tscheme) { _t_integrator = tscheme; } + inline void SetTimeScheme(TimeScheme* tscheme) { + _t_integrator = tscheme; + _t_integrator->SetGround(GroundBody); + for (auto obj : BodyList) + _t_integrator->AddBody(obj); + for (auto obj : RodList) + _t_integrator->AddRod(obj); + for (auto obj : PointList) + _t_integrator->AddPoint(obj); + for (auto obj : LineList) + _t_integrator->AddLine(obj); + _t_integrator->SetCFL(cfl); + _t_integrator->Init(); + } protected: /** @brief Read the input file, setting up all the required objects and diff --git a/source/Time.cpp b/source/Time.cpp index d1aa416f..a883298d 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -495,7 +495,7 @@ ImplicitSchemeBase::ImplicitSchemeBase(moordyn::Log* log, unsigned int iters) : TimeSchemeBase(log, waves) , _iters(iters) - , _c0(0.5) + , _c0(0.9) , _c1(0.0) { } @@ -504,8 +504,10 @@ template real ImplicitSchemeBase::Relax(const unsigned int& iter) { - const real x = (iter + 1) / _iters; - return c0() / _iters + c1() * tanh(x); + const real x = 4. * ((iter + 1.) / _iters - 0.5); // [-1, 1] + const real y0 = 1. / _iters; // (0, 1] + const real y1 = 0.5 * (tanh(x) + 1.); // (0, 1) + return c0() * (1. - y0) + c1() * (1. - y1); } ImplicitEulerScheme::ImplicitEulerScheme(moordyn::Log* log, @@ -550,8 +552,7 @@ ImplicitNewmarkScheme::ImplicitNewmarkScheme(moordyn::Log* log, unsigned int iters, real gamma, real beta) - : TimeSchemeBase(log, waves) - , _iters(iters) + : ImplicitSchemeBase(log, waves, iters) , _gamma(gamma) , _beta(beta) { @@ -559,6 +560,8 @@ ImplicitNewmarkScheme::ImplicitNewmarkScheme(moordyn::Log* log, s << "gamma=" << gamma << ",beta=" << beta << " implicit Newmark (" << iters << " iterations)"; name = s.str(); + c0(0.9); + c1(0.15); } void @@ -570,7 +573,7 @@ ImplicitNewmarkScheme::Step(real& dt) t += dt; rd[2] = rd[0]; // We use rd[2] just as a tmp storage to compute relaxation - for (unsigned int i = 0; i < _iters; i++) { + for (unsigned int i = 0; i < iters(); i++) { // At the time of computing r acts as an input, and rd as an output. // Thus we just need to apply the Newmark scheme on r[1] and store // the new rates of change on rd[1] @@ -578,7 +581,7 @@ ImplicitNewmarkScheme::Step(real& dt) Update(dt, 1); CalcStateDeriv(1); - if (i < _iters - 1) { + if (i < iters() - 1) { // We cannot relax the last step const real relax = Relax(i); rd[1].Mix(rd[2], relax); @@ -594,29 +597,6 @@ ImplicitNewmarkScheme::Step(real& dt) TimeSchemeBase::Step(dt); } -#ifndef INEWMARK_RELAX_INIT -#define INEWMARK_RELAX_INIT 0.95 -#endif - -#ifndef INEWMARK_RELAX_POW -#define INEWMARK_RELAX_POW 3 -#endif - -#ifndef INEWMARK_RELAX_CFL -#define INEWMARK_RELAX_CFL 2.0 -#endif - -real -ImplicitNewmarkScheme::Relax(const unsigned int& iter) -{ - const real f = (real)iter / _iters; - const real relax = INEWMARK_RELAX_INIT * (1 - pow(f, INEWMARK_RELAX_POW)); - // The relax factor shall be bounded by the CFL - const real relax_cfl = (std::min)(INEWMARK_RELAX_INIT, - INEWMARK_RELAX_CFL * GetCFL()); - return (std::max)(relax, relax_cfl); -} - TimeScheme* create_time_scheme(const std::string& name, moordyn::Log* log, @@ -648,7 +628,7 @@ create_time_scheme(const std::string& name, } else if (str::startswith(str::lower(name), "beuler")) { try { unsigned int iters = std::stoi(name.substr(6)); - out = new BackwardEulerScheme(log, waves, iters); + out = new ImplicitEulerScheme(log, waves, iters, 1.0); } catch (std::invalid_argument) { stringstream s; s << "Invalid Backward Euler name format '" << name << "'"; @@ -657,7 +637,7 @@ create_time_scheme(const std::string& name, } else if (str::startswith(str::lower(name), "midpoint")) { try { unsigned int iters = std::stoi(name.substr(8)); - out = new MidpointScheme(log, waves, iters); + out = new ImplicitEulerScheme(log, waves, iters, 0.5); } catch (std::invalid_argument) { stringstream s; s << "Invalid Midpoint name format '" << name << "'"; diff --git a/source/Time.hpp b/source/Time.hpp index 405ebae5..f5b43d1a 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1262,70 +1262,6 @@ class ImplicitEulerScheme : public ImplicitSchemeBase<2, 2> real _dt_factor; }; -/** @class BackwardEulerScheme Time.hpp - * @brief Implicit 1st order Backward Euler time scheme - * - * The implicit 1st order Backward Euler method is an implicit method where the - * derivative is evaluated at the end of the time step. - * - * It is quite popular due to its dissipative properties - */ -class BackwardEulerScheme : public ImplicitEulerScheme -{ - public: - /** @brief Costructor - * @param log Logging handler - * @param waves Waves instance - * @param iters The number of inner iterations to find the derivative - */ - BackwardEulerScheme(moordyn::Log* log, - WavesRef waves, - unsigned int iters = 10) - : ImplicitEulerScheme(log, waves, iters, 1.0) - { - if (iters < 10) { - c0(0.1 - 0.01 * iters); - c1(0.07); - } - else { - c0(0.0); - c1(1.0 / (10.0 + 0.051 * iters * iters)); - } - } - - /// @brief Destructor - ~BackwardEulerScheme() {} -}; - -/** @class MidpointScheme Time.hpp - * @brief Implicit 1st order Midpoint time scheme - * - * The implicit 1st order Midpoint method is an implicit method where the - * derivative is evaluated at the middle of the time step. - * - * It is quite popular due to its energy conservation properties. - */ -class MidpointScheme : public ImplicitEulerScheme -{ - public: - /** @brief Costructor - * @param log Logging handler - * @param waves Waves instance - * @param iters The number of inner iterations to find the derivative - */ - MidpointScheme(moordyn::Log* log, - WavesRef waves, - unsigned int iters = 10) - : ImplicitEulerScheme(log, waves, iters, 0.5) - { - c0(1.0); - c1(1.0); - } - - /// @brief Destructor - ~MidpointScheme() {} -}; - /** @class ImplicitNewmarkScheme Time.hpp * @brief Implicit Newmark Scheme * @@ -1334,7 +1270,7 @@ class MidpointScheme : public ImplicitEulerScheme * and solids, specifically on its Average Constant Acceleration incarnation * @see https://en.wikipedia.org/wiki/Newmark-beta_method */ -class ImplicitNewmarkScheme : public TimeSchemeBase<2, 3> +class ImplicitNewmarkScheme : public ImplicitSchemeBase<2, 3> { public: /** @brief Costructor @@ -1361,16 +1297,6 @@ class ImplicitNewmarkScheme : public TimeSchemeBase<2, 3> virtual void Step(real& dt); private: - /** @brief Compute the relaxation factor - * - * This method is responsible of avoiding overshooting when computing the - * derivatives - * @param iter The current iteration - */ - real Relax(const unsigned int& iter); - - /// The number of iterations - unsigned int _iters; /// Alpha factor real _gamma; /// Beta factor diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index bb748a47..cada36f6 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -46,7 +46,9 @@ set(CATCH2_TESTS polyester quasi_static_chain local_euler + beuler midpoint + aca ) function(make_executable test_name, extension) diff --git a/tests/Mooring/midpoint/WD0600_Chain.txt b/tests/Mooring/midpoint/WD0600_Chain.txt deleted file mode 100644 index 1a7b6307..00000000 --- a/tests/Mooring/midpoint/WD0600_Chain.txt +++ /dev/null @@ -1,28 +0,0 @@ ---------------------- MoorDyn Input File ------------------------------------ -MoorDyn input file of the mooring system for FD validation cases ------------------------ 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.252 390 1.674e9 -1.0 0 1.37 1.0 0.64 0.0 ----------------------- POINT PROPERTIES -------------------------------- -ID Type X Y Z Mass Volume CdA Ca -(#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) -1 Fixed 1500 0.0 -600.0 0 0 0 0 -2 Vessel 0.0 0.0 0.0 0 0 0 0 ----------------------- LINES ---------------------------------------- -ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs -(#) (name) (#) (#) (m) (-) (-) -1 chain 1 2 1700 170 - ----------------------- OPTIONS ----------------------------------------- -2 writeLog Write a log file -0.1 cfl CFL to determine the simulation timestep -1.0e5 kBot bottom stiffness (Pa/m) -1.0e4 cBot bottom damping (Pa-s/m) -1025.0 WtrDnsty water density (kg/m^3) -600 WtrDpth water depth (m) -1.0 dtIC time interval for analyzing convergence during IC gen (s) -100.0 TmaxIC max time for ic gen (s) -1.0e-2 threshIC threshold for IC convergence (-) -0.5 FrictionCoefficient Coulomb friction between the line and the seabed (-) -midpoint10 tScheme Time scheme to apply -------------------------- need this line -------------------------------------- diff --git a/tests/aca.cpp b/tests/aca.cpp new file mode 100644 index 00000000..da57bdc3 --- /dev/null +++ b/tests/aca.cpp @@ -0,0 +1,200 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file aca.cpp + * Tests ran with the Average Constant Acceleration Newmark scheme + */ + +#include "MoorDyn2.h" +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; + +/// Time step in the moton files +#define DT 0.1 +/// List of available depths +#define DEPTH "0600" +/// List of available motions +#define MOTION "ZZP1_A1" +/// List of static tensions at the fairlead predicted by quasi-static codes +#define STATIC_FAIR_TENSION 5232.6 +/// List of static tensions at the anchor predicted by quasi-static codes +#define STATIC_ANCHOR_TENSION 3244.2 +/// Allowed relative error in the static tension value +#define MAX_STATIC_ERROR 0.1 +/// Allowed relative error in the variable tension value +#define MAX_DYNAMIC_ERROR 0.15 + +/** @brief Parse a line of a tabulated file + * @param line The line of text + * @return The vector of values + */ +vector +parse_tab_line(const char* line) +{ + vector fields; + const char del = '\t'; + stringstream sstream(line); + string word; + while (std::getline(sstream, word, del)) { + fields.push_back(stod(word.c_str())); + } + return fields; +} + +/** @brief Read a tabulated file + * @param filepath The tabulated file path + * @return 2D array, where the first dimension is the file line and the second + * is the field + */ +vector> +read_tab_file(const char* filepath) +{ + vector> data; + fstream f; + f.open(filepath, ios::in); + if (!f.is_open()) + return data; + string line; + while (getline(f, line)) { + data.push_back(parse_tab_line(line.c_str())); + } + f.close(); + + return data; +} + +TEST_CASE("quasi_static_chain with aca10") +{ + stringstream lines_file, motion_file, ref_file; + lines_file << "Mooring/WD" << DEPTH << "_Chain" << ".txt"; + motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; + ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION + << ".txt"; + auto motion_data = read_tab_file(motion_file.str().c_str()); + auto ref_data = read_tab_file(ref_file.str().c_str()); + + MoorDyn system = MoorDyn_Create(lines_file.str().c_str()); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + // Set the fairlead points, as they are in the config file + std::fill(x, x + 3, 0.0); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Compute the static tension + int num_lines = 1; + float fh, fv, ah, av; + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair0 = sqrt(fh * fh + fv * fv); + const double ffair_ref0 = 1.e3 * STATIC_FAIR_TENSION; + const double fanch0 = sqrt(ah * ah + av * av); + const double fanch_ref0 = 1.e3 * STATIC_ANCHOR_TENSION; + const double efair0 = (ffair0 - ffair_ref0) / ffair_ref0; + const double eanch0 = (fanch0 - fanch_ref0) / fanch_ref0; + REQUIRE(efair0 <= MAX_STATIC_ERROR); + REQUIRE(eanch0 <= MAX_STATIC_ERROR); + + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "aca10") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.5) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + // Start integrating. The integration have a first chunk of initialization + // motion to get something more periodic. In that chunk of the simulation + // we are not checking for errors + double ef_time = 0.0; + double ef_value = 0.0; + double ef_ref = 0.0; + double ea_time = 0.0; + double ea_value = 0.0; + double ea_ref = 0.0; + unsigned int i_ref = 0; // To track the line in the ref values file + double f[3]; + double t_ref0 = motion_data[0][0]; + for (unsigned int i = 0; i < motion_data.size() - 1; i++) { + double t_ref = motion_data[i][0]; + double t = t_ref - t_ref0; + double dt = DT; + for (unsigned int j = 0; j < 3; j++) { + x[j] = motion_data[i][j + 1]; + dx[j] = (motion_data[i + 1][j + 1] - x[j]) / dt; + } + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + if (t_ref < 0.0) + continue; + + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair = sqrt(fh * fh + fv * fv) - ffair0; + const double ffair_ref = 1.e3 * ref_data[i_ref][3] - ffair_ref0; + const double fanch = sqrt(ah * ah + av * av) - fanch0; + const double fanch_ref = 2.0 * (1.e3 * ref_data[i_ref][4] - fanch_ref0); + if (fabs(ffair - ffair_ref) > ef_value) { + ef_time = t; + ef_value = fabs(ffair - ffair_ref); + } + if (fabs(ffair_ref) > ef_ref) + ef_ref = fabs(ffair_ref); + if (fabs(fanch - fanch_ref) > ea_value) { + ea_time = t; + ea_value = fabs(fanch - fanch_ref); + } + if (fabs(fanch_ref) > ea_ref) + ea_ref = fabs(fanch_ref); + + i_ref++; + } + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); + + ef_value = ef_value / (2.0 * ef_ref); + const double max_rel_err = MAX_DYNAMIC_ERROR; + REQUIRE(ef_value <= max_rel_err); + ea_value = ea_value / (2.0 * ea_ref); + // For the time being we better ignore these errors + // REQUIRE(ea_value <= max_rel_err); +} diff --git a/tests/beuler.cpp b/tests/beuler.cpp new file mode 100644 index 00000000..12d3db0b --- /dev/null +++ b/tests/beuler.cpp @@ -0,0 +1,200 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file beuler.cpp + * Tests ran with the implicit Backwards Euler + */ + +#include "MoorDyn2.h" +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; + +/// Time step in the moton files +#define DT 0.1 +/// List of available depths +#define DEPTH "0600" +/// List of available motions +#define MOTION "ZZP1_A1" +/// List of static tensions at the fairlead predicted by quasi-static codes +#define STATIC_FAIR_TENSION 5232.6 +/// List of static tensions at the anchor predicted by quasi-static codes +#define STATIC_ANCHOR_TENSION 3244.2 +/// Allowed relative error in the static tension value +#define MAX_STATIC_ERROR 0.1 +/// Allowed relative error in the variable tension value +#define MAX_DYNAMIC_ERROR 0.15 + +/** @brief Parse a line of a tabulated file + * @param line The line of text + * @return The vector of values + */ +vector +parse_tab_line(const char* line) +{ + vector fields; + const char del = '\t'; + stringstream sstream(line); + string word; + while (std::getline(sstream, word, del)) { + fields.push_back(stod(word.c_str())); + } + return fields; +} + +/** @brief Read a tabulated file + * @param filepath The tabulated file path + * @return 2D array, where the first dimension is the file line and the second + * is the field + */ +vector> +read_tab_file(const char* filepath) +{ + vector> data; + fstream f; + f.open(filepath, ios::in); + if (!f.is_open()) + return data; + string line; + while (getline(f, line)) { + data.push_back(parse_tab_line(line.c_str())); + } + f.close(); + + return data; +} + +TEST_CASE("quasi_static_chain with beuler10") +{ + stringstream lines_file, motion_file, ref_file; + lines_file << "Mooring/WD" << DEPTH << "_Chain" << ".txt"; + motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; + ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION + << ".txt"; + auto motion_data = read_tab_file(motion_file.str().c_str()); + auto ref_data = read_tab_file(ref_file.str().c_str()); + + MoorDyn system = MoorDyn_Create(lines_file.str().c_str()); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + // Set the fairlead points, as they are in the config file + std::fill(x, x + 3, 0.0); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Compute the static tension + int num_lines = 1; + float fh, fv, ah, av; + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair0 = sqrt(fh * fh + fv * fv); + const double ffair_ref0 = 1.e3 * STATIC_FAIR_TENSION; + const double fanch0 = sqrt(ah * ah + av * av); + const double fanch_ref0 = 1.e3 * STATIC_ANCHOR_TENSION; + const double efair0 = (ffair0 - ffair_ref0) / ffair_ref0; + const double eanch0 = (fanch0 - fanch_ref0) / fanch_ref0; + REQUIRE(efair0 <= MAX_STATIC_ERROR); + REQUIRE(eanch0 <= MAX_STATIC_ERROR); + + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "beuler10") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.6) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + // Start integrating. The integration have a first chunk of initialization + // motion to get something more periodic. In that chunk of the simulation + // we are not checking for errors + double ef_time = 0.0; + double ef_value = 0.0; + double ef_ref = 0.0; + double ea_time = 0.0; + double ea_value = 0.0; + double ea_ref = 0.0; + unsigned int i_ref = 0; // To track the line in the ref values file + double f[3]; + double t_ref0 = motion_data[0][0]; + for (unsigned int i = 0; i < motion_data.size() - 1; i++) { + double t_ref = motion_data[i][0]; + double t = t_ref - t_ref0; + double dt = DT; + for (unsigned int j = 0; j < 3; j++) { + x[j] = motion_data[i][j + 1]; + dx[j] = (motion_data[i + 1][j + 1] - x[j]) / dt; + } + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + if (t_ref < 0.0) + continue; + + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair = sqrt(fh * fh + fv * fv) - ffair0; + const double ffair_ref = 1.e3 * ref_data[i_ref][3] - ffair_ref0; + const double fanch = sqrt(ah * ah + av * av) - fanch0; + const double fanch_ref = 2.0 * (1.e3 * ref_data[i_ref][4] - fanch_ref0); + if (fabs(ffair - ffair_ref) > ef_value) { + ef_time = t; + ef_value = fabs(ffair - ffair_ref); + } + if (fabs(ffair_ref) > ef_ref) + ef_ref = fabs(ffair_ref); + if (fabs(fanch - fanch_ref) > ea_value) { + ea_time = t; + ea_value = fabs(fanch - fanch_ref); + } + if (fabs(fanch_ref) > ea_ref) + ea_ref = fabs(fanch_ref); + + i_ref++; + } + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); + + ef_value = ef_value / (2.0 * ef_ref); + const double max_rel_err = MAX_DYNAMIC_ERROR; + REQUIRE(ef_value <= max_rel_err); + ea_value = ea_value / (2.0 * ea_ref); + // For the time being we better ignore these errors + // REQUIRE(ea_value <= max_rel_err); +} diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp index 2c0cce97..d55aecbf 100644 --- a/tests/midpoint.cpp +++ b/tests/midpoint.cpp @@ -28,8 +28,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -/** @file quasi_static_chain.cpp - * Validation against Orcaflex +/** @file midpoint.cpp + * Tests ran with the implicit Midpoint scheme */ #include "MoorDyn2.h" @@ -98,11 +98,10 @@ read_tab_file(const char* filepath) return data; } -TEST_CASE("Validation") +TEST_CASE("quasi_static_chain with midpoint10") { stringstream lines_file, motion_file, ref_file; - lines_file << "Mooring/midpoint/WD" << DEPTH << "_Chain" - << ".txt"; + lines_file << "Mooring/WD" << DEPTH << "_Chain" << ".txt"; motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION << ".txt"; @@ -136,8 +135,9 @@ TEST_CASE("Validation") REQUIRE(efair0 <= MAX_STATIC_ERROR); REQUIRE(eanch0 <= MAX_STATIC_ERROR); - // Change the time step - REQUIRE(MoorDyn_SetCFL(system, 0.16) == MOORDYN_SUCCESS); + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "midpoint10") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.9) == MOORDYN_SUCCESS); double dtM; REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); std::cout << "New time step = " << dtM << " s" << std::endl; From 7766a5d5bbf3ac5e0a9d885ff551f0fac2cb7e04 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 23 Feb 2024 09:53:01 +0100 Subject: [PATCH 059/145] New time steps --- tests/time_schemes.cpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index 223ea957..f192f325 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -76,18 +76,18 @@ static std::vector dts({ "1.5E-4", "1.5E-4", "1.1E-4", "1.0E-4", - "1.9E-4", - "2.0E-4", - "2.0E-4", - "2.0E-4", - "2.8E-4", - "3.4E-4", - "3.6E-4", - "3.8E-4", - "2.0E-4", - "2.0E-3", - "2.4E-3", - "2.4E-3" }); + "9.6E-4", + "1.4E-3", + "1.5E-3", + "1.6E-3", + "1.4E-3", + "1.9E-3", + "1.9E-3", + "1.9E-3", + "9.4E-4", + "1.5E-3", + "1.5E-3", + "1.6E-3" }); using namespace std; From 11081e9d259f205bbd1030e267b2750a98ca4eff Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 23 Feb 2024 10:00:28 +0100 Subject: [PATCH 060/145] Added the complex example to the midpoint scheme --- tests/midpoint.cpp | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp index d55aecbf..c4555266 100644 --- a/tests/midpoint.cpp +++ b/tests/midpoint.cpp @@ -198,3 +198,32 @@ TEST_CASE("quasi_static_chain with midpoint10") // For the time being we better ignore these errors // REQUIRE(ea_value <= max_rel_err); } + +TEST_CASE("Complex system simulation with midpoint5") +{ + MoorDyn system = MoorDyn_Create("Mooring/local_euler/complex_system.txt"); + REQUIRE(system); + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + auto point = MoorDyn_GetPoint(system, 4); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x) == MOORDYN_SUCCESS); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "midpoint5") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.75) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + double f[6]; + double t = 0.0, dt = 50.0; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} From 2aa724d4e61f8dc88d4ca98e7e9fcfd5e6b9219a Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 22 Mar 2024 11:23:16 +0100 Subject: [PATCH 061/145] Wilson-theta scheme --- source/State.cpp | 93 +++++++++++++++++ source/State.hpp | 48 +++++++++ source/Time.cpp | 56 ++++++++++ source/Time.hpp | 42 ++++++++ tests/CMakeLists.txt | 1 + tests/time_schemes.cpp | 6 +- tests/wilson.cpp | 229 +++++++++++++++++++++++++++++++++++++++++ 7 files changed, 473 insertions(+), 2 deletions(-) create mode 100644 tests/wilson.cpp diff --git a/source/State.cpp b/source/State.cpp index f8f20434..00bca46a 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -499,6 +499,68 @@ StateVarDeriv>::Newmark( return ret; } +template<> +StateVarDeriv +StateVarDeriv::Wilson( + const StateVarDeriv& visitor, const real& tau, const real& dt) +{ + StateVarDeriv ret; + const real f = tau / dt; + ret.acc = (1 - 0.5 * f) * acc + 0.5 * f * visitor.acc; + ret.vel = vel + 0.5 * dt * ( + (1 - 1.0 / 3.0 * f) * acc + 1.0 / 3.0 * f * visitor.acc); + return ret; +} + +template<> +StateVarDeriv +StateVarDeriv::Wilson( + const StateVarDeriv& visitor, const real& tau, const real& dt) +{ + StateVarDeriv ret; + const real f = tau / dt; + ret.acc = (1 - 0.5 * f) * acc + 0.5 * f * visitor.acc; + ret.vel = vel + 0.5 * dt * ( + (1 - 1.0 / 3.0 * f) * acc + 1.0 / 3.0 * f * visitor.acc); + return ret; +} + +template<> +StateVarDeriv +StateVarDeriv::Wilson( + const StateVarDeriv& visitor, + const real& tau, + const real& dt) +{ + StateVarDeriv ret; + const real f = tau / dt; + ret.acc = (1 - 0.5 * f) * acc + 0.5 * f * visitor.acc; + ret.vel = vel + XYZQuat::fromVec6(0.5 * dt * ( + (1 - 1.0 / 3.0 * f) * acc + 1.0 / 3.0 * f * visitor.acc)); + return ret; +} + +template<> +StateVarDeriv> +StateVarDeriv>::Wilson( + const StateVarDeriv>& visitor, + const real& tau, + const real& dt) +{ + StateVarDeriv> ret; + ret.vel.reserve(vel.size()); + ret.acc.reserve(acc.size()); + const real f = tau / dt; + const real f2 = 0.5 * f; + const real f3 = 1.0 / 3.0 * f; + for (unsigned int i = 0; i < vel.size(); i++) { + ret.acc.push_back((1 - f2) * acc[i] + f2 * visitor.acc[i]); + ret.vel.push_back(vel[i] + 0.5 * dt * ( + (1 - f3) * acc[i] + f3 * visitor.acc[i])); + } + return ret; +} + template<> void StateVarDeriv::Mix(const StateVarDeriv& rhs, const real& f) @@ -825,6 +887,37 @@ DMoorDynStateDt::Newmark(const DMoorDynStateDt& rhs, return out; } +DMoorDynStateDt +DMoorDynStateDt::Wilson(const DMoorDynStateDt& rhs, + const real& tau, + const real& dt) +{ + DMoorDynStateDt out; + + if (lines.size() != rhs.lines.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.lines.reserve(lines.size()); + for (unsigned int i = 0; i < lines.size(); i++) + out.lines.push_back(lines[i].Wilson(rhs.lines[i], tau, dt)); + if (points.size() != rhs.points.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.points.reserve(points.size()); + for (unsigned int i = 0; i < points.size(); i++) + out.points.push_back(points[i].Wilson(rhs.points[i], tau, dt)); + if (rods.size() != rhs.rods.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.rods.reserve(rods.size()); + for (unsigned int i = 0; i < rods.size(); i++) + out.rods.push_back(rods[i].Wilson(rhs.rods[i], tau, dt)); + if (bodies.size() != rhs.bodies.size()) + throw moordyn::invalid_value_error("Invalid input size"); + out.bodies.reserve(bodies.size()); + for (unsigned int i = 0; i < bodies.size(); i++) + out.bodies.push_back(bodies[i].Wilson(rhs.bodies[i], tau, dt)); + + return out; +} + void DMoorDynStateDt::Mix(const DMoorDynStateDt& visitor, const real& f) { diff --git a/source/State.hpp b/source/State.hpp index 8c2bdf75..200cd90d 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -193,6 +193,30 @@ class StateVarDeriv real gamma = 0.5, real beta = 0.25); + /** @brief Carry out a Wilson step + * + * The resulting state rate of change will have the following acceleration + * + * \f[ \dot{u(t_{n+1})} = + * (1 - \frac{\tau}{2 \theta \Delta t}) \dot{u(t_{n})} + + * \frac{\tau}{2 \theta \Delta t} \dot{u(t_{n+1})}) \f] + * + * and the following velocity + * + * \f[ u(t_{n+1}) = u(t_{n}) + \frac{\tau}{2} ( + * (1 - \frac{\tau}{3 \theta \Delta t}) \dot{u(t_{n})} + + * \frac{\tau}{3 \theta \Delta t} \dot{u(t_{n+1})}) \f] + * + * Note that \f$ \tau \f$ can be smaller than \f$ \theta \Delta t \f$. + * + * @param visitor The acceleration at the next time step + * @param tau Time advancing, \f$ \tau \f$. + * @param dt Enlarged time step, \f$ \theta \Delta t \f$. + */ + StateVarDeriv Wilson(const StateVarDeriv& visitor, + const real& tau, + const real& dt); + /** @brief Mix this state variation rate with another one * * This can be used as a relaxation method when looking for stationary @@ -377,6 +401,30 @@ class DMoorDynStateDt real gamma = 0.5, real beta = 0.25); + /** @brief Carry out a Wilson step + * + * The resulting state rate of change will have the following acceleration + * + * \f[ \dot{u(t_{n+1})} = + * (1 - \frac{\tau}{2 \theta \Delta t}) \dot{u(t_{n})} + + * \frac{\tau}{2 \theta \Delta t} \dot{u(t_{n+1})}) \f] + * + * and the following velocity + * + * \f[ u(t_{n+1}) = u(t_{n}) + \frac{\tau}{2} ( + * (1 - \frac{\tau}{3 \theta \Delta t}) \dot{u(t_{n})} + + * \frac{\tau}{3 \theta \Delta t} \dot{u(t_{n+1})}) \f] + * + * Note that \f$ \tau \f$ can be smaller than \f$ \theta \Delta t \f$. + * + * @param visitor The acceleration at the next time step + * @param tau Time advancing, \f$ \tau \f$. + * @param dt Enlarged time step, \f$ \theta \Delta t \f$. + */ + DMoorDynStateDt Wilson(const DMoorDynStateDt& visitor, + const real& tau, + const real& dt); + /** @brief Mix this state variation rate with another one * * This can be used as a relaxation method when looking for stationary diff --git a/source/Time.cpp b/source/Time.cpp index a883298d..af01225e 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -597,6 +597,52 @@ ImplicitNewmarkScheme::Step(real& dt) TimeSchemeBase::Step(dt); } +ImplicitWilsonScheme::ImplicitWilsonScheme(moordyn::Log* log, + moordyn::WavesRef waves, + unsigned int iters, + real theta) + : ImplicitSchemeBase(log, waves, iters) + , _theta(theta) +{ + stringstream s; + s << "theta=" << theta << " implicit Wilson (" + << iters << " iterations)"; + name = s.str(); + c0(0.015); + c1(0.000); +} + +void +ImplicitWilsonScheme::Step(real& dt) +{ + const real tdt = _theta * dt; + t += tdt; + rd[1] = rd[0]; // We use rd[1] just as a tmp storage to compute relaxation + for (unsigned int i = 0; i < iters(); i++) { + // At the time of computing r acts as an input, and rd as an output. + // Thus we just need to apply the Newmark scheme on r[1] and store + // the new rates of change on rd[1] + r[1] = r[0] + rd[0].Wilson(rd[1], tdt, tdt) * tdt; + Update(tdt, 1); + CalcStateDeriv(1); + + if (i < iters() - 1) { + // We cannot relax on the last step + const real relax = Relax(i); + rd[0].Mix(rd[1], relax); + rd[1] = rd[0]; + } + } + + // Apply + t -= (1.f - _theta) * dt; + r[1] = r[0] + rd[0].Wilson(rd[1], dt, tdt) * dt; + r[0] = r[1]; + rd[0] = rd[1]; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + TimeScheme* create_time_scheme(const std::string& name, moordyn::Log* log, @@ -653,6 +699,16 @@ create_time_scheme(const std::string& name, << name << "'"; throw moordyn::invalid_value_error(s.str().c_str()); } + } else if (str::startswith(str::lower(name), "wilson")) { + try { + unsigned int iters = std::stoi(name.substr(6)); + out = new ImplicitWilsonScheme(log, waves, iters, 1.37); + } catch (std::invalid_argument) { + stringstream s; + s << "Invalid Wilson name format '" + << name << "'"; + throw moordyn::invalid_value_error(s.str().c_str()); + } } else { stringstream s; s << "Unknown time scheme '" << name << "'"; diff --git a/source/Time.hpp b/source/Time.hpp index f5b43d1a..1e9a9f69 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1303,6 +1303,48 @@ class ImplicitNewmarkScheme : public ImplicitSchemeBase<2, 3> real _beta; }; +/** @class ImplicitNewmarkScheme Time.hpp + * @brief Implicit Wilson Scheme + * + * The implicit Wilson scheme is so far similar to the Implicit Euler scheme, + * but the derivatives are computed considering a time step larger than the + * integration one, instead of lower. + * + * With the computed acceleration a Taylor series expansion is practised to + * integrate. + * + * @see https://www.academia.edu/download/59040594/wilson197220190426-49259-kipdfs.pdf + */ +class ImplicitWilsonScheme : public ImplicitSchemeBase<2, 3> +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + * @param gamma The gamma factor + * @param beta The beta factor + */ + ImplicitWilsonScheme(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10, + real theta = 1.37); + + /// @brief Destructor + ~ImplicitWilsonScheme() {} + + /** @brief Run a time step + * + * This function is the one that must be specialized on each time scheme + * @param dt Time step + */ + virtual void Step(real& dt); + + private: + /// Theta factor + real _theta; +}; + /** @brief Create a time scheme * @param name The time scheme name, one of the following: * "Euler", "Heun", "RK2", "RK4", "AB3", "AB4" diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index cada36f6..fa1fe884 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -49,6 +49,7 @@ set(CATCH2_TESTS beuler midpoint aca + wilson ) function(make_executable test_name, extension) diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index f192f325..79ccfaf0 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -68,7 +68,8 @@ static std::vector schemes({ "Euler", "ACA5", "ACA10", "ACA15", - "ACA20" }); + "ACA20", + "Wilson20" }); static std::vector dts({ "1.5E-4", "1.8E-4", "2.6E-4", @@ -87,7 +88,8 @@ static std::vector dts({ "1.5E-4", "9.4E-4", "1.5E-3", "1.5E-3", - "1.6E-3" }); + "1.6E-3", + "2.4E-3"}); using namespace std; diff --git a/tests/wilson.cpp b/tests/wilson.cpp new file mode 100644 index 00000000..734da76a --- /dev/null +++ b/tests/wilson.cpp @@ -0,0 +1,229 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file wilson.cpp + * Tests ran with the implicit Wilson scheme + */ + +#include "MoorDyn2.h" +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; + +/// Time step in the moton files +#define DT 0.1 +/// List of available depths +#define DEPTH "0600" +/// List of available motions +#define MOTION "ZZP1_A1" +/// List of static tensions at the fairlead predicted by quasi-static codes +#define STATIC_FAIR_TENSION 5232.6 +/// List of static tensions at the anchor predicted by quasi-static codes +#define STATIC_ANCHOR_TENSION 3244.2 +/// Allowed relative error in the static tension value +#define MAX_STATIC_ERROR 0.1 +/// Allowed relative error in the variable tension value +#define MAX_DYNAMIC_ERROR 0.15 + +/** @brief Parse a line of a tabulated file + * @param line The line of text + * @return The vector of values + */ +vector +parse_tab_line(const char* line) +{ + vector fields; + const char del = '\t'; + stringstream sstream(line); + string word; + while (std::getline(sstream, word, del)) { + fields.push_back(stod(word.c_str())); + } + return fields; +} + +/** @brief Read a tabulated file + * @param filepath The tabulated file path + * @return 2D array, where the first dimension is the file line and the second + * is the field + */ +vector> +read_tab_file(const char* filepath) +{ + vector> data; + fstream f; + f.open(filepath, ios::in); + if (!f.is_open()) + return data; + string line; + while (getline(f, line)) { + data.push_back(parse_tab_line(line.c_str())); + } + f.close(); + + return data; +} + +TEST_CASE("quasi_static_chain with wilson20") +{ + stringstream lines_file, motion_file, ref_file; + lines_file << "Mooring/WD" << DEPTH << "_Chain" << ".txt"; + motion_file << "Mooring/QuasiStatic/" << MOTION << ".txt"; + ref_file << "Mooring/QuasiStatic/WD" << DEPTH << "_Chain_" << MOTION + << ".txt"; + auto motion_data = read_tab_file(motion_file.str().c_str()); + auto ref_data = read_tab_file(ref_file.str().c_str()); + + MoorDyn system = MoorDyn_Create(lines_file.str().c_str()); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + // Set the fairlead points, as they are in the config file + std::fill(x, x + 3, 0.0); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Compute the static tension + int num_lines = 1; + float fh, fv, ah, av; + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair0 = sqrt(fh * fh + fv * fv); + const double ffair_ref0 = 1.e3 * STATIC_FAIR_TENSION; + const double fanch0 = sqrt(ah * ah + av * av); + const double fanch_ref0 = 1.e3 * STATIC_ANCHOR_TENSION; + const double efair0 = (ffair0 - ffair_ref0) / ffair_ref0; + const double eanch0 = (fanch0 - fanch_ref0) / fanch_ref0; + REQUIRE(efair0 <= MAX_STATIC_ERROR); + REQUIRE(eanch0 <= MAX_STATIC_ERROR); + + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "wilson20") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.8) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + // Start integrating. The integration have a first chunk of initialization + // motion to get something more periodic. In that chunk of the simulation + // we are not checking for errors + double ef_time = 0.0; + double ef_value = 0.0; + double ef_ref = 0.0; + double ea_time = 0.0; + double ea_value = 0.0; + double ea_ref = 0.0; + unsigned int i_ref = 0; // To track the line in the ref values file + double f[3]; + double t_ref0 = motion_data[0][0]; + for (unsigned int i = 0; i < motion_data.size() - 1; i++) { + double t_ref = motion_data[i][0]; + double t = t_ref - t_ref0; + double dt = DT; + for (unsigned int j = 0; j < 3; j++) { + x[j] = motion_data[i][j + 1]; + dx[j] = (motion_data[i + 1][j + 1] - x[j]) / dt; + } + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + if (t_ref < 0.0) + continue; + + REQUIRE(MoorDyn_GetFASTtens( + system, &num_lines, &fh, &fv, &ah, &av) == MOORDYN_SUCCESS); + const double ffair = sqrt(fh * fh + fv * fv) - ffair0; + const double ffair_ref = 1.e3 * ref_data[i_ref][3] - ffair_ref0; + const double fanch = sqrt(ah * ah + av * av) - fanch0; + const double fanch_ref = 2.0 * (1.e3 * ref_data[i_ref][4] - fanch_ref0); + if (fabs(ffair - ffair_ref) > ef_value) { + ef_time = t; + ef_value = fabs(ffair - ffair_ref); + } + if (fabs(ffair_ref) > ef_ref) + ef_ref = fabs(ffair_ref); + if (fabs(fanch - fanch_ref) > ea_value) { + ea_time = t; + ea_value = fabs(fanch - fanch_ref); + } + if (fabs(fanch_ref) > ea_ref) + ea_ref = fabs(fanch_ref); + + i_ref++; + } + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); + + ef_value = ef_value / (2.0 * ef_ref); + const double max_rel_err = MAX_DYNAMIC_ERROR; + REQUIRE(ef_value <= max_rel_err); + ea_value = ea_value / (2.0 * ea_ref); + // For the time being we better ignore these errors + // REQUIRE(ea_value <= max_rel_err); +} + +TEST_CASE("Complex system simulation with wilson20") +{ + MoorDyn system = MoorDyn_Create("Mooring/local_euler/complex_system.txt"); + REQUIRE(system); + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + double x[3], dx[3]; + auto point = MoorDyn_GetPoint(system, 4); + REQUIRE(point); + REQUIRE(MoorDyn_GetPointPos(point, x) == MOORDYN_SUCCESS); + std::fill(dx, dx + 3, 0.0); + REQUIRE(MoorDyn_Init(system, x, dx) == MOORDYN_SUCCESS); + + // Change the time scheme + REQUIRE(MoorDyn_SetTimeScheme(system, "wilson20") == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.75) == MOORDYN_SUCCESS); + double dtM; + REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); + std::cout << "New time step = " << dtM << " s" << std::endl; + + double f[6]; + double t = 0.0, dt = 50.0; + REQUIRE(MoorDyn_Step(system, x, dx, f, &t, &dt) == MOORDYN_SUCCESS); + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} From 9395781865b1bf19c409f4e6e1d4f59266b6bf8f Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 27 Mar 2024 11:39:31 +0100 Subject: [PATCH 062/145] WIP Anderson's acceleration --- source/Time.cpp | 142 +++++++++++++++++++++++++++++++++++ source/Time.hpp | 194 +++++++++++++++++++++++++++++++++++++++++++++++- 2 files changed, 334 insertions(+), 2 deletions(-) diff --git a/source/Time.cpp b/source/Time.cpp index af01225e..82f9e7ae 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -510,6 +510,112 @@ ImplicitSchemeBase::Relax(const unsigned int& iter) return c0() * (1. - y0) + c1() * (1. - y1); } +template +AndersonSchemeBase::AndersonSchemeBase(moordyn::Log* log, + WavesRef waves, + unsigned int iters, + unsigned int m, + real tol, + real tol_rel) + : ImplicitSchemeBase(log, waves) + , _iters(iters) + , _m((std::min)(m, iters)) + , _tol(tol) + , _tol_rel(tol_rel) +{ +} + +template +void +AndersonSchemeBase::qr(unsigned int iter, + unsigned int org, + unsigned int dst, + float dt) +{ + // Resize the matrices on demand + if (_X.rows() == 0) { + const unsigned int n = ndof(); + _x.resize(n, 2); + _g.resize(n, 2); + _X.resize(n, _m); + _G.resize(n, _m); + } + + // Roll the states and fill + _x.col(0) = _x.col(1); + _g.col(0) = _g.col(1); + fill(org, dst); + + auto [res_mean, res_max] = residue(); + this->LOGMSG << ", iter " << iter << ", residue = " << res_mean + << " (max=" << res_max << ")" << std::endl; + + const real relax = this->Relax(iter); + + if (iter == 0) { + _g0 = res_mean; + // We cannot do anything else because we have not data enough. So let's + // just relax the point so we do not get too far away from the + // attractor + this->rd[dst].Mix(this->rd[org], relax); + return; + } + + // Roll the matrices and fill them + unsigned int m = (std::min)(iter, _m); + for (unsigned int col = 0; col < m - 1; col++) { + _X.col(_m - m + col) = _X.col(_m - m + col + 1); + _G.col(_m - m + col) = _G.col(_m - m + col + 1); + } + _X.col(_m - 1) = _x.col(1) - _x.col(0); + _G.col(_m - 1) = _g.col(1) - _g.col(0); + + if (m < 2) { + // Again, we cannot produce an estimation yet + this->rd[dst].Mix(this->rd[org], relax); + return; + } + + // Solve + auto QR = _G(Eigen::placeholders::all, + Eigen::seqN(_m - m, m)).completeOrthogonalDecomposition(); + Eigen::Matrix + gamma = QR.solve(_g.col(1)); + + // Produce a new estimation + Eigen::Matrix + acc = _x.col(1) + _g.col(1) - (_X + _G) * gamma; + unsigned int n = 0; + for (unsigned int i = 0; i < this->lines.size(); i++) { + for (unsigned int j = 0; j < this->rd[org].lines[i].acc.size(); j++) { + this->rd[dst].lines[i].acc[j] = acc(Eigen::seqN(n, 3), 0); + this->rd[dst].lines[i].vel[j] = this->rd[org].lines[i].vel[j] + dt * ( + this->rd[dst].lines[i].acc[j] - this->rd[org].lines[i].acc[j]); + n += 3; + } + } + for (unsigned int i = 0; i < this->points.size(); i++) { + this->rd[dst].points[i].acc = acc(Eigen::seqN(n, 3), 0); + this->rd[dst].points[i].vel = this->rd[org].points[i].vel + dt * ( + this->rd[dst].points[i].acc - this->rd[org].points[i].acc); + n += 3; + } + for (unsigned int i = 0; i < this->rods.size(); i++) { + this->rd[dst].rods[i].acc = acc(Eigen::seqN(n, 6), 0); + this->rd[dst].rods[i].vel = this->rd[org].rods[i].vel + XYZQuat::fromVec6( + dt * (this->rd[dst].rods[i].acc - this->rd[org].rods[i].acc)); + n += 6; + } + for (unsigned int i = 0; i < this->bodies.size(); i++) { + this->rd[dst].bodies[i].acc = acc(Eigen::seqN(n, 6), 0); + this->rd[dst].bodies[i].vel = this->rd[org].bodies[i].vel + XYZQuat::fromVec6( + dt * (this->rd[dst].bodies[i].acc - this->rd[org].bodies[i].acc)); + n += 6; + } + + this->rd[dst].Mix(this->rd[org], relax); +} + ImplicitEulerScheme::ImplicitEulerScheme(moordyn::Log* log, moordyn::WavesRef waves, unsigned int iters, @@ -547,6 +653,42 @@ ImplicitEulerScheme::Step(real& dt) TimeSchemeBase::Step(dt); } +AndersonEulerScheme::AndersonEulerScheme(moordyn::Log* log, + moordyn::WavesRef waves, + unsigned int iters, + real dt_factor) + : AndersonSchemeBase(log, waves, iters) + , _dt_factor(dt_factor) +{ + stringstream s; + s << "k=" << dt_factor << " implicit Anderson Euler (" << iters + << " iterations)"; + name = s.str(); +} + +void +AndersonEulerScheme::Step(real& dt) +{ + t += _dt_factor * dt; + for (unsigned int i = 0; i < iters(); i++) { + r[1] = r[0] + rd[0] * (_dt_factor * dt); + Update(_dt_factor * dt, 1); + CalcStateDeriv(1); + + qr(i, 0, 1, _dt_factor * dt); + rd[0] = rd[1]; + + if (this->converged()) + break; + } + + // Apply + r[0] = r[0] + rd[0] * dt; + t += (1.0 - _dt_factor) * dt; + Update(dt, 0); + TimeSchemeBase::Step(dt); +} + ImplicitNewmarkScheme::ImplicitNewmarkScheme(moordyn::Log* log, moordyn::WavesRef waves, unsigned int iters, diff --git a/source/Time.hpp b/source/Time.hpp index 1e9a9f69..9cae8ac3 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1170,8 +1170,6 @@ class ImplicitSchemeBase : public TimeSchemeBase * @param log Logging handler * @param waves Waves instance * @param iters The number of inner iterations to find the derivative - * @param dt_factor The inner evaluation point factor. 0.5 for the midpoint - * method, 1.0 for the backward Euler method */ ImplicitSchemeBase(moordyn::Log* log, WavesRef waves, @@ -1225,6 +1223,161 @@ class ImplicitSchemeBase : public TimeSchemeBase real _c1; }; +/** @class AndersonSchemeBase Time.hpp + * @brief A generic abstract implicit scheme accelerated with Anderson scheme + * + * This class can be later overloaded to implement a plethora of time schemes + */ +template +class AndersonSchemeBase : public ImplicitSchemeBase +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + * @param m The number of points to compute Anderson's acceleration + * @param tol Minimum residue to consider that the solution has converged + * @param tol_rel Relative residue reduction to consider that the solution + * has converged + */ + AndersonSchemeBase(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10, + unsigned int m = 3, + real tol = 1.e-5, + real tol_rel = 1.e-3); + + /// @brief Destructor + virtual ~AndersonSchemeBase() {} + + /** @brief Get the residual tolerance + * + * When the maximum residue falls below this value the inner iteration + * is stopped + * @return The tolerance + */ + inline real tol() const { return _tol; } + + /** @brief Set the residual tolerance + * + * When the maximum residue falls below this value the inner iteration + * is stopped + * @param t The tolerance + */ + inline void tol(const real t) { _tol = t; } + + protected: + /** @brief Get the number of subiterations + * @return The number of iterations + */ + inline unsigned int iters() const { return _iters; } + + /** @brief Produce a new estimation + * @param iter The current iteration + * @param org The input point, x + * @param dst The input eval, f(x), as well as the output + * @param dt The time step to integrate the acceleration as the velocity + */ + void qr(unsigned int iter, unsigned int org, unsigned int dst, float dt); + + /** @brief Check if the iterator has converged + * @return true if the maximum residue has fallen below the tolerance, + * false otherwise + */ + inline const bool converged() const + { + const real g = _g.col(1).cwiseAbs().mean(); + return (g < _tol) || (g / _g0 < _tol_rel); + } + + /** @brief Get the stats of the residues + * @return The average and maximum residue + */ + inline const std::tuple residue() const + { + return { _g.col(1).cwiseAbs().mean(), _g.col(1).cwiseAbs().maxCoeff() }; + } + + private: + /// The number of iterations + unsigned int _iters; + + /// The number of points to compute Anderson's acceleration + unsigned int _m; + + /// Minimum residue to consider that the solution has converged + real _tol; + + /// Relative residue reduction to consider that the solution has converged + real _tol_rel; + + /// Initial residue + real _g0; + + /// The evaluation points list + Eigen::Matrix _x; + + /// The residues list + Eigen::Matrix _g; + + /// The evaluation points variation matrix + Eigen::Matrix _X; + + /// The residues variation matrix + Eigen::Matrix _G; + + /** @brief Compute the number of acceleration DOFs + * @return The number of acceleration DOFs + */ + inline unsigned int ndof() const { + unsigned int n = 3 * this->points.size() + 6 * (this->bodies.size() + this->rods.size()); + for (unsigned int i = 0; i < this->lines.size(); i++) + n += 3 * this->rd[0].lines[i].acc.size(); + return n; + } + + /** @brief Fill the last column of the X matrix + * @param org The point, x + * @param dst The eval, f(x) + * @note This function is assuming that the matrix is already resized + */ + inline void fill(unsigned int org, unsigned int dst) + { + unsigned int i, j, n = 0; + for (i = 0; i < this->lines.size(); i++) { + for (j = 0; j < this->rd[org].lines[i].acc.size(); j++) { + const vec x = this->rd[org].lines[i].acc[j]; + const vec fx = this->rd[dst].lines[i].acc[j]; + _x(Eigen::seqN(n, 3), 1) = x; + _g(Eigen::seqN(n, 3), 1) = fx - x; + n += 3; + } + } + for (i = 0; i < this->points.size(); i++) { + const vec x = this->rd[org].points[i].acc; + const vec fx = this->rd[dst].points[i].acc; + _x(Eigen::seqN(n, 3), 1) = x; + _g(Eigen::seqN(n, 3), 1) = fx - x; + n += 3; + } + for (i = 0; i < this->rods.size(); i++) { + const vec6 x = this->rd[org].rods[i].acc; + const vec6 fx = this->rd[dst].rods[i].acc; + _x(Eigen::seqN(n, 6), 1) = x; + _g(Eigen::seqN(n, 6), 1) = fx - x; + n += 6; + } + for (i = 0; i < this->bodies.size(); i++) { + const vec6 x = this->rd[org].bodies[i].acc; + const vec6 fx = this->rd[dst].bodies[i].acc; + _x(Eigen::seqN(n, 6), 1) = x; + _g(Eigen::seqN(n, 6), 1) = fx - x; + n += 6; + } + } +}; + /** @class ImplicitEulerScheme Time.hpp * @brief Implicit 1st order Euler time scheme * @@ -1262,6 +1415,43 @@ class ImplicitEulerScheme : public ImplicitSchemeBase<2, 2> real _dt_factor; }; +/** @class AndersonEulerScheme Time.hpp + * @brief Implicit 1st order Euler time scheme + * + * The implicit Euler method is an implicit method where the derivative is + * evaluated somewhere inside the time step. Obviously, since that point depends + * on the derivative itself, a fixed point problem shall be solved + */ +class AndersonEulerScheme : public AndersonSchemeBase<2, 2> +{ + public: + /** @brief Costructor + * @param log Logging handler + * @param waves Waves instance + * @param iters The number of inner iterations to find the derivative + * @param dt_factor The inner evaluation point factor. 0.5 for the midpoint + * method, 1.0 for the backward Euler method + */ + AndersonEulerScheme(moordyn::Log* log, + WavesRef waves, + unsigned int iters = 10, + real dt_factor = 0.5); + + /// @brief Destructor + virtual ~AndersonEulerScheme() {} + + /** @brief Run a time step + * + * This function is the one that must be specialized on each time scheme + * @param dt Time step + */ + virtual void Step(real& dt); + + private: + /// The evaluation point + real _dt_factor; +}; + /** @class ImplicitNewmarkScheme Time.hpp * @brief Implicit Newmark Scheme * From 86ac45f28067cfae661ab33a44babfbad0c0742b Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 27 Mar 2024 14:56:10 +0100 Subject: [PATCH 063/145] WIP Anderson's accelerator --- source/Misc.hpp | 6 +++++ source/Time.cpp | 70 +++++++++++++++++++++++++++++++++---------------- source/Time.hpp | 24 ++++++++++++----- 3 files changed, 71 insertions(+), 29 deletions(-) diff --git a/source/Misc.hpp b/source/Misc.hpp index 44c46a46..13c6421f 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -79,6 +79,12 @@ typedef Matrix Vector6d; typedef Matrix Matrix6d; typedef Matrix Vector6i; typedef Matrix Matrix6i; +// It is also convenient for us to define a generic Eigen dynamic matrix class +#ifdef MOORDYN_SINGLEPRECISSION +typedef MatrixXf MatrixXr; +#else +typedef MatrixXd MatrixXr; +#endif } /** @brief MoorDyn2 C++ API namespace diff --git a/source/Time.cpp b/source/Time.cpp index 82f9e7ae..3fff30b9 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -516,12 +516,15 @@ AndersonSchemeBase::AndersonSchemeBase(moordyn::Log* log, unsigned int iters, unsigned int m, real tol, - real tol_rel) - : ImplicitSchemeBase(log, waves) + real tol_rel, + real regularization) + : ImplicitSchemeBase(log, waves, iters) , _iters(iters) , _m((std::min)(m, iters)) , _tol(tol) , _tol_rel(tol_rel) + , _regularization(regularization) + , _n(0) { } @@ -534,11 +537,11 @@ AndersonSchemeBase::qr(unsigned int iter, { // Resize the matrices on demand if (_X.rows() == 0) { - const unsigned int n = ndof(); - _x.resize(n, 2); - _g.resize(n, 2); - _X.resize(n, _m); - _G.resize(n, _m); + _n = ndof(); + _x.resize(_n, 2); + _g.resize(_n, 2); + _X.resize(_n, _m); + _G.resize(_n, _m); } // Roll the states and fill @@ -547,9 +550,6 @@ AndersonSchemeBase::qr(unsigned int iter, fill(org, dst); auto [res_mean, res_max] = residue(); - this->LOGMSG << ", iter " << iter << ", residue = " << res_mean - << " (max=" << res_max << ")" << std::endl; - const real relax = this->Relax(iter); if (iter == 0) { @@ -561,6 +561,9 @@ AndersonSchemeBase::qr(unsigned int iter, return; } + this->rd[dst].Mix(this->rd[org], this->Relax(iter)); + return; + // Roll the matrices and fill them unsigned int m = (std::min)(iter, _m); for (unsigned int col = 0; col < m - 1; col++) { @@ -570,21 +573,33 @@ AndersonSchemeBase::qr(unsigned int iter, _X.col(_m - 1) = _x.col(1) - _x.col(0); _G.col(_m - 1) = _g.col(1) - _g.col(0); - if (m < 2) { + if (m < _m) { // Again, we cannot produce an estimation yet this->rd[dst].Mix(this->rd[org], relax); return; } - // Solve - auto QR = _G(Eigen::placeholders::all, - Eigen::seqN(_m - m, m)).completeOrthogonalDecomposition(); - Eigen::Matrix - gamma = QR.solve(_g.col(1)); + auto [res_prev_mean, res_prev_max] = residue(1); + if ((res_prev_mean < res_mean) && (res_prev_max < res_max)) { + // The acceleration is enworstning the prediction, better to stop this + // non-sense + this->rd[dst].Mix(this->rd[org], relax); + return; + } - // Produce a new estimation - Eigen::Matrix - acc = _x.col(1) + _g.col(1) - (_X + _G) * gamma; + Eigen::MatrixXr reg = _regularization * Eigen::MatrixXr::Identity(m, m); + // Solve using the Woodbury identity + // Eigen::MatrixXr XtG_inv = (_X.transpose() * _G + reg).inverse(); + // Eigen::MatrixXr B = Eigen::MatrixXr::Identity(_n, _n) + + // (_X - _G) * XtG_inv * _X.transpose(); + // Eigen::MatrixXr acc = _x.col(1) + B * _g.col(1); + // Solve by straight application + Eigen::MatrixXr Gr = _G; + Gr.block(_m - m, 0, m, m) += reg; + auto QR = Gr(Eigen::placeholders::all, + Eigen::seqN(_m - m, m)).completeOrthogonalDecomposition(); + Eigen::MatrixXr gamma = QR.solve(_g.col(1)); + Eigen::MatrixXr acc = _x.col(1) + _g.col(1) - (_X + Gr) * gamma; unsigned int n = 0; for (unsigned int i = 0; i < this->lines.size(); i++) { for (unsigned int j = 0; j < this->rd[org].lines[i].acc.size(); j++) { @@ -673,10 +688,12 @@ AndersonEulerScheme::Step(real& dt) for (unsigned int i = 0; i < iters(); i++) { r[1] = r[0] + rd[0] * (_dt_factor * dt); Update(_dt_factor * dt, 1); - CalcStateDeriv(1); + CalcStateDeriv(0); - qr(i, 0, 1, _dt_factor * dt); - rd[0] = rd[1]; + if (i < iters() - 1) { + qr(i, 1, 0, _dt_factor * dt); + rd[1] = rd[0]; + } if (this->converged()) break; @@ -831,6 +848,15 @@ create_time_scheme(const std::string& name, s << "Invalid Midpoint name format '" << name << "'"; throw moordyn::invalid_value_error(s.str().c_str()); } + } else if (str::startswith(str::lower(name), "anderson")) { + try { + unsigned int iters = std::stoi(name.substr(8)); + out = new AndersonEulerScheme(log, waves, iters, 0.5); + } catch (std::invalid_argument) { + stringstream s; + s << "Invalid Midpoint name format '" << name << "'"; + throw moordyn::invalid_value_error(s.str().c_str()); + } } else if (str::startswith(str::lower(name), "aca")) { try { unsigned int iters = std::stoi(name.substr(3)); diff --git a/source/Time.hpp b/source/Time.hpp index 9cae8ac3..fe06e7fa 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -1244,9 +1244,10 @@ class AndersonSchemeBase : public ImplicitSchemeBase AndersonSchemeBase(moordyn::Log* log, WavesRef waves, unsigned int iters = 10, - unsigned int m = 3, - real tol = 1.e-5, - real tol_rel = 1.e-3); + unsigned int m = 4, + real tol = 1.e-2, + real tol_rel = 1.e-2, + real regularization = 1.e-10); /// @brief Destructor virtual ~AndersonSchemeBase() {} @@ -1292,11 +1293,14 @@ class AndersonSchemeBase : public ImplicitSchemeBase } /** @brief Get the stats of the residues + * @param ago Either 0 to get the latests residue or 1 to get the previous + * one. * @return The average and maximum residue */ - inline const std::tuple residue() const + inline const std::tuple residue(unsigned int ago=0) const { - return { _g.col(1).cwiseAbs().mean(), _g.col(1).cwiseAbs().maxCoeff() }; + return { _g.col(1 - ago).cwiseAbs().mean(), + _g.col(1 - ago).cwiseAbs().maxCoeff() }; } private: @@ -1312,6 +1316,12 @@ class AndersonSchemeBase : public ImplicitSchemeBase /// Relative residue reduction to consider that the solution has converged real _tol_rel; + /// Regularization factor + real _regularization; + + /// Number of dofs + real _n; + /// Initial residue real _g0; @@ -1322,10 +1332,10 @@ class AndersonSchemeBase : public ImplicitSchemeBase Eigen::Matrix _g; /// The evaluation points variation matrix - Eigen::Matrix _X; + Eigen::MatrixXr _X; /// The residues variation matrix - Eigen::Matrix _G; + Eigen::MatrixXr _G; /** @brief Compute the number of acceleration DOFs * @return The number of acceleration DOFs From b4a8caeab8cbef25352a856fc32d407576d1b3ab Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 5 Jun 2024 16:17:01 +0200 Subject: [PATCH 064/145] Simplified some computations --- source/Line.cpp | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index ff798ee8..68070026 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -799,10 +799,7 @@ Line::getStateDeriv() // vectors (qs) for each segment (this is used for bending calculations) lstr[i] = unitvector(qs[i], r[i], r[i + 1]); - // this is the denominator of how the stretch rate equation was - // formulated - const double ldstr_top = (r[i + 1] - r[i]).dot(rd[i + 1] - rd[i]); - ldstr[i] = ldstr_top / lstr[i]; // strain rate of segment + ldstr[i] = qs[i].dot(rd[i + 1] - rd[i]); // strain rate of segment // V[i] = A * l[i]; // volume attributed to segment } @@ -911,18 +908,17 @@ Line::getStateDeriv() E = getNonlinearE(lstr[i], l[i]); if (lstr[i] / l[i] > 1.0) { - T[i] = E * A * (1. / l[i] - 1. / lstr[i]) * (r[i + 1] - r[i]); + T[i] = E * A * (lstr[i] - l[i]) / l[i] * qs[i]; } else { // cable can't "push" ... // or can it, if bending stiffness is nonzero? <<<<<<<<< - T[i] = vec(0.0, 0.0, 0.0); + T[i] = vec::Zero(); } // line internal damping force if (nCpoints > 0) c = getNonlinearC(ldstr[i], l[i]); - - Td[i] = c * A * (ldstr[i] / l[i]) * (r[i + 1] - r[i]) / lstr[i]; + Td[i] = c * A * ldstr[i] / l[i] * qs[i]; } // Bending loads From b074a3068081d188c02ca9e31c0cb26fb0e016c4 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 10 Jun 2024 07:30:34 +0200 Subject: [PATCH 065/145] Wrong number of nodes on the API provided wave kinematics --- wrappers/python/cmoordyn.cpp | 34 +++++++++++++++------------------- 1 file changed, 15 insertions(+), 19 deletions(-) diff --git a/wrappers/python/cmoordyn.cpp b/wrappers/python/cmoordyn.cpp index 09b1978a..d1597aa8 100644 --- a/wrappers/python/cmoordyn.cpp +++ b/wrappers/python/cmoordyn.cpp @@ -494,14 +494,12 @@ ext_wave_coords(PyObject*, PyObject* args) return NULL; // We need to know the number of coordinates to allocate - unsigned int nlines; - MoorDyn_GetNumberLines(system, &nlines); - unsigned int n = 0; - for (unsigned int i = 0; i < nlines; i++) { - unsigned int nnodes; - MoorDynLine l = MoorDyn_GetLine(system, i + 1); - MoorDyn_GetLineNumberNodes(l, &nnodes); - n += nnodes; + int err; + unsigned int n; + err = MoorDyn_ExternalWaveKinGetN(system, &n); + if (err != 0) { + PyErr_SetString(PyExc_RuntimeError, "MoorDyn reported an error"); + return NULL; } double* coords = (double*)malloc(n * 3 * sizeof(double)); @@ -509,7 +507,7 @@ ext_wave_coords(PyObject*, PyObject* args) PyErr_SetString(PyExc_RuntimeError, "Failure allocating memory"); return NULL; } - const int err = MoorDyn_ExternalWaveKinGetCoordinates(system, coords); + err = MoorDyn_ExternalWaveKinGetCoordinates(system, coords); if (err != 0) { free(coords); PyErr_SetString(PyExc_RuntimeError, "MoorDyn reported an error"); @@ -543,16 +541,14 @@ ext_wave_set(PyObject*, PyObject* args) return NULL; // We need to know the number of coordinates to avoid errors - unsigned int nlines; - MoorDyn_GetNumberLines(system, &nlines); - unsigned int n = 0; - for (unsigned int i = 0; i < nlines; i++) { - unsigned int nnodes; - MoorDynLine l = MoorDyn_GetLine(system, i + 1); - MoorDyn_GetLineNumberNodes(l, &nnodes); - n += nnodes; - n *= 3; + int err; + unsigned int n; + err = MoorDyn_ExternalWaveKinGetN(system, &n); + if (err != 0) { + PyErr_SetString(PyExc_RuntimeError, "MoorDyn reported an error"); + return NULL; } + n *= 3; v_lst = PySequence_Fast(v_lst, "1st argument must be iterable"); if (!v_lst) @@ -584,7 +580,7 @@ ext_wave_set(PyObject*, PyObject* args) } // Now we can call MoorDyn - const int err = MoorDyn_ExternalWaveKinSet(system, v_arr, a_arr, t); + err = MoorDyn_ExternalWaveKinSet(system, v_arr, a_arr, t); free(v_arr); free(a_arr); return PyLong_FromLong(err); From 1e91467074dfb1ad0fe3d1c4e08a056cf761de37 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 06:41:13 +0200 Subject: [PATCH 066/145] Tweaked the AB2 scheme, which was failing --- tests/time_schemes.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/time_schemes.cpp b/tests/time_schemes.cpp index 79ccfaf0..9c6742d5 100644 --- a/tests/time_schemes.cpp +++ b/tests/time_schemes.cpp @@ -74,7 +74,7 @@ static std::vector dts({ "1.5E-4", "1.8E-4", "2.6E-4", "4.9E-4", - "1.5E-4", + "1.4E-4", "1.1E-4", "1.0E-4", "9.6E-4", From 696c5b573e7ea8b8c7dbfde281c6c3a00a65a082 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 08:14:02 +0200 Subject: [PATCH 067/145] Unitialized q0 on zero-length rods --- source/Rod.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/source/Rod.cpp b/source/Rod.cpp index 4c5ca541..5be494cf 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -124,12 +124,12 @@ Rod::setup(int number_in, // segments) (1 = fully submerged, 0 = out of water) if (N == 0) { - // special case of zero-length rod, which is denoted by numsegs=0 in the - // intput file + // special case of zero-length rod, which is denoted by numsegs=0 in + // the intput file + q0 = vec::Zero(); l.assign(1, 0.); // line unstretched segment lengths V.assign(1, 0.); // segment volume? UnstrLen = 0.0; // set Rod length to zero - q = vec::Zero(); } else { // normal finite-length case UnstrLen = unitvector(q0, endCoords.head<3>(), endCoords.tail<3>()); @@ -137,9 +137,8 @@ Rod::setup(int number_in, UnstrLen / N; // distribute line length evenly over segments l.assign(N, lseg); // line unstretched segment lengths V.assign(N, lseg * 0.25 * pi * d * d); // segment volume? - // get Rod axis direction vector and Rod length - q = q0; } + q = q0; // ------------------------- set starting kinematics // ------------------------- From 0924f148c54d9d51b72caa166c425b800c19771c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 08:46:28 +0200 Subject: [PATCH 068/145] Slightly reduce the time step so midpoint is not failing --- tests/midpoint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp index c4555266..1b493447 100644 --- a/tests/midpoint.cpp +++ b/tests/midpoint.cpp @@ -216,7 +216,7 @@ TEST_CASE("Complex system simulation with midpoint5") // Change the time scheme REQUIRE(MoorDyn_SetTimeScheme(system, "midpoint5") == MOORDYN_SUCCESS); - REQUIRE(MoorDyn_SetCFL(system, 0.75) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.7) == MOORDYN_SUCCESS); double dtM; REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); std::cout << "New time step = " << dtM << " s" << std::endl; From ed4b4f147f756507f0386fad61ff50949f1c89fb Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 08:59:22 +0200 Subject: [PATCH 069/145] Started the automatic memory checking --- .github/workflows/memcheck.yml | 46 ++++++++++++++++++++++++++++++++++ CMakeLists.txt | 9 +++++++ tests/valgrind_suppress.txt | 1 + 3 files changed, 56 insertions(+) create mode 100644 .github/workflows/memcheck.yml create mode 100644 tests/valgrind_suppress.txt diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml new file mode 100644 index 00000000..04dff019 --- /dev/null +++ b/.github/workflows/memcheck.yml @@ -0,0 +1,46 @@ +name: memcheck + +on: + pull_request: + branches: [ $default-branch, master ] + +permissions: write-all + +env: + # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) + BUILD_TYPE: Release + VTK_VERSION_MAJOR: 9 + VTK_VERSION_MINOR: 2 + VTK_VERSION_PATCH: 6 + +jobs: + build: + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-22.04] + + steps: + - uses: actions/checkout@v4 + + - name: Install valgrind + run: | + sudo apt-get -qq update + sudo apt-get -qq -y install valgrind + + - name: Install VTK + run: | + sudo apt-get -qq update + sudo apt-get -qq -y install libvtk9-dev + + - name: Configure CMake + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DBUILD_TESTING=ON + + - name: Build + id: build + run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Test + working-directory: ${{github.workspace}}/build + # We are just testing in Linux + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure diff --git a/CMakeLists.txt b/CMakeLists.txt index bbe2536d..1086a6f4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -141,6 +141,15 @@ if(${MOORDYN_FASTMATH}) endif() endif() +find_program(MEMORYCHECK_COMMAND valgrind) +if(NOT ${MEMORYCHECK_COMMAND}) + message(WARNING "valgrind is not found, you will not be able to run memchecks") +else(NOT ${MEMORYCHECK_COMMAND}) + set(MEMORYCHECK_SUPPRESSIONS_FILE + "${PROJECT_SOURCE_DIR}/tests/valgrind_suppress.txt") +endif() + + # Compile the library add_subdirectory(source) # And the eventual wrappers diff --git a/tests/valgrind_suppress.txt b/tests/valgrind_suppress.txt new file mode 100644 index 00000000..8d1c8b69 --- /dev/null +++ b/tests/valgrind_suppress.txt @@ -0,0 +1 @@ + From 8a03a81b6be1e7ce8264442c94469ba4f33aba09 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:22:43 +0200 Subject: [PATCH 070/145] Typo checking if valgrind was found --- CMakeLists.txt | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1086a6f4..1c875c2b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -142,11 +142,10 @@ if(${MOORDYN_FASTMATH}) endif() find_program(MEMORYCHECK_COMMAND valgrind) -if(NOT ${MEMORYCHECK_COMMAND}) +if(NOT MEMORYCHECK_COMMAND) message(WARNING "valgrind is not found, you will not be able to run memchecks") else(NOT ${MEMORYCHECK_COMMAND}) - set(MEMORYCHECK_SUPPRESSIONS_FILE - "${PROJECT_SOURCE_DIR}/tests/valgrind_suppress.txt") + set(MEMORYCHECK_SUPPRESSIONS_FILE "${PROJECT_SOURCE_DIR}/tests/valgrind_suppress.txt") endif() From 7260f82770f8dce89217a65deb4b88f1ace7e385 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:23:46 +0200 Subject: [PATCH 071/145] Suppress some system mem leaks --- tests/valgrind_suppress.txt | 27 ++++++++++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/tests/valgrind_suppress.txt b/tests/valgrind_suppress.txt index 8d1c8b69..780290b8 100644 --- a/tests/valgrind_suppress.txt +++ b/tests/valgrind_suppress.txt @@ -1 +1,26 @@ - +{ + + Memcheck:Leak + match-leak-kinds: reachable + fun:malloc + fun:gomp_malloc + fun:gomp_init_num_threads + fun:initialize_env + fun:call_init + fun:call_init + fun:_dl_init + obj:/usr/lib/ld-linux-x86-64.so.2 +} +{ + + Memcheck:Leak + match-leak-kinds: reachable + fun:calloc + fun:gomp_malloc_cleared + fun:add_initial_icv_to_list + fun:initialize_env + fun:call_init + fun:call_init + fun:_dl_init + obj:/usr/lib/ld-linux-x86-64.so.2 +} From 91c26e9b1b815177c67df9b0438f79498e1f1582 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:24:16 +0200 Subject: [PATCH 072/145] Release the logger when the MoorDyn system creation fails --- source/MoorDyn2.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index a94d3da6..c95ca509 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -139,6 +139,9 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) waves = std::make_shared(_log); const moordyn::error_id err = ReadInFile(); + if (err != MOORDYN_SUCCESS) { + delete GetLogger(); + } MOORDYN_THROW(err, "Exception while reading the input file"); LOGDBG << "MoorDyn is expecting " << NCoupledDOF() @@ -178,7 +181,7 @@ moordyn::MoorDyn::~MoorDyn() for (auto obj : LineList) delete obj; - delete _log; + delete GetLogger(); } moordyn::error_id From ca1a3488a5b70e464adaa6031669d64617e6083c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:41:12 +0200 Subject: [PATCH 073/145] RelWithDebInfo for running mem checks --- .github/workflows/memcheck.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 04dff019..5a91802b 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -8,7 +8,7 @@ permissions: write-all env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) - BUILD_TYPE: Release + BUILD_TYPE: RelWithDebInfo VTK_VERSION_MAJOR: 9 VTK_VERSION_MINOR: 2 VTK_VERSION_PATCH: 6 From eaaf847e2feb9323f1c623a5c107c6720660de06 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:44:42 +0200 Subject: [PATCH 074/145] Run several memchecks simutaneously --- .github/workflows/memcheck.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 5a91802b..1958a6ca 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -9,6 +9,7 @@ permissions: write-all env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) BUILD_TYPE: RelWithDebInfo + PROCESSES: 4 VTK_VERSION_MAJOR: 9 VTK_VERSION_MINOR: 2 VTK_VERSION_PATCH: 6 @@ -43,4 +44,4 @@ jobs: - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux - run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} From b7d3890a5ddf16dafcd8968a42d27159c1eda2c4 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 09:50:28 +0200 Subject: [PATCH 075/145] Mem leak on test --- tests/conveying_fluid.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/tests/conveying_fluid.cpp b/tests/conveying_fluid.cpp index bca4982f..a0733873 100644 --- a/tests/conveying_fluid.cpp +++ b/tests/conveying_fluid.cpp @@ -82,6 +82,7 @@ TEST_CASE("Pipe buckling while conveying fluid") pin[i] = P; REQUIRE(MoorDyn_SetLinePressBend(line, 1) == MOORDYN_SUCCESS); REQUIRE(MoorDyn_SetLinePressInt(line, pin) == MOORDYN_SUCCESS); + free(pin); REQUIRE(MoorDyn_Init(system, NULL, NULL) == MOORDYN_SUCCESS); From fc3e6563683f8cbd9e8b405f28d5c5eab582ad14 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 10:17:44 +0200 Subject: [PATCH 076/145] Release the previous time integrator before setting the new one --- .github/workflows/memcheck.yml | 2 +- source/MoorDyn2.hpp | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 1958a6ca..88b92ee6 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -44,4 +44,4 @@ jobs: - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux - run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure --timeout 7200 -j ${{env.PROCESSES}} diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index 88e4bb08..4c331f77 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -369,6 +369,7 @@ class MoorDyn final : public io::IO * @return The time integrator */ inline void SetTimeScheme(TimeScheme* tscheme) { + if (_t_integrator) delete _t_integrator; _t_integrator = tscheme; _t_integrator->SetGround(GroundBody); for (auto obj : BodyList) From 263adeab8042c259e16a304ad678d234d8a77c16 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 10:25:36 +0200 Subject: [PATCH 077/145] Uninitialized error values when no IC is computed (e.g. TmaxIC=0.0) --- source/MoorDyn2.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index c95ca509..ef06b81a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -345,7 +345,8 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) real t = 0; real error_prev = (std::numeric_limits::max)(); - real error0, error; + real error = (std::numeric_limits::max)(); + real error0 = error; // The function is enclosed in parenthesis to avoid Windows min() and max() // macros break it // See From e04362f3a8e28726b421055065910e47fe244e4d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 11:40:27 +0200 Subject: [PATCH 078/145] Unintialized accelerations --- source/Rod.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/source/Rod.cpp b/source/Rod.cpp index 5be494cf..6d868602 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -143,6 +143,9 @@ Rod::setup(int number_in, // ------------------------- set starting kinematics // ------------------------- + // Initialize the accelerations to avoid border cases, like Pinned rods + // reading the linear acceleration without ssetting it + acc6 = vec6::Zero(); // set Rod positions if applicable if (type == FREE) { // For an independent rod, set the position right off the bat @@ -671,6 +674,7 @@ Rod::getStateDeriv() // of the matrix. See // https://eigen.tuxfamily.org/dox/group__TutorialLinearAlgebra.html const mat M_out3 = M_out6(Eigen::seqN(3, 3), Eigen::seqN(3, 3)); + acc6(Eigen::seqN(0, 3)) = vec::Zero(); acc6(Eigen::seqN(3, 3)) = M_out3.inverse() * Fnet_out3; // dxdt = V (velocities) From fb73f9365c6819d546089a2bb2d6fba58af1d15e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 11:49:10 +0200 Subject: [PATCH 079/145] Conn -> Point --- tests/Mooring/BodiesAndRods.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/Mooring/BodiesAndRods.dat b/tests/Mooring/BodiesAndRods.dat index 8beb781f..e468c0dc 100644 --- a/tests/Mooring/BodiesAndRods.dat +++ b/tests/Mooring/BodiesAndRods.dat @@ -52,5 +52,5 @@ Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs 0.01 dtIC - Time lapse between convergence tests (s) ------------------------------ OUTPUTS ----------------------------------------------------- FairTen1 FairTen2 FairTen3 -Con2px Con2py Con2pz +Point2px Point2py Point2pz --------------------------- need this line ------------------------------------------------- From cc8269ce820c3e1e39ba69f3b30579f413f19e73 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 11:54:18 +0200 Subject: [PATCH 080/145] Exclude very long tests from mem check --- .github/workflows/memcheck.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 88b92ee6..d93c8cbc 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -44,4 +44,4 @@ jobs: - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux - run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure --timeout 7200 -j ${{env.PROCESSES}} + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} -E "(time_schemes|seafloor)" From 44cb75c35b279f1cab3663f47f00fcca1afb099d Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 11:58:20 +0200 Subject: [PATCH 081/145] Give a shot to the memcheck on github --- .github/workflows/memcheck.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index d93c8cbc..b473537c 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -1,6 +1,8 @@ name: memcheck on: + push: + branches: [ cfl ] pull_request: branches: [ $default-branch, master ] From 31498fbe1505672f379f5c03034debcbb508e6d5 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 12:00:14 +0200 Subject: [PATCH 082/145] Renamed job --- .github/workflows/memcheck.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index b473537c..c2c55c8c 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -17,7 +17,7 @@ env: VTK_VERSION_PATCH: 6 jobs: - build: + memcheck: runs-on: ${{ matrix.os }} strategy: matrix: From 11a7bfb0536be8b91ecc7d9d6e998c9a1991f5ab Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 12:33:54 +0200 Subject: [PATCH 083/145] Disable more long tests --- .github/workflows/memcheck.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index c2c55c8c..1df1c6f5 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -46,4 +46,4 @@ jobs: - name: Test working-directory: ${{github.workspace}}/build # We are just testing in Linux - run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} -E "(time_schemes|seafloor)" + run: ctest -C ${{env.BUILD_TYPE}} -T memcheck --output-on-failure -j ${{env.PROCESSES}} -E "(seafloor|time_schemes|wavekin|wilson)" From afff2665602a7483e5b9672e54875e1f6341cab7 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 12:35:30 +0200 Subject: [PATCH 084/145] Mem leak on test --- tests/io.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/tests/io.cpp b/tests/io.cpp index 1418d909..a36a69ec 100644 --- a/tests/io.cpp +++ b/tests/io.cpp @@ -499,6 +499,7 @@ restore() MoorDyn_Close(system); return false; } + free(backup); double f2[9]; t = 0.0; err = MoorDyn_Step(system, x, dx, f2, &t, &dt); From 0c4c7f428eef0a28a86aad113e26c125ca8a3fc3 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 12:37:19 +0200 Subject: [PATCH 085/145] Do not mem check VTK (a lot of false positives) --- .github/workflows/memcheck.yml | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 1df1c6f5..5b4e922d 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -12,9 +12,6 @@ env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) BUILD_TYPE: RelWithDebInfo PROCESSES: 4 - VTK_VERSION_MAJOR: 9 - VTK_VERSION_MINOR: 2 - VTK_VERSION_PATCH: 6 jobs: memcheck: @@ -31,13 +28,8 @@ jobs: sudo apt-get -qq update sudo apt-get -qq -y install valgrind - - name: Install VTK - run: | - sudo apt-get -qq update - sudo apt-get -qq -y install libvtk9-dev - - name: Configure CMake - run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=ON -DBUILD_TESTING=ON + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON -DEXTERNAL_EIGEN:BOOL=OFF -DPYTHON_WRAPPER:BOOL=OFF -DRUST_WRAPPER:BOOL=OFF -DUSE_VTK=OFF -DBUILD_TESTING=ON - name: Build id: build From 16d7d9e62c4a64ff470f1ee3fb4bdd5adca18d0c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 11 Jun 2024 12:51:59 +0200 Subject: [PATCH 086/145] Restrict the mem checks to the pre-releases again --- .github/workflows/memcheck.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/memcheck.yml b/.github/workflows/memcheck.yml index 5b4e922d..77bc9670 100644 --- a/.github/workflows/memcheck.yml +++ b/.github/workflows/memcheck.yml @@ -1,8 +1,6 @@ name: memcheck on: - push: - branches: [ cfl ] pull_request: branches: [ $default-branch, master ] From 29395c9f4dac2bc7bd50a29a98874547174bebd5 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 12 Jun 2024 10:24:32 +0200 Subject: [PATCH 087/145] Increase the stationary solution convergence verbosity --- source/MoorDyn2.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index ef06b81a..262b1f5a 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -367,6 +367,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) t_integrator.AddLine(obj); t_integrator.SetCFL((std::min)(cfl, 1.0)); t_integrator.Init(); + auto n_states = t_integrator.NStates(); while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt // Integrate one ICD timestep (ICdt) real t_target = ICdt; @@ -403,12 +404,12 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) break; error_prev = error; - LOGDBG << "Stationary solution t = " << t << "s, error change = " - << 100.0 * error_deriv << "% \r"; + LOGDBG << "Stationary solution t = " << t << "s, " + << "error avg = " << error / n_states << " m/s2, " + << "error change = " << 100.0 * error_deriv << "% \r"; } if (!skip_ic) { - auto n_states = t_integrator.NStates(); LOGMSG << "Remaining error after " << t << " s = " << error / n_states << " m/s2" << endl; LOGMSG << "Best score at " << best_score_t From deb6e9041adbc302b4e85c8674c96f7d3fb6b9e0 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 12 Jun 2024 10:24:55 +0200 Subject: [PATCH 088/145] Lowe and Langley (OMAE-2006) validation --- tests/CMakeLists.txt | 1 + .../Mooring/lowe_and_langley_2006/Case 1.csv | 779 +++++++++++++++++ .../Mooring/lowe_and_langley_2006/Case 2.csv | 791 ++++++++++++++++++ .../Mooring/lowe_and_langley_2006/Case 3.csv | 775 +++++++++++++++++ .../Mooring/lowe_and_langley_2006/Case 4.csv | 297 +++++++ .../Mooring/lowe_and_langley_2006/Case 5.csv | 292 +++++++ .../Mooring/lowe_and_langley_2006/Case 6.csv | 299 +++++++ tests/Mooring/lowe_and_langley_2006/line.txt | 30 + tests/lowe_and_langley_2006.cpp | 321 +++++++ 9 files changed, 3585 insertions(+) create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 1.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 2.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 3.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 4.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 5.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/Case 6.csv create mode 100644 tests/Mooring/lowe_and_langley_2006/line.txt create mode 100644 tests/lowe_and_langley_2006.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index fa1fe884..392cdc05 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -45,6 +45,7 @@ set(CATCH2_TESTS conveying_fluid polyester quasi_static_chain + lowe_and_langley_2006 local_euler beuler midpoint diff --git a/tests/Mooring/lowe_and_langley_2006/Case 1.csv b/tests/Mooring/lowe_and_langley_2006/Case 1.csv new file mode 100644 index 00000000..f20ab9bf --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 1.csv @@ -0,0 +1,779 @@ +0.00000, 49.72775 +0.10000, 49.66335 +0.20000, 49.50234 +0.30000, 49.11593 +0.40000, 49.11593 +0.50000, 48.95492 +0.60000, 48.79391 +0.70000, 48.47190 +0.80000, 48.27869 +0.90000, 48.18208 +1.00000, 47.82787 +1.10000, 47.82787 +1.20000, 47.69906 +1.30000, 47.53806 +1.40000, 47.24824 +1.50000, 47.05504 +1.60000, 46.89403 +1.70000, 46.60422 +1.80000, 46.60422 +1.90000, 46.21780 +2.00000, 45.76698 +2.10000, 45.67037 +2.20000, 45.38056 +2.30000, 45.15515 +2.40000, 44.96194 +2.50000, 44.96194 +2.60000, 44.80094 +2.70000, 44.57553 +2.80000, 44.28571 +2.90000, 44.18911 +3.00000, 43.96370 +3.10000, 43.96370 +3.20000, 43.77049 +3.30000, 43.51288 +3.40000, 43.35187 +3.50000, 43.19087 +3.60000, 42.99766 +3.70000, 42.83665 +3.80000, 42.83665 +3.90000, 42.67564 +4.00000, 42.57904 +4.10000, 42.41803 +4.20000, 42.28923 +4.30000, 42.22482 +4.40000, 42.03162 +4.50000, 42.03162 +4.60000, 41.96721 +4.70000, 41.83841 +4.80000, 41.74180 +4.90000, 41.67740 +5.00000, 41.64520 +5.10000, 41.61300 +5.20000, 41.61300 +5.30000, 41.54859 +5.40000, 41.51639 +5.50000, 41.51639 +5.60000, 41.48419 +5.70000, 41.48419 +5.80000, 41.48419 +5.90000, 41.48419 +6.00000, 41.48419 +6.10000, 41.51639 +6.20000, 41.51639 +6.30000, 41.58080 +6.40000, 41.64520 +6.50000, 41.67740 +6.60000, 41.67740 +6.70000, 41.70960 +6.80000, 41.77400 +6.90000, 41.87061 +7.00000, 41.90281 +7.10000, 41.90281 +7.20000, 41.96721 +7.30000, 41.96721 +7.40000, 42.06382 +7.50000, 42.12822 +7.60000, 42.22482 +7.70000, 42.32143 +7.80000, 42.41803 +7.90000, 42.54684 +8.00000, 42.54684 +8.10000, 42.51464 +8.30000, 42.77225 +8.40000, 42.90105 +8.50000, 42.96546 +8.60000, 42.96546 +8.70000, 43.12646 +8.80000, 43.22307 +8.90000, 43.28747 +9.00000, 43.38407 +9.10000, 43.54508 +9.20000, 43.67389 +9.30000, 43.67389 +9.40000, 43.70609 +9.50000, 43.96370 +9.60000, 44.02810 +9.70000, 44.18911 +9.80000, 44.31792 +9.90000, 44.44672 +10.00000, 44.44672 +10.10000, 44.63993 +10.20000, 44.73653 +10.30000, 44.83314 +10.40000, 44.99415 +10.50000, 45.12295 +10.60000, 45.25176 +10.70000, 45.25176 +10.80000, 45.38056 +10.90000, 45.50937 +11.00000, 45.60597 +11.10000, 45.73478 +11.20000, 45.86358 +11.30000, 45.89578 +11.40000, 45.89578 +11.50000, 46.02459 +11.60000, 46.18560 +11.70000, 46.31440 +11.80000, 46.41101 +11.90000, 46.44321 +12.00000, 46.60422 +12.10000, 46.60422 +12.20000, 46.63642 +12.30000, 46.70082 +12.40000, 46.73302 +12.50000, 46.82963 +12.60000, 46.86183 +12.70000, 46.92623 +12.80000, 46.92623 +12.90000, 46.95843 +13.00000, 46.99063 +13.10000, 47.02283 +13.20000, 47.02283 +13.30000, 47.02283 +13.40000, 47.02283 +13.50000, 47.02283 +13.60000, 47.02283 +13.70000, 47.02283 +13.80000, 47.02283 +13.90000, 47.02283 +14.00000, 46.99063 +14.10000, 46.95843 +14.20000, 46.95843 +14.30000, 46.92623 +14.40000, 46.89403 +14.50000, 46.86183 +14.60000, 46.86183 +14.70000, 46.79742 +14.80000, 46.79742 +14.90000, 46.73302 +15.00000, 46.70082 +15.20000, 46.66862 +15.30000, 46.63642 +15.40000, 46.53981 +15.50000, 46.53981 +15.60000, 46.50761 +15.70000, 46.47541 +15.80000, 46.47541 +16.10000, 46.31440 +16.20000, 46.31440 +16.30000, 46.31440 +16.40000, 46.31440 +16.50000, 46.31440 +16.60000, 46.31440 +16.70000, 46.31440 +16.80000, 46.31440 +16.90000, 46.31440 +17.00000, 46.31440 +17.10000, 46.31440 +17.20000, 46.34660 +17.30000, 46.34660 +17.40000, 46.37881 +17.50000, 46.47541 +17.60000, 46.47541 +17.70000, 46.47541 +17.80000, 46.47541 +17.90000, 46.60422 +18.00000, 46.60422 +18.10000, 46.63642 +18.20000, 46.73302 +18.30000, 46.73302 +18.40000, 46.82963 +18.50000, 46.95843 +18.60000, 47.02283 +18.70000, 47.18384 +18.80000, 47.18384 +18.90000, 47.24824 +19.00000, 47.24824 +19.10000, 47.37705 +19.20000, 47.50585 +19.30000, 47.60246 +19.40000, 47.66686 +19.50000, 47.89227 +19.60000, 47.98888 +19.70000, 47.98888 +19.80000, 48.05328 +19.90000, 48.31089 +20.00000, 48.37529 +20.10000, 48.50410 +20.20000, 48.63290 +20.30000, 48.63290 +20.40000, 48.82611 +20.50000, 49.01932 +20.60000, 49.14813 +20.70000, 49.24473 +20.80000, 49.40574 +20.90000, 49.50234 +21.00000, 49.50234 +21.10000, 49.72775 +21.20000, 49.82436 +21.30000, 50.01756 +21.40000, 50.11417 +21.50000, 50.33958 +21.60000, 50.50059 +21.70000, 50.50059 +21.80000, 50.56499 +21.90000, 50.69379 +22.00000, 50.75820 +22.10000, 50.95141 +22.20000, 51.01581 +22.30000, 51.14461 +22.40000, 51.14461 +22.50000, 51.30562 +22.60000, 51.43443 +22.70000, 51.46663 +22.80000, 51.59543 +22.90000, 51.69204 +23.00000, 51.72424 +23.10000, 51.72424 +23.20000, 51.85304 +23.30000, 51.94965 +23.40000, 51.98185 +23.50000, 52.07845 +23.60000, 52.11066 +23.70000, 52.20726 +23.80000, 52.20726 +23.90000, 52.20726 +24.00000, 52.20726 +24.10000, 52.23946 +24.20000, 52.23946 +24.30000, 52.23946 +24.40000, 52.23946 +24.50000, 52.23946 +24.60000, 52.23946 +24.70000, 52.23946 +24.80000, 52.20726 +24.90000, 52.17506 +25.00000, 52.14286 +25.10000, 52.11066 +25.20000, 52.11066 +25.30000, 52.04625 +25.40000, 51.94965 +25.50000, 51.85304 +25.60000, 51.78864 +25.70000, 51.59543 +25.80000, 51.49883 +25.90000, 51.49883 +26.00000, 51.40222 +26.10000, 51.27342 +26.20000, 51.20902 +26.30000, 51.01581 +26.40000, 50.95141 +26.50000, 50.95141 +26.60000, 50.75820 +26.70000, 50.46838 +26.80000, 50.30738 +26.90000, 50.14637 +27.00000, 49.88876 +27.10000, 49.72775 +27.20000, 49.72775 +27.30000, 49.66335 +27.40000, 49.30913 +27.50000, 49.24473 +27.60000, 48.98712 +27.70000, 48.76171 +27.80000, 48.53630 +27.90000, 48.53630 +28.00000, 48.18208 +28.10000, 47.95667 +28.20000, 47.76347 +28.30000, 47.53806 +28.40000, 47.31265 +28.50000, 47.11944 +28.60000, 47.11944 +28.70000, 47.02283 +28.80000, 46.73302 +28.90000, 46.34660 +29.00000, 46.12119 +29.10000, 45.89578 +29.20000, 45.54157 +29.30000, 45.54157 +29.40000, 45.38056 +29.50000, 45.12295 +29.60000, 44.92974 +29.70000, 44.70433 +29.80000, 44.47892 +29.90000, 44.22131 +30.00000, 44.22131 +30.10000, 43.99590 +30.20000, 43.80269 +30.30000, 43.60948 +30.40000, 43.44848 +30.50000, 43.22307 +30.60000, 43.12646 +30.70000, 43.12646 +30.80000, 42.99766 +30.90000, 42.77225 +31.00000, 42.61124 +31.10000, 42.51464 +31.20000, 42.32143 +31.30000, 42.22482 +31.40000, 42.22482 +31.50000, 42.16042 +31.60000, 41.99941 +31.70000, 41.93501 +31.80000, 41.80621 +31.90000, 41.77400 +32.00000, 41.77400 +32.10000, 41.74180 +32.20000, 41.64520 +32.30000, 41.64520 +32.40000, 41.61300 +32.50000, 41.58080 +32.60000, 41.58080 +32.70000, 41.58080 +32.80000, 41.58080 +32.90000, 41.58080 +33.00000, 41.58080 +33.10000, 41.58080 +33.20000, 41.58080 +33.30000, 41.64520 +33.40000, 41.64520 +33.50000, 41.64520 +33.60000, 41.67740 +33.70000, 41.70960 +33.80000, 41.77400 +33.90000, 41.83841 +34.00000, 41.87061 +34.10000, 41.87061 +34.20000, 41.96721 +34.30000, 42.03162 +34.40000, 42.09602 +34.50000, 42.16042 +34.60000, 42.28923 +34.70000, 42.35363 +34.80000, 42.35363 +34.90000, 42.41803 +35.00000, 42.54684 +35.10000, 42.48244 +35.30000, 42.90105 +35.40000, 42.90105 +35.50000, 42.90105 +35.60000, 43.02986 +35.70000, 43.09426 +35.80000, 43.28747 +35.90000, 43.35187 +36.00000, 43.48068 +36.10000, 43.64169 +36.20000, 43.64169 +36.30000, 43.77049 +36.40000, 43.89930 +36.50000, 43.99590 +36.60000, 44.06030 +36.70000, 44.18911 +36.80000, 44.28571 +36.90000, 44.28571 +37.00000, 44.44672 +37.10000, 44.60773 +37.20000, 44.76874 +37.30000, 44.89754 +37.40000, 45.02635 +37.50000, 45.15515 +37.60000, 45.15515 +37.70000, 45.18735 +37.80000, 45.31616 +37.90000, 45.50937 +38.00000, 45.63817 +38.10000, 45.79918 +38.20000, 45.79918 +38.30000, 45.86358 +38.40000, 46.05679 +38.50000, 46.08899 +38.60000, 46.18560 +38.70000, 46.31440 +38.80000, 46.41101 +38.90000, 46.41101 +39.00000, 46.47541 +39.10000, 46.53981 +39.20000, 46.63642 +39.30000, 46.70082 +39.40000, 46.73302 +39.50000, 46.82963 +39.60000, 46.82963 +39.70000, 46.89403 +39.80000, 46.95843 +39.90000, 46.99063 +40.00000, 47.02283 +40.10000, 47.02283 +40.20000, 47.02283 +40.30000, 47.02283 +40.40000, 47.02283 +40.50000, 47.02283 +40.60000, 47.02283 +40.70000, 47.02283 +40.80000, 47.02283 +40.90000, 47.02283 +41.00000, 47.02283 +41.10000, 47.02283 +41.20000, 46.95843 +41.30000, 46.92623 +41.40000, 46.89403 +41.50000, 46.86183 +41.60000, 46.79742 +41.70000, 46.79742 +41.80000, 46.70082 +42.30000, 46.63642 +42.40000, 46.63642 +42.50000, 46.53981 +42.60000, 46.47541 +42.70000, 46.47541 +42.80000, 46.44321 +43.20000, 46.34660 +43.30000, 46.34660 +43.40000, 46.31440 +43.50000, 46.31440 +43.60000, 46.31440 +43.70000, 46.31440 +43.80000, 46.31440 +43.90000, 46.31440 +44.00000, 46.31440 +44.10000, 46.31440 +44.20000, 46.34660 +44.30000, 46.34660 +44.40000, 46.34660 +44.50000, 46.34660 +44.60000, 46.44321 +44.70000, 46.47541 +44.80000, 46.50761 +44.90000, 46.53981 +45.00000, 46.63642 +45.10000, 46.63642 +45.20000, 46.66862 +45.30000, 46.73302 +45.40000, 46.79742 +45.50000, 46.95843 +45.60000, 46.99063 +45.70000, 47.08724 +45.80000, 47.08724 +45.90000, 47.24824 +46.00000, 47.31265 +46.10000, 47.34485 +46.20000, 47.47365 +46.30000, 47.57026 +46.40000, 47.69906 +46.50000, 47.69906 +46.60000, 47.76347 +46.70000, 47.98888 +46.80000, 48.14988 +46.90000, 48.31089 +47.00000, 48.37529 +47.10000, 48.50410 +47.20000, 48.50410 +47.30000, 48.63290 +47.40000, 48.82611 +47.50000, 48.95492 +47.60000, 49.11593 +47.70000, 49.24473 +47.80000, 49.43794 +47.90000, 49.43794 +48.00000, 49.63115 +48.10000, 49.72775 +48.20000, 49.88876 +48.30000, 49.95316 +48.40000, 50.17857 +48.50000, 50.24297 +48.60000, 50.24297 +48.70000, 50.40398 +48.80000, 50.59719 +48.90000, 50.72600 +49.00000, 50.82260 +49.10000, 50.95141 +49.20000, 51.11241 +49.30000, 51.11241 +49.40000, 51.14461 +49.50000, 51.24122 +49.60000, 51.40222 +49.70000, 51.46663 +49.80000, 51.56323 +49.90000, 51.56323 +50.00000, 51.72424 +50.10000, 51.78864 +50.20000, 51.88525 +50.30000, 51.94965 +50.40000, 52.01405 +50.50000, 52.04625 +50.60000, 52.04625 +50.70000, 52.07845 +50.80000, 52.11066 +50.90000, 52.20726 +51.00000, 52.20726 +51.10000, 52.23946 +51.20000, 52.23946 +51.30000, 52.23946 +51.40000, 52.23946 +51.50000, 52.23946 +51.60000, 52.23946 +51.70000, 52.23946 +51.80000, 52.23946 +51.90000, 52.20726 +52.00000, 52.20726 +52.10000, 52.14286 +52.20000, 52.07845 +52.30000, 52.04625 +52.40000, 51.98185 +52.50000, 51.91745 +52.60000, 51.75644 +52.70000, 51.75644 +52.80000, 51.72424 +52.90000, 51.59543 +53.00000, 51.43443 +53.10000, 51.27342 +53.20000, 51.14461 +53.30000, 50.95141 +53.40000, 50.95141 +53.50000, 50.82260 +53.60000, 50.75820 +53.70000, 50.56499 +53.80000, 50.40398 +53.90000, 50.17857 +54.00000, 50.01756 +54.10000, 50.01756 +54.20000, 49.82436 +54.30000, 49.53454 +54.40000, 49.37354 +54.50000, 49.18033 +54.60000, 48.95492 +54.70000, 48.72951 +54.80000, 48.72951 +54.90000, 48.47190 +55.00000, 48.21429 +55.10000, 47.98888 +55.20000, 47.79567 +55.30000, 47.53806 +55.40000, 47.53806 +55.50000, 47.37705 +55.60000, 47.11944 +55.70000, 46.92623 +55.80000, 46.79742 +55.90000, 46.41101 +56.00000, 46.15340 +56.10000, 46.15340 +56.20000, 45.86358 +56.30000, 45.41276 +56.40000, 45.25176 +56.50000, 45.09075 +56.60000, 44.89754 +56.70000, 44.76874 +56.80000, 44.76874 +56.90000, 44.44672 +57.00000, 44.35012 +57.10000, 44.15691 +57.20000, 43.80269 +57.30000, 43.64169 +57.40000, 43.44848 +57.50000, 43.44848 +57.60000, 43.19087 +57.70000, 43.02986 +57.80000, 42.93326 +57.90000, 42.77225 +58.00000, 42.70785 +58.10000, 42.54684 +58.20000, 42.54684 +58.30000, 42.41803 +58.40000, 42.32143 +58.50000, 42.09602 +58.60000, 41.99941 +58.70000, 41.96721 +58.80000, 41.83841 +58.90000, 41.83841 +59.00000, 41.77400 +59.10000, 41.70960 +59.20000, 41.64520 +59.30000, 41.64520 +59.40000, 41.64520 +59.50000, 41.58080 +59.60000, 41.58080 +59.70000, 41.58080 +59.80000, 41.58080 +59.90000, 41.58080 +60.00000, 41.58080 +60.10000, 41.58080 +60.20000, 41.58080 +60.30000, 41.58080 +60.40000, 41.64520 +60.50000, 41.67740 +60.60000, 41.70960 +60.70000, 41.77400 +60.80000, 41.83841 +60.90000, 41.83841 +61.00000, 41.87061 +61.10000, 41.90281 +61.20000, 41.90281 +61.30000, 42.03162 +61.40000, 42.06382 +61.50000, 42.19262 +61.60000, 42.19262 +61.70000, 42.28923 +61.80000, 42.35363 +61.90000, 42.45023 +62.00000, 42.48244 +62.10000, 42.57904 +62.40000, 42.93326 +62.50000, 42.86885 +62.60000, 42.99766 +62.70000, 43.19087 +62.80000, 43.28747 +62.90000, 43.35187 +63.00000, 43.35187 +63.10000, 43.48068 +63.20000, 43.57728 +63.30000, 43.73829 +63.40000, 43.86710 +63.50000, 43.99590 +63.60000, 44.09251 +63.70000, 44.09251 +63.80000, 44.22131 +63.90000, 44.35012 +64.00000, 44.47892 +64.10000, 44.57553 +64.20000, 44.67213 +64.30000, 44.96194 +64.40000, 44.96194 +64.50000, 44.99415 +64.60000, 45.12295 +64.70000, 45.28396 +64.80000, 45.41276 +64.90000, 45.50937 +65.00000, 45.67037 +65.10000, 45.67037 +65.20000, 45.76698 +65.30000, 45.89578 +65.40000, 45.92799 +65.50000, 46.08899 +65.60000, 46.18560 +65.70000, 46.31440 +65.80000, 46.31440 +65.90000, 46.37881 +66.00000, 46.50761 +66.10000, 46.57201 +66.20000, 46.60422 +66.30000, 46.73302 +66.40000, 46.73302 +66.50000, 46.73302 +66.60000, 46.79742 +66.70000, 46.86183 +66.80000, 46.95843 +66.90000, 46.99063 +67.00000, 47.02283 +67.10000, 47.02283 +67.20000, 47.02283 +67.30000, 47.02283 +67.40000, 47.02283 +67.50000, 47.02283 +67.60000, 47.02283 +67.70000, 47.02283 +67.80000, 47.02283 +67.90000, 47.02283 +68.00000, 47.02283 +68.10000, 46.99063 +68.20000, 46.95843 +68.30000, 46.89403 +68.40000, 46.89403 +68.50000, 46.89403 +68.60000, 46.86183 +68.70000, 46.86183 +69.40000, 46.60422 +69.50000, 46.57201 +69.60000, 46.53981 +69.70000, 46.47541 +69.80000, 46.47541 +69.90000, 46.47541 +70.10000, 46.28220 +70.20000, 46.31440 +70.30000, 46.31440 +70.40000, 46.31440 +70.50000, 46.31440 +70.60000, 46.31440 +70.70000, 46.31440 +70.80000, 46.31440 +70.90000, 46.31440 +71.00000, 46.31440 +71.10000, 46.31440 +71.20000, 46.31440 +71.30000, 46.31440 +71.40000, 46.34660 +71.50000, 46.34660 +71.60000, 46.41101 +71.70000, 46.47541 +71.80000, 46.50761 +71.90000, 46.53981 +72.00000, 46.53981 +72.10000, 46.53981 +72.20000, 46.70082 +72.30000, 46.70082 +72.40000, 46.79742 +72.50000, 46.89403 +72.60000, 46.89403 +72.70000, 46.99063 +72.80000, 47.08724 +72.90000, 47.15164 +73.00000, 47.28044 +73.10000, 47.40925 +73.20000, 47.50585 +73.30000, 47.50585 +73.40000, 47.60246 +73.50000, 47.69906 +73.60000, 47.82787 +73.70000, 48.02108 +73.80000, 48.14988 +73.90000, 48.31089 +74.00000, 48.31089 +74.10000, 48.37529 +74.20000, 48.50410 +74.30000, 48.69731 +74.40000, 48.82611 +74.50000, 49.01932 +74.60000, 49.05152 +74.70000, 49.05152 +74.80000, 49.30913 +74.90000, 49.37354 +75.00000, 49.53454 +75.10000, 49.75995 +75.20000, 49.88876 +75.30000, 49.98536 +75.40000, 49.98536 +75.50000, 50.17857 +75.60000, 50.30738 +75.70000, 50.37178 +75.80000, 50.53279 +75.90000, 50.69379 +76.00000, 50.82260 +76.10000, 50.82260 +76.20000, 50.91920 +76.30000, 51.04801 +76.40000, 51.24122 +76.50000, 51.33782 +76.60000, 51.40222 +76.70000, 51.53103 +76.80000, 51.53103 +76.90000, 51.59543 +77.00000, 51.72424 +77.10000, 51.75644 +77.20000, 51.82084 +77.30000, 51.91745 +77.40000, 52.01405 +77.50000, 52.01405 +77.60000, 52.04625 +77.70000, 52.07845 +77.80000, 52.14286 +77.90000, 52.20726 +78.00000, 52.20726 +78.10000, 52.23946 +78.20000, 52.23946 +78.30000, 52.23946 +78.40000, 52.23946 +78.50000, 52.23946 +78.60000, 52.23946 +78.70000, 52.23946 +78.80000, 52.23946 +78.90000, 52.23946 +79.00000, 52.20726 +79.10000, 52.20726 +79.20000, 52.11066 +79.30000, 52.04625 +79.40000, 51.98185 +79.50000, 51.98185 +79.60000, 51.82084 +79.70000, 51.75644 +79.80000, 51.62763 +79.90000, 51.65984 diff --git a/tests/Mooring/lowe_and_langley_2006/Case 2.csv b/tests/Mooring/lowe_and_langley_2006/Case 2.csv new file mode 100644 index 00000000..e0486faf --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 2.csv @@ -0,0 +1,791 @@ +0.10000, 48.18208 +0.20000, 48.08548 +0.30000, 47.92447 +0.40000, 47.92447 +0.50000, 47.79567 +0.60000, 47.69906 +0.70000, 47.47365 +0.80000, 47.37705 +0.90000, 47.31265 +1.00000, 47.15164 +1.10000, 47.15164 +1.20000, 47.05504 +1.30000, 46.82963 +1.40000, 46.76522 +1.50000, 46.53981 +1.60000, 46.41101 +1.70000, 46.34660 +1.80000, 46.34660 +1.90000, 46.18560 +2.00000, 46.08899 +2.10000, 45.92799 +2.20000, 45.79918 +2.30000, 45.73478 +2.40000, 45.57377 +2.50000, 45.57377 +2.60000, 45.44496 +2.70000, 45.28396 +2.80000, 45.15515 +2.90000, 45.09075 +3.00000, 44.99415 +3.10000, 44.99415 +3.20000, 44.83314 +3.30000, 44.80094 +3.40000, 44.67213 +3.50000, 44.57553 +3.60000, 44.51112 +3.70000, 44.41452 +3.80000, 44.41452 +3.90000, 44.41452 +4.00000, 44.35012 +4.10000, 44.31792 +4.20000, 44.28571 +4.30000, 44.28571 +4.40000, 44.28571 +4.50000, 44.28571 +4.60000, 44.28571 +4.70000, 44.28571 +4.80000, 44.28571 +4.90000, 44.35012 +5.00000, 44.35012 +5.10000, 44.35012 +5.20000, 44.35012 +5.30000, 44.41452 +5.40000, 44.41452 +5.50000, 44.35012 +5.70000, 44.63993 +5.80000, 44.73653 +5.90000, 44.73653 +6.00000, 44.80094 +6.10000, 44.80094 +6.20000, 44.92974 +6.30000, 44.99415 +6.40000, 45.15515 +6.50000, 45.28396 +6.60000, 45.28396 +6.70000, 45.38056 +6.80000, 45.47717 +6.90000, 45.60597 +7.00000, 45.67037 +7.10000, 45.70258 +7.20000, 45.83138 +7.30000, 45.83138 +7.40000, 45.96019 +7.50000, 46.08899 +7.60000, 46.21780 +7.70000, 46.31440 +7.80000, 46.50761 +7.90000, 46.60422 +8.00000, 46.60422 +8.10000, 46.60422 +8.20000, 46.73302 +8.30000, 46.79742 +8.40000, 46.95843 +8.50000, 46.99063 +8.60000, 46.99063 +8.70000, 47.15164 +8.80000, 47.31265 +8.90000, 47.40925 +9.00000, 47.50585 +9.10000, 47.66686 +9.20000, 47.79567 +9.30000, 47.79567 +9.40000, 47.82787 +9.50000, 47.98888 +9.60000, 48.05328 +9.70000, 48.18208 +9.80000, 48.27869 +9.90000, 48.40749 +10.00000, 48.40749 +10.10000, 48.40749 +10.20000, 48.53630 +10.30000, 48.63290 +10.40000, 48.66511 +10.50000, 48.76171 +10.60000, 48.82611 +10.70000, 48.82611 +10.80000, 48.89052 +10.90000, 48.98712 +11.00000, 48.98712 +11.10000, 49.05152 +11.20000, 49.05152 +11.30000, 49.05152 +11.40000, 49.05152 +11.50000, 49.11593 +11.60000, 49.11593 +11.70000, 49.11593 +11.80000, 49.11593 +11.90000, 49.11593 +12.00000, 49.11593 +12.10000, 49.11593 +12.20000, 49.08372 +12.30000, 49.05152 +12.40000, 49.01932 +12.50000, 49.01932 +12.60000, 48.98712 +12.70000, 48.89052 +12.80000, 48.89052 +12.90000, 48.82611 +13.00000, 48.69731 +13.10000, 48.60070 +13.20000, 48.56850 +13.30000, 48.40749 +13.40000, 48.34309 +13.50000, 48.34309 +13.60000, 48.27869 +13.70000, 48.14988 +13.80000, 48.08548 +13.90000, 47.95667 +14.00000, 47.79567 +14.10000, 47.66686 +14.20000, 47.66686 +14.30000, 47.53806 +14.40000, 47.44145 +14.50000, 47.31265 +14.60000, 47.21604 +14.70000, 47.11944 +14.80000, 47.11944 +14.90000, 47.02283 +15.00000, 46.76522 +15.10000, 46.66862 +15.20000, 46.57201 +15.30000, 46.34660 +15.40000, 46.25000 +15.50000, 46.25000 +15.60000, 46.15340 +15.70000, 46.05679 +16.00000, 45.63817 +16.10000, 45.54157 +16.20000, 45.54157 +16.30000, 45.28396 +16.40000, 45.21956 +16.50000, 45.18735 +16.60000, 45.05855 +16.70000, 44.99415 +16.80000, 44.89754 +16.90000, 44.89754 +17.00000, 44.80094 +17.10000, 44.73653 +17.20000, 44.70433 +17.30000, 44.63993 +17.40000, 44.57553 +17.50000, 44.54333 +17.60000, 44.54333 +17.70000, 44.44672 +17.80000, 44.41452 +17.90000, 44.38232 +18.00000, 44.38232 +18.10000, 44.38232 +18.20000, 44.41452 +18.30000, 44.41452 +18.40000, 44.41452 +18.50000, 44.44672 +18.60000, 44.51112 +18.70000, 44.54333 +18.80000, 44.54333 +18.90000, 44.57553 +19.00000, 44.57553 +19.10000, 44.67213 +19.20000, 44.70433 +19.30000, 44.83314 +19.40000, 44.89754 +19.50000, 44.99415 +19.60000, 45.09075 +19.70000, 45.09075 +19.80000, 45.12295 +19.90000, 45.25176 +20.00000, 45.28396 +20.10000, 45.44496 +20.20000, 45.50937 +20.30000, 45.50937 +20.40000, 45.63817 +20.50000, 45.79918 +20.60000, 45.89578 +20.70000, 45.96019 +20.80000, 46.02459 +20.90000, 46.12119 +21.00000, 46.12119 +21.10000, 46.25000 +21.20000, 46.37881 +21.30000, 46.50761 +21.40000, 46.60422 +21.50000, 46.79742 +21.60000, 46.92623 +21.70000, 46.92623 +21.80000, 46.92623 +21.90000, 47.02283 +22.00000, 47.05504 +22.10000, 47.24824 +22.20000, 47.28044 +22.30000, 47.40925 +22.40000, 47.40925 +22.50000, 47.60246 +22.60000, 47.69906 +22.70000, 47.79567 +22.80000, 47.92447 +22.90000, 47.98888 +23.00000, 48.02108 +23.10000, 48.02108 +23.20000, 48.14988 +23.30000, 48.24649 +23.40000, 48.37529 +23.50000, 48.40749 +23.60000, 48.50410 +23.70000, 48.60070 +23.80000, 48.60070 +23.90000, 48.66511 +24.00000, 48.72951 +24.10000, 48.79391 +24.20000, 48.82611 +24.30000, 48.92272 +24.40000, 48.95492 +24.50000, 48.95492 +24.60000, 49.01932 +24.70000, 49.05152 +24.80000, 49.05152 +24.90000, 49.08372 +25.00000, 49.11593 +25.10000, 49.11593 +25.20000, 49.11593 +25.30000, 49.11593 +25.40000, 49.11593 +25.50000, 49.08372 +25.60000, 49.05152 +25.70000, 48.98712 +25.80000, 48.98712 +25.90000, 48.98712 +26.00000, 48.98712 +26.10000, 48.89052 +26.20000, 48.85831 +26.30000, 48.72951 +26.40000, 48.72951 +26.50000, 48.72951 +26.60000, 48.69731 +26.70000, 48.47190 +26.80000, 48.43970 +26.90000, 48.40749 +27.00000, 48.24649 +27.10000, 48.18208 +27.20000, 48.18208 +27.30000, 48.11768 +27.40000, 47.95667 +27.50000, 47.89227 +27.60000, 47.76347 +27.70000, 47.63466 +27.80000, 47.53806 +27.90000, 47.53806 +28.00000, 47.24824 +28.10000, 47.18384 +28.20000, 47.08724 +28.30000, 46.89403 +28.40000, 46.79742 +28.50000, 46.66862 +28.60000, 46.66862 +28.70000, 46.44321 +28.80000, 46.37881 +28.90000, 46.31440 +29.00000, 46.15340 +29.10000, 45.99239 +29.20000, 45.92799 +29.30000, 45.92799 +29.40000, 45.76698 +29.50000, 45.67037 +29.60000, 45.54157 +29.70000, 45.44496 +29.80000, 45.34836 +29.90000, 45.15515 +30.00000, 45.15515 +30.10000, 45.05855 +30.20000, 44.96194 +30.30000, 44.86534 +30.40000, 44.76874 +30.50000, 44.70433 +30.60000, 44.63993 +30.70000, 44.63993 +30.80000, 44.57553 +30.90000, 44.54333 +31.00000, 44.44672 +31.10000, 44.41452 +31.20000, 44.38232 +31.30000, 44.38232 +31.40000, 44.38232 +31.50000, 44.38232 +31.60000, 44.35012 +31.70000, 44.35012 +31.80000, 44.35012 +31.90000, 44.38232 +32.00000, 44.38232 +32.10000, 44.41452 +32.20000, 44.41452 +32.30000, 44.47892 +32.40000, 44.47892 +32.50000, 44.44672 +32.60000, 44.63993 +32.70000, 44.63993 +32.80000, 44.70433 +32.90000, 44.83314 +33.00000, 44.89754 +33.10000, 44.96194 +33.20000, 45.09075 +33.30000, 45.15515 +33.40000, 45.15515 +33.50000, 45.18735 +33.60000, 45.31616 +33.70000, 45.47717 +33.80000, 45.50937 +33.90000, 45.60597 +34.00000, 45.73478 +34.10000, 45.73478 +34.20000, 45.86358 +34.30000, 45.99239 +34.40000, 46.05679 +34.50000, 46.18560 +34.60000, 46.28220 +34.70000, 46.44321 +34.80000, 46.44321 +34.90000, 46.47541 +35.00000, 46.53981 +35.10000, 46.76522 +35.20000, 46.79742 +35.30000, 46.92623 +35.40000, 47.02283 +35.50000, 47.02283 +35.60000, 47.18384 +35.70000, 47.21604 +35.80000, 47.40925 +35.90000, 47.47365 +36.00000, 47.60246 +36.10000, 47.69906 +36.20000, 47.69906 +36.30000, 47.86007 +36.40000, 47.98888 +36.50000, 47.98888 +36.60000, 48.11768 +36.70000, 48.21429 +36.80000, 48.31089 +36.90000, 48.31089 +37.00000, 48.40749 +37.10000, 48.43970 +37.20000, 48.56850 +37.30000, 48.63290 +37.40000, 48.69731 +37.50000, 48.79391 +37.60000, 48.79391 +37.70000, 48.79391 +37.80000, 48.85831 +37.90000, 48.95492 +38.00000, 48.98712 +38.10000, 49.01932 +38.20000, 49.01932 +38.30000, 49.05152 +38.40000, 49.05152 +38.50000, 49.11593 +38.60000, 49.11593 +38.70000, 49.11593 +38.80000, 49.11593 +38.90000, 49.11593 +39.00000, 49.11593 +39.10000, 49.08372 +39.20000, 49.05152 +39.30000, 49.05152 +39.40000, 48.98712 +39.50000, 48.92272 +39.60000, 48.92272 +39.70000, 48.85831 +39.80000, 48.79391 +39.90000, 48.76171 +40.00000, 48.66511 +40.10000, 48.63290 +40.20000, 48.56850 +40.30000, 48.56850 +40.40000, 48.43970 +40.50000, 48.34309 +40.60000, 48.24649 +40.70000, 48.14988 +40.80000, 48.05328 +40.90000, 47.92447 +41.00000, 47.92447 +41.10000, 47.82787 +41.20000, 47.69906 +41.30000, 47.60246 +41.40000, 47.44145 +41.50000, 47.34485 +41.60000, 47.15164 +41.70000, 47.15164 +41.80000, 46.99063 +41.90000, 46.92623 +42.00000, 46.73302 +42.10000, 46.60422 +42.20000, 46.44321 +42.30000, 46.34660 +42.40000, 46.34660 +42.50000, 46.21780 +42.60000, 46.05679 +42.70000, 46.02459 +42.80000, 45.70258 +42.90000, 45.67037 +43.00000, 45.57377 +43.10000, 45.57377 +43.20000, 45.47717 +43.30000, 45.34836 +43.40000, 45.25176 +43.50000, 45.09075 +43.60000, 44.99415 +43.70000, 44.99415 +43.80000, 44.96194 +43.90000, 44.80094 +44.00000, 44.76874 +44.10000, 44.73653 +44.20000, 44.67213 +44.30000, 44.63993 +44.40000, 44.63993 +44.50000, 44.57553 +44.60000, 44.47892 +44.70000, 44.41452 +44.80000, 44.38232 +44.90000, 44.38232 +45.00000, 44.38232 +45.10000, 44.38232 +45.20000, 44.38232 +45.30000, 44.38232 +45.40000, 44.38232 +45.50000, 44.41452 +45.60000, 44.41452 +45.70000, 44.51112 +45.80000, 44.51112 +45.90000, 44.57553 +46.00000, 44.63993 +46.10000, 44.67213 +46.20000, 44.73653 +46.30000, 44.80094 +46.40000, 44.86534 +46.50000, 44.86534 +46.60000, 44.92974 +46.70000, 45.05855 +46.80000, 45.09075 +46.90000, 45.21956 +47.00000, 45.31616 +47.10000, 45.38056 +47.20000, 45.38056 +47.30000, 45.50937 +47.40000, 45.67037 +47.50000, 45.70258 +47.60000, 45.79918 +47.70000, 45.92799 +47.80000, 45.96019 +47.90000, 45.96019 +48.00000, 46.15340 +48.10000, 46.25000 +48.20000, 46.37881 +48.30000, 46.41101 +48.40000, 46.60422 +48.50000, 46.63642 +48.60000, 46.63642 +48.70000, 46.76522 +48.80000, 46.89403 +48.90000, 46.99063 +49.00000, 47.11944 +49.10000, 47.24824 +49.20000, 47.37705 +49.30000, 47.37705 +49.40000, 47.40925 +49.50000, 47.50585 +49.60000, 47.66686 +49.70000, 47.73126 +49.80000, 47.89227 +49.90000, 47.89227 +50.00000, 47.98888 +50.10000, 48.11768 +50.20000, 48.21429 +50.30000, 48.21429 +50.40000, 48.34309 +50.50000, 48.40749 +50.60000, 48.40749 +50.70000, 48.50410 +50.80000, 48.56850 +50.90000, 48.63290 +51.00000, 48.72951 +51.10000, 48.79391 +51.20000, 48.82611 +51.30000, 48.82611 +51.40000, 48.85831 +51.50000, 48.95492 +51.60000, 48.98712 +51.70000, 49.05152 +51.80000, 49.05152 +51.90000, 49.05152 +52.00000, 49.05152 +52.10000, 49.11593 +52.20000, 49.11593 +52.30000, 49.11593 +52.40000, 49.11593 +52.50000, 49.11593 +52.60000, 49.05152 +52.70000, 49.05152 +52.80000, 49.05152 +52.90000, 49.05152 +53.00000, 48.98712 +53.10000, 48.92272 +53.20000, 48.85831 +53.30000, 48.72951 +53.40000, 48.72951 +53.50000, 48.69731 +53.60000, 48.66511 +53.70000, 48.60070 +53.80000, 48.43970 +53.90000, 48.40749 +54.00000, 48.27869 +54.10000, 48.27869 +54.20000, 48.18208 +54.30000, 48.05328 +54.40000, 47.95667 +54.50000, 47.86007 +54.60000, 47.73126 +54.70000, 47.63466 +54.80000, 47.63466 +54.90000, 47.50585 +55.00000, 47.34485 +55.10000, 47.21604 +55.20000, 47.08724 +55.30000, 46.92623 +55.40000, 46.92623 +55.50000, 46.79742 +55.60000, 46.70082 +55.70000, 46.60422 +55.80000, 46.41101 +55.90000, 46.31440 +56.00000, 46.15340 +56.10000, 46.15340 +56.20000, 46.02459 +56.30000, 45.96019 +56.40000, 45.76698 +56.50000, 45.67037 +56.60000, 45.54157 +56.70000, 45.47717 +56.80000, 45.47717 +56.90000, 45.31616 +57.00000, 45.25176 +57.10000, 45.09075 +57.20000, 44.99415 +57.30000, 44.86534 +57.40000, 44.76874 +57.50000, 44.76874 +57.60000, 44.70433 +57.70000, 44.63993 +57.80000, 44.60773 +57.90000, 44.57553 +58.00000, 44.51112 +58.10000, 44.47892 +58.20000, 44.47892 +58.30000, 44.38232 +58.40000, 44.38232 +58.50000, 44.38232 +58.60000, 44.38232 +58.70000, 44.38232 +58.80000, 44.38232 +58.90000, 44.38232 +59.00000, 44.38232 +59.10000, 44.41452 +59.20000, 44.47892 +59.30000, 44.54333 +59.70000, 44.73653 +59.80000, 44.73653 +59.90000, 44.80094 +60.00000, 44.89754 +60.10000, 44.96194 +60.20000, 45.05855 +60.30000, 45.05855 +60.40000, 45.15515 +60.50000, 45.28396 +60.60000, 45.38056 +60.70000, 45.47717 +60.80000, 45.60597 +60.90000, 45.60597 +61.00000, 45.67037 +61.10000, 45.79918 +61.20000, 45.79918 +61.30000, 45.89578 +61.40000, 46.08899 +61.50000, 46.21780 +61.60000, 46.21780 +61.70000, 46.31440 +61.80000, 46.44321 +61.90000, 46.57201 +62.00000, 46.60422 +62.10000, 46.76522 +62.20000, 46.79742 +62.30000, 46.79742 +62.40000, 46.89403 +62.50000, 46.99063 +62.60000, 47.11944 +62.70000, 47.31265 +62.80000, 47.40925 +62.90000, 47.47365 +63.00000, 47.47365 +63.10000, 47.60246 +63.20000, 47.69906 +63.30000, 47.82787 +63.40000, 47.92447 +63.50000, 48.02108 +63.60000, 48.11768 +63.70000, 48.11768 +63.80000, 48.21429 +63.90000, 48.31089 +64.00000, 48.40749 +64.10000, 48.47190 +64.20000, 48.53630 +64.30000, 48.66511 +64.40000, 48.66511 +64.50000, 48.66511 +64.60000, 48.72951 +64.70000, 48.82611 +64.80000, 48.85831 +64.90000, 48.92272 +65.00000, 48.98712 +65.10000, 48.98712 +65.20000, 49.01932 +65.30000, 49.05152 +65.40000, 49.05152 +65.50000, 49.08372 +65.60000, 49.11593 +65.70000, 49.11593 +65.80000, 49.11593 +65.90000, 49.11593 +66.00000, 49.05152 +66.10000, 49.05152 +66.20000, 49.05152 +66.30000, 49.01932 +66.40000, 49.01932 +66.50000, 49.01932 +66.60000, 48.98712 +66.70000, 48.92272 +66.80000, 48.85831 +66.90000, 48.72951 +67.00000, 48.69731 +67.10000, 48.69731 +67.20000, 48.60070 +67.30000, 48.50410 +67.40000, 48.43970 +67.50000, 48.34309 +67.60000, 48.27869 +67.70000, 48.14988 +67.80000, 48.14988 +67.90000, 48.05328 +68.00000, 47.89227 +68.10000, 47.76347 +68.20000, 47.66686 +68.30000, 47.53806 +68.40000, 47.47365 +68.50000, 47.47365 +68.60000, 47.31265 +68.70000, 47.24824 +68.80000, 47.08724 +68.90000, 46.95843 +69.00000, 46.73302 +69.10000, 46.63642 +69.20000, 46.63642 +69.30000, 46.53981 +69.40000, 46.37881 +69.50000, 46.25000 +69.60000, 46.12119 +69.70000, 46.02459 +70.00000, 45.70258 +70.10000, 45.60597 +70.20000, 45.47717 +70.30000, 45.34836 +70.40000, 45.28396 +70.50000, 45.05855 +70.60000, 45.05855 +70.70000, 45.02635 +70.80000, 44.99415 +70.90000, 44.83314 +71.00000, 44.76874 +71.10000, 44.70433 +71.20000, 44.63993 +71.30000, 44.63993 +71.40000, 44.57553 +71.50000, 44.54333 +71.60000, 44.47892 +71.70000, 44.41452 +71.80000, 44.41452 +71.90000, 44.38232 +72.00000, 44.38232 +72.10000, 44.38232 +72.20000, 44.38232 +72.30000, 44.38232 +72.40000, 44.38232 +72.50000, 44.38232 +72.60000, 44.38232 +72.70000, 44.38232 +72.80000, 44.47892 +72.90000, 44.51112 +73.00000, 44.60773 +73.10000, 44.70433 +73.20000, 44.73653 +73.30000, 44.73653 +73.40000, 44.73653 +73.50000, 44.83314 +73.60000, 44.86534 +73.70000, 45.02635 +73.80000, 45.05855 +73.90000, 45.21956 +74.00000, 45.21956 +74.10000, 45.34836 +74.20000, 45.38056 +74.30000, 45.50937 +74.40000, 45.67037 +74.50000, 45.76698 +74.60000, 45.76698 +74.70000, 45.76698 +74.80000, 45.92799 +74.90000, 45.96019 +75.00000, 46.12119 +75.10000, 46.28220 +75.20000, 46.41101 +75.30000, 46.50761 +75.40000, 46.50761 +75.50000, 46.60422 +75.60000, 46.70082 +75.70000, 46.73302 +75.80000, 46.79742 +75.90000, 46.95843 +76.00000, 47.08724 +76.10000, 47.08724 +76.20000, 47.21604 +76.30000, 47.31265 +76.40000, 47.50585 +76.50000, 47.60246 +76.60000, 47.66686 +76.70000, 47.79567 +76.80000, 47.79567 +76.90000, 47.89227 +77.00000, 48.02108 +77.10000, 48.02108 +77.20000, 48.14988 +77.30000, 48.21429 +77.40000, 48.34309 +77.50000, 48.34309 +77.60000, 48.43970 +77.70000, 48.50410 +77.80000, 48.60070 +77.90000, 48.66511 +78.00000, 48.69731 +78.10000, 48.79391 +78.20000, 48.79391 +78.30000, 48.82611 +78.40000, 48.89052 +78.50000, 48.98712 +78.60000, 48.98712 +78.70000, 49.01932 +78.80000, 49.01932 +78.90000, 49.01932 +79.00000, 49.05152 +79.10000, 49.08372 +79.20000, 49.11593 +79.30000, 49.11593 +79.40000, 49.11593 +79.50000, 49.11593 +79.60000, 49.05152 +79.70000, 49.05152 +79.80000, 49.01932 +79.90000, 49.01932 diff --git a/tests/Mooring/lowe_and_langley_2006/Case 3.csv b/tests/Mooring/lowe_and_langley_2006/Case 3.csv new file mode 100644 index 00000000..b66cd5b4 --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 3.csv @@ -0,0 +1,775 @@ +0.10000, 55.71721 +0.20000, 55.45960 +0.30000, 55.07319 +0.40000, 55.07319 +0.50000, 54.84778 +0.60000, 54.49356 +0.70000, 54.17155 +0.80000, 53.78513 +0.90000, 53.65632 +1.00000, 53.20550 +1.10000, 53.20550 +1.20000, 53.04450 +1.30000, 52.65808 +1.40000, 52.30386 +1.50000, 51.94965 +1.60000, 51.40222 +1.70000, 51.01581 +1.80000, 51.01581 +1.90000, 50.66159 +2.00000, 50.30738 +2.10000, 49.95316 +2.20000, 49.69555 +2.30000, 49.53454 +2.40000, 49.30913 +2.50000, 49.30913 +2.60000, 49.21253 +2.70000, 48.98712 +2.80000, 48.82611 +2.90000, 48.76171 +3.00000, 48.56850 +3.10000, 48.56850 +3.20000, 48.34309 +3.30000, 48.08548 +3.40000, 47.89227 +3.50000, 47.76347 +3.60000, 47.40925 +3.70000, 47.28044 +3.80000, 47.28044 +3.90000, 47.11944 +4.00000, 46.89403 +4.10000, 46.70082 +4.20000, 46.47541 +4.30000, 46.41101 +4.40000, 46.21780 +4.50000, 46.21780 +4.60000, 45.96019 +4.70000, 45.79918 +4.80000, 45.63817 +4.90000, 45.38056 +5.00000, 45.21956 +5.10000, 45.15515 +5.20000, 45.15515 +5.30000, 44.89754 +5.40000, 44.80094 +5.50000, 44.73653 +5.60000, 44.41452 +5.70000, 44.28571 +5.80000, 44.28571 +5.90000, 44.28571 +6.00000, 44.18911 +6.10000, 44.18911 +6.20000, 44.15691 +6.30000, 44.09251 +6.40000, 44.02810 +6.50000, 43.96370 +6.60000, 43.96370 +6.70000, 43.96370 +6.80000, 43.89930 +6.90000, 43.83489 +7.00000, 43.77049 +7.10000, 43.70609 +7.20000, 43.64169 +7.30000, 43.64169 +7.40000, 43.54508 +7.50000, 43.41628 +7.60000, 43.35187 +7.70000, 43.22307 +7.80000, 43.09426 +7.90000, 42.93326 +8.00000, 42.93326 +8.10000, 42.83665 +8.20000, 42.64344 +8.30000, 42.51464 +8.40000, 42.25703 +8.50000, 42.19262 +8.60000, 42.19262 +8.70000, 41.99941 +8.80000, 41.64520 +8.90000, 41.45199 +9.00000, 41.22658 +9.10000, 40.90457 +9.20000, 40.61475 +9.30000, 40.61475 +9.40000, 40.51815 +9.50000, 40.13173 +9.60000, 40.03513 +9.70000, 39.71311 +9.80000, 39.32670 +9.90000, 39.03689 +10.00000, 39.03689 +10.10000, 38.81148 +10.20000, 38.58607 +10.30000, 38.36066 +10.40000, 38.10304 +10.50000, 37.87763 +10.60000, 37.52342 +10.70000, 37.52342 +10.80000, 37.29801 +10.90000, 36.97600 +11.00000, 36.78279 +11.90000, 36.84719 +12.00000, 37.04040 +12.10000, 37.04040 +12.20000, 37.13700 +12.30000, 37.23361 +12.40000, 37.36241 +12.50000, 37.49122 +12.60000, 37.74883 +12.70000, 37.90984 +12.80000, 37.90984 +12.90000, 38.10304 +13.00000, 38.29625 +13.10000, 38.52166 +13.20000, 38.71487 +13.30000, 39.06909 +13.40000, 39.29450 +13.50000, 39.29450 +13.60000, 39.39110 +13.70000, 39.80972 +13.80000, 39.90632 +13.90000, 40.19614 +14.00000, 40.74356 +14.10000, 41.00117 +14.20000, 41.00117 +14.30000, 41.22658 +14.40000, 41.58080 +14.50000, 41.87061 +14.60000, 42.19262 +14.70000, 42.51464 +14.80000, 42.51464 +14.90000, 42.90105 +15.00000, 43.28747 +15.10000, 43.64169 +15.20000, 43.93150 +15.30000, 44.47892 +15.40000, 44.80094 +15.50000, 44.80094 +15.60000, 44.96194 +15.70000, 45.41276 +15.80000, 45.73478 +15.90000, 46.12119 +16.00000, 46.50761 +16.10000, 46.82963 +16.20000, 46.82963 +16.30000, 47.40925 +16.40000, 47.76347 +16.50000, 48.08548 +16.60000, 48.43970 +16.70000, 48.82611 +16.80000, 49.21253 +16.90000, 49.21253 +17.00000, 49.59895 +17.10000, 49.95316 +17.20000, 50.21077 +17.30000, 50.53279 +17.40000, 50.85480 +17.50000, 51.24122 +17.60000, 51.24122 +17.70000, 51.62763 +17.80000, 51.75644 +17.90000, 52.17506 +18.00000, 52.30386 +18.10000, 52.65808 +18.20000, 53.01230 +18.30000, 53.01230 +18.40000, 53.26991 +18.50000, 53.49532 +18.60000, 53.75293 +18.70000, 54.01054 +18.80000, 54.10714 +18.90000, 54.26815 +19.00000, 54.26815 +19.10000, 54.42916 +19.20000, 54.68677 +19.30000, 54.78337 +19.40000, 54.91218 +19.50000, 55.07319 +19.60000, 55.23419 +19.70000, 55.23419 +19.80000, 55.23419 +19.90000, 55.33080 +20.00000, 55.39520 +20.10000, 55.45960 +20.20000, 55.49180 +20.30000, 55.49180 +20.40000, 55.52400 +20.50000, 55.55621 +20.60000, 55.55621 +20.70000, 55.62061 +20.80000, 55.62061 +20.90000, 55.65281 +21.00000, 55.65281 +21.10000, 55.65281 +21.20000, 55.65281 +21.30000, 55.65281 +21.40000, 55.68501 +21.50000, 55.71721 +21.60000, 55.81382 +21.70000, 55.81382 +21.80000, 55.81382 +21.90000, 55.91042 +22.00000, 55.94262 +22.10000, 56.00703 +22.20000, 56.07143 +22.30000, 56.16803 +22.40000, 56.16803 +22.50000, 56.29684 +22.60000, 56.36124 +22.70000, 56.49005 +22.80000, 56.58665 +22.90000, 56.68326 +23.00000, 56.71546 +23.10000, 56.71546 +23.20000, 56.77986 +23.30000, 56.94087 +23.40000, 57.00527 +23.50000, 57.10187 +23.60000, 57.23068 +23.70000, 57.32728 +23.80000, 57.32728 +23.90000, 57.42389 +24.00000, 57.48829 +24.10000, 57.55269 +24.20000, 57.58489 +24.30000, 57.61710 +24.40000, 57.64930 +24.50000, 57.64930 +24.60000, 57.74590 +24.70000, 57.74590 +24.80000, 57.77810 +24.90000, 57.77810 +25.00000, 57.77810 +25.10000, 57.77810 +25.20000, 57.77810 +25.30000, 57.74590 +25.40000, 57.68150 +25.50000, 57.61710 +25.60000, 57.58489 +25.70000, 57.48829 +25.80000, 57.39169 +25.90000, 57.39169 +26.00000, 57.32728 +26.10000, 57.19848 +26.20000, 57.13407 +26.30000, 56.94087 +26.40000, 56.87646 +26.50000, 56.87646 +26.60000, 56.71546 +26.70000, 56.42564 +26.80000, 56.26464 +26.90000, 56.07143 +27.00000, 55.81382 +27.10000, 55.55621 +27.20000, 55.55621 +27.30000, 55.45960 +27.40000, 55.04098 +27.50000, 54.91218 +27.60000, 54.62237 +27.70000, 54.33255 +27.80000, 54.04274 +27.90000, 54.04274 +28.00000, 53.55972 +28.10000, 53.26991 +28.20000, 52.91569 +28.30000, 52.59368 +28.40000, 52.20726 +28.50000, 51.88525 +28.60000, 51.88525 +28.70000, 51.40222 +28.80000, 51.08021 +28.90000, 50.72600 +29.00000, 50.30738 +29.10000, 50.14637 +29.20000, 49.79215 +29.30000, 49.79215 +29.40000, 49.56674 +29.50000, 49.40574 +29.60000, 49.24473 +29.70000, 49.05152 +29.80000, 48.89052 +29.90000, 48.66511 +30.00000, 48.66511 +30.10000, 48.47190 +30.20000, 48.31089 +30.30000, 48.11768 +30.40000, 47.92447 +30.50000, 47.73126 +30.60000, 47.63466 +30.70000, 47.63466 +30.80000, 47.37705 +30.90000, 47.11944 +31.00000, 46.89403 +31.10000, 46.66862 +31.20000, 46.47541 +31.30000, 46.25000 +31.40000, 46.25000 +31.50000, 46.15340 +31.60000, 45.92799 +31.70000, 45.86358 +31.80000, 45.67037 +31.90000, 45.47717 +32.00000, 45.47717 +32.10000, 45.28396 +32.20000, 45.09075 +32.30000, 44.89754 +32.40000, 44.80094 +32.50000, 44.67213 +32.60000, 44.44672 +32.70000, 44.44672 +32.80000, 44.38232 +32.90000, 44.31792 +33.00000, 44.22131 +33.10000, 44.22131 +33.20000, 44.12471 +33.30000, 44.06030 +33.40000, 44.06030 +33.50000, 44.02810 +33.60000, 43.99590 +33.70000, 43.96370 +33.80000, 43.89930 +33.90000, 43.83489 +34.00000, 43.83489 +34.10000, 43.83489 +34.20000, 43.67389 +34.30000, 43.64169 +34.40000, 43.54508 +34.50000, 43.41628 +34.60000, 43.31967 +34.70000, 43.19087 +34.80000, 43.19087 +34.90000, 43.15867 +35.00000, 43.02986 +35.10000, 42.90105 +35.20000, 42.67564 +35.30000, 42.41803 +35.40000, 42.22482 +35.50000, 42.22482 +35.60000, 42.06382 +35.70000, 41.99941 +35.80000, 41.64520 +35.90000, 41.54859 +36.00000, 41.29098 +36.10000, 40.87237 +36.20000, 40.87237 +36.30000, 40.64696 +36.40000, 40.42155 +36.50000, 40.19614 +36.60000, 40.00293 +36.70000, 39.71311 +36.80000, 39.45550 +36.90000, 39.45550 +37.00000, 39.13349 +37.10000, 38.87588 +37.20000, 38.58607 +37.30000, 38.32845 +37.40000, 38.00644 +37.50000, 37.68443 +37.60000, 37.68443 +37.70000, 37.58782 +37.80000, 37.33021 +37.90000, 37.07260 +38.00000, 36.81499 +39.00000, 36.91159 +39.10000, 37.00820 +39.20000, 37.13700 +39.30000, 37.23361 +39.40000, 37.36241 +39.50000, 37.52342 +39.60000, 37.52342 +39.70000, 37.74883 +39.80000, 37.94204 +39.90000, 38.03864 +40.00000, 38.32845 +40.10000, 38.45726 +40.20000, 38.68267 +40.30000, 38.68267 +40.40000, 39.06909 +40.50000, 39.29450 +40.60000, 39.55211 +40.70000, 39.77752 +40.80000, 40.03513 +40.90000, 40.32494 +41.00000, 40.32494 +41.10000, 40.61475 +41.20000, 40.93677 +41.30000, 41.16218 +41.40000, 41.58080 +41.50000, 41.90281 +41.60000, 42.35363 +41.70000, 42.35363 +41.80000, 42.74005 +41.90000, 42.96546 +42.00000, 43.35187 +42.10000, 43.60948 +42.20000, 44.02810 +42.30000, 44.15691 +42.40000, 44.15691 +42.50000, 44.57553 +42.60000, 45.15515 +42.70000, 45.47717 +42.80000, 45.79918 +42.90000, 46.18560 +43.00000, 46.44321 +43.10000, 46.44321 +43.20000, 46.99063 +43.30000, 47.24824 +43.40000, 47.73126 +43.50000, 48.11768 +43.60000, 48.40749 +43.70000, 48.40749 +43.80000, 48.76171 +43.90000, 49.27693 +44.00000, 49.66335 +44.10000, 49.79215 +44.20000, 50.30738 +44.30000, 50.43618 +44.40000, 50.43618 +44.50000, 50.82260 +44.60000, 51.30562 +44.70000, 51.62763 +44.80000, 51.88525 +44.90000, 52.14286 +45.00000, 52.62588 +45.10000, 52.62588 +45.20000, 52.69028 +45.30000, 53.01230 +45.40000, 53.23770 +45.50000, 53.49532 +45.60000, 53.72073 +45.70000, 53.88173 +45.80000, 53.88173 +45.90000, 54.23595 +46.00000, 54.39696 +46.10000, 54.49356 +46.20000, 54.68677 +46.30000, 54.81557 +46.40000, 55.00878 +46.50000, 55.00878 +46.60000, 55.04098 +46.70000, 55.13759 +46.80000, 55.33080 +46.90000, 55.36300 +47.00000, 55.39520 +47.10000, 55.45960 +47.20000, 55.45960 +47.30000, 55.49180 +47.40000, 55.49180 +47.50000, 55.52400 +47.60000, 55.55621 +47.70000, 55.62061 +47.80000, 55.62061 +47.90000, 55.62061 +48.00000, 55.65281 +48.10000, 55.65281 +48.20000, 55.65281 +48.30000, 55.65281 +48.40000, 55.68501 +48.50000, 55.68501 +48.60000, 55.68501 +48.70000, 55.78162 +48.80000, 55.81382 +48.90000, 55.91042 +49.00000, 55.97482 +49.10000, 56.03923 +49.20000, 56.13583 +49.30000, 56.13583 +49.40000, 56.16803 +49.50000, 56.23244 +49.60000, 56.36124 +49.70000, 56.45785 +49.80000, 56.58665 +49.90000, 56.58665 +50.00000, 56.58665 +50.10000, 56.81206 +50.20000, 56.84426 +50.30000, 56.94087 +50.40000, 57.06967 +50.50000, 57.13407 +50.60000, 57.13407 +50.70000, 57.26288 +50.80000, 57.26288 +50.90000, 57.35948 +51.00000, 57.45609 +51.10000, 57.55269 +51.20000, 57.58489 +51.30000, 57.58489 +51.40000, 57.61710 +51.50000, 57.68150 +51.60000, 57.74590 +51.70000, 57.74590 +51.80000, 57.77810 +51.90000, 57.77810 +52.00000, 57.77810 +52.10000, 57.74590 +52.20000, 57.74590 +52.30000, 57.74590 +52.40000, 57.64930 +52.50000, 57.61710 +52.60000, 57.55269 +52.70000, 57.55269 +52.80000, 57.55269 +52.90000, 57.45609 +53.00000, 57.32728 +53.10000, 57.23068 +53.20000, 57.13407 +53.30000, 56.87646 +53.40000, 56.87646 +53.50000, 56.77986 +53.60000, 56.71546 +53.70000, 56.49005 +53.80000, 56.32904 +53.90000, 56.07143 +54.00000, 55.91042 +54.10000, 55.91042 +54.20000, 55.68501 +54.30000, 55.33080 +54.40000, 55.07319 +54.50000, 54.81557 +54.60000, 54.55796 +54.70000, 54.26815 +54.80000, 54.26815 +54.90000, 53.94614 +55.00000, 53.62412 +55.10000, 53.30211 +55.20000, 52.94789 +55.30000, 52.62588 +55.40000, 52.62588 +55.50000, 52.36827 +55.60000, 51.94965 +55.70000, 51.62763 +55.80000, 51.17681 +55.90000, 50.79040 +56.00000, 50.37178 +56.10000, 50.37178 +56.20000, 50.17857 +56.30000, 49.72775 +56.40000, 49.53454 +56.50000, 49.37354 +56.60000, 49.21253 +56.70000, 49.14813 +56.80000, 49.14813 +56.90000, 48.89052 +57.00000, 48.82611 +57.10000, 48.60070 +57.20000, 48.34309 +57.30000, 48.11768 +57.40000, 47.95667 +57.50000, 47.95667 +57.60000, 47.69906 +57.70000, 47.50585 +57.80000, 47.40925 +57.90000, 47.08724 +58.00000, 46.95843 +58.10000, 46.73302 +58.20000, 46.73302 +58.30000, 46.53981 +58.40000, 46.41101 +58.50000, 46.05679 +58.60000, 45.92799 +58.70000, 45.79918 +58.80000, 45.54157 +58.90000, 45.54157 +59.00000, 45.44496 +59.10000, 45.21956 +59.20000, 45.12295 +59.30000, 44.92974 +59.40000, 44.80094 +59.50000, 44.67213 +59.60000, 44.67213 +59.70000, 44.41452 +59.80000, 44.38232 +59.90000, 44.31792 +60.00000, 44.22131 +60.10000, 44.22131 +60.20000, 44.15691 +60.30000, 44.15691 +60.40000, 44.09251 +60.50000, 44.02810 +60.60000, 43.96370 +60.70000, 43.89930 +60.80000, 43.83489 +60.90000, 43.83489 +61.00000, 43.83489 +61.10000, 43.80269 +61.20000, 43.73829 +61.30000, 43.64169 +61.40000, 43.48068 +61.50000, 43.41628 +61.60000, 43.41628 +61.70000, 43.35187 +61.80000, 43.15867 +61.90000, 43.09426 +62.00000, 43.02986 +62.10000, 42.86885 +62.20000, 42.70785 +62.30000, 42.70785 +62.40000, 42.45023 +62.50000, 42.35363 +62.60000, 42.16042 +62.70000, 41.90281 +62.80000, 41.70960 +62.90000, 41.45199 +63.00000, 41.45199 +63.10000, 41.22658 +63.20000, 40.96897 +63.30000, 40.71136 +63.40000, 40.48595 +63.50000, 40.19614 +63.60000, 39.97073 +63.70000, 39.97073 +63.80000, 39.55211 +63.90000, 39.32670 +64.00000, 39.13349 +64.10000, 38.81148 +64.20000, 38.71487 +64.30000, 38.26405 +64.40000, 38.26405 +64.50000, 38.16745 +64.60000, 37.87763 +64.70000, 37.49122 +64.80000, 37.20141 +64.90000, 37.00820 +65.00000, 36.78279 +65.10000, 36.78279 +65.90000, 36.78279 +66.00000, 36.87939 +66.10000, 37.04040 +66.20000, 37.07260 +66.30000, 37.26581 +66.40000, 37.33021 +66.50000, 37.33021 +66.60000, 37.49122 +66.70000, 37.78103 +66.80000, 37.94204 +66.90000, 38.16745 +67.00000, 38.32845 +67.10000, 38.32845 +67.20000, 38.48946 +67.30000, 38.74707 +67.40000, 38.94028 +67.50000, 39.23009 +67.60000, 39.51991 +67.70000, 39.74532 +67.80000, 39.74532 +67.90000, 40.00293 +68.00000, 40.45375 +68.10000, 40.74356 +68.20000, 40.96897 +68.30000, 41.22658 +68.40000, 41.41979 +68.50000, 41.41979 +68.60000, 41.96721 +68.70000, 42.09602 +68.80000, 42.45023 +68.90000, 42.99766 +69.00000, 43.31967 +69.10000, 43.57728 +69.20000, 43.57728 +69.30000, 43.96370 +69.40000, 44.25351 +69.50000, 44.67213 +69.60000, 45.09075 +69.70000, 45.44496 +69.80000, 45.76698 +69.90000, 45.76698 +70.00000, 46.18560 +70.10000, 46.50761 +70.20000, 47.05504 +70.30000, 47.44145 +70.40000, 47.57026 +70.50000, 48.21429 +70.60000, 48.21429 +70.70000, 48.34309 +70.80000, 48.72951 +70.90000, 49.34133 +71.00000, 49.66335 +71.10000, 49.98536 +71.20000, 50.27518 +71.30000, 50.27518 +71.40000, 50.53279 +71.50000, 50.88700 +71.60000, 51.14461 +71.70000, 51.49883 +71.80000, 51.82084 +71.90000, 52.14286 +72.00000, 52.14286 +72.10000, 52.40047 +72.20000, 52.81909 +72.30000, 53.07670 +72.40000, 53.26991 +72.50000, 53.52752 +72.60000, 53.52752 +72.70000, 53.72073 +72.80000, 53.91393 +72.90000, 54.01054 +73.00000, 54.26815 +73.10000, 54.49356 +73.20000, 54.68677 +73.30000, 54.68677 +73.40000, 54.78337 +73.50000, 54.94438 +73.60000, 55.04098 +73.70000, 55.16979 +73.80000, 55.26639 +73.90000, 55.36300 +74.00000, 55.36300 +74.10000, 55.36300 +74.20000, 55.45960 +74.30000, 55.49180 +74.40000, 55.49180 +74.50000, 55.55621 +74.60000, 55.55621 +74.70000, 55.55621 +74.80000, 55.62061 +74.90000, 55.62061 +75.00000, 55.62061 +75.10000, 55.65281 +75.20000, 55.65281 +75.30000, 55.68501 +75.40000, 55.68501 +75.50000, 55.68501 +75.60000, 55.74941 +75.70000, 55.74941 +75.80000, 55.78162 +75.90000, 55.81382 +76.00000, 55.94262 +76.10000, 55.94262 +76.20000, 55.97482 +76.30000, 56.10363 +76.40000, 56.16803 +76.50000, 56.29684 +76.60000, 56.39344 +76.70000, 56.45785 +76.80000, 56.45785 +76.90000, 56.55445 +77.00000, 56.61885 +77.10000, 56.68326 +77.20000, 56.81206 +77.30000, 56.94087 +77.40000, 57.06967 +77.50000, 57.06967 +77.60000, 57.10187 +77.70000, 57.23068 +77.80000, 57.29508 +77.90000, 57.39169 +78.00000, 57.45609 +78.10000, 57.55269 +78.20000, 57.55269 +78.30000, 57.58489 +78.40000, 57.61710 +78.50000, 57.68150 +78.60000, 57.74590 +78.70000, 57.74590 +78.80000, 57.74590 +78.90000, 57.74590 +79.00000, 57.77810 +79.10000, 57.77810 +79.20000, 57.74590 +79.30000, 57.74590 +79.40000, 57.64930 +79.50000, 57.64930 +79.60000, 57.61710 +79.70000, 57.55269 +79.80000, 57.52049 +79.90000, 57.45609 diff --git a/tests/Mooring/lowe_and_langley_2006/Case 4.csv b/tests/Mooring/lowe_and_langley_2006/Case 4.csv new file mode 100644 index 00000000..c1fc6ba8 --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 4.csv @@ -0,0 +1,297 @@ +-0.00000, 44.41342 +0.10000, 44.26082 +0.20000, 43.99378 +0.30000, 43.82210 +0.40000, 43.68858 +0.50000, 43.53598 +0.60000, 43.32615 +0.70000, 43.19263 +0.80000, 43.04003 +0.90000, 42.86836 +1.10000, 42.75391 +1.20000, 42.69668 +1.30000, 42.58223 +1.40000, 42.48686 +1.50000, 42.41056 +1.60000, 42.25796 +1.70000, 42.18166 +1.80000, 42.12443 +1.90000, 42.08628 +2.00000, 42.00998 +2.10000, 42.00998 +2.20000, 42.04813 +2.30000, 42.12443 +2.40000, 42.18166 +2.50000, 42.31518 +2.60000, 42.44871 +2.70000, 42.75391 +2.80000, 43.11633 +2.90000, 43.51690 +3.00000, 44.14637 +3.10000, 44.58510 +3.20000, 45.10012 +3.30000, 45.63422 +3.40000, 46.54981 +3.50000, 47.14114 +3.60000, 47.92321 +3.70000, 48.81973 +3.80000, 49.33475 +3.90000, 49.90700 +4.00000, 50.74629 +4.10000, 51.29947 +4.20000, 51.77634 +4.30000, 52.11969 +4.40000, 52.53934 +4.50000, 52.73009 +4.60000, 52.86361 +4.70000, 52.97806 +4.80000, 53.03528 +4.90000, 53.07343 +5.00000, 53.07343 +5.10000, 53.14973 +5.20000, 53.14973 +5.30000, 53.14973 +5.40000, 53.14973 +5.50000, 53.11158 +5.60000, 53.07343 +5.70000, 53.03528 +5.80000, 52.92083 +5.90000, 52.82546 +6.00000, 52.69194 +6.10000, 52.44396 +6.20000, 52.27229 +6.30000, 52.08154 +6.40000, 51.87171 +6.50000, 51.47114 +6.60000, 51.20409 +6.70000, 50.93704 +6.80000, 50.49832 +6.90000, 50.07867 +7.00000, 49.67810 +7.10000, 49.35383 +7.20000, 48.85788 +7.30000, 48.47638 +7.40000, 48.13303 +7.50000, 47.71338 +7.60000, 47.44633 +7.70000, 47.23651 +7.80000, 46.98854 +7.90000, 46.64519 +8.00000, 46.45444 +8.10000, 46.28277 +8.20000, 46.05387 +8.30000, 45.92034 +8.40000, 45.80589 +8.50000, 45.71052 +8.60000, 45.63422 +8.70000, 45.55792 +8.80000, 45.51977 +8.90000, 45.44347 +9.00000, 45.40532 +9.10000, 45.34809 +9.20000, 45.21457 +9.30000, 45.10012 +9.40000, 44.98567 +9.50000, 44.83307 +9.60000, 44.56602 +9.70000, 44.37527 +9.80000, 44.18452 +9.90000, 43.91748 +10.00000, 43.74580 +10.10000, 43.59320 +10.20000, 43.45968 +10.30000, 43.23078 +10.40000, 43.07818 +10.50000, 42.98281 +10.60000, 42.81113 +10.70000, 42.71576 +10.80000, 42.65853 +10.90000, 42.62038 +11.00000, 42.48686 +11.10000, 42.46778 +11.20000, 42.46778 +11.30000, 42.46778 +11.40000, 42.46778 +11.50000, 42.41056 +11.60000, 42.35333 +11.70000, 42.29611 +11.80000, 42.29611 +11.90000, 42.29611 +12.00000, 42.31518 +12.10000, 42.35333 +12.20000, 42.41056 +12.30000, 42.52501 +12.40000, 42.73483 +12.50000, 42.88743 +12.60000, 43.09725 +12.70000, 43.49783 +12.80000, 43.78395 +12.90000, 44.18452 +13.00000, 44.56602 +13.10000, 45.19550 +13.20000, 45.59607 +13.30000, 46.14924 +13.40000, 46.96946 +13.50000, 47.54171 +13.60000, 48.20933 +13.70000, 48.87695 +13.80000, 49.69717 +13.90000, 50.17405 +14.00000, 50.63185 +14.10000, 51.24224 +14.20000, 51.60467 +14.30000, 51.89079 +14.40000, 52.25321 +14.50000, 52.31044 +14.60000, 52.42489 +14.70000, 52.52026 +14.80000, 52.59656 +14.90000, 52.63471 +15.00000, 52.67286 +15.10000, 52.69194 +15.20000, 52.73009 +15.30000, 52.76824 +15.40000, 52.78731 +15.50000, 52.82546 +15.60000, 52.84453 +15.70000, 52.84453 +15.80000, 52.76824 +15.90000, 52.69194 +16.00000, 52.61564 +16.10000, 52.50119 +16.20000, 52.29136 +16.30000, 52.11969 +16.40000, 51.87171 +16.50000, 51.45207 +16.60000, 51.20409 +16.70000, 50.93704 +16.80000, 50.63185 +16.90000, 50.17405 +17.00000, 49.81162 +17.10000, 49.48735 +17.20000, 49.02955 +17.30000, 48.74343 +17.40000, 48.40008 +17.60000, 47.67523 +17.70000, 47.35096 +17.80000, 47.06484 +17.90000, 46.72149 +18.00000, 46.51166 +18.10000, 46.32091 +18.20000, 46.18739 +18.30000, 46.01572 +18.40000, 45.92034 +18.50000, 45.82497 +18.60000, 45.67237 +18.70000, 45.63422 +18.80000, 45.57699 +18.90000, 45.50069 +19.00000, 45.34809 +19.10000, 45.27179 +19.20000, 45.17642 +19.30000, 44.98567 +19.40000, 44.85215 +19.50000, 44.71862 +19.60000, 44.45157 +19.70000, 44.26082 +19.80000, 44.07008 +19.90000, 43.89840 +20.00000, 43.65043 +20.10000, 43.45968 +20.20000, 43.32615 +20.30000, 43.15448 +20.40000, 43.02096 +20.50000, 42.86836 +20.60000, 42.77298 +20.70000, 42.65853 +20.80000, 42.58223 +21.00000, 42.46778 +21.10000, 42.46778 +21.20000, 42.46778 +21.30000, 42.46778 +21.40000, 42.46778 +21.50000, 42.46778 +21.60000, 42.41056 +21.70000, 42.35333 +21.80000, 42.35333 +21.90000, 42.39148 +22.00000, 42.42963 +22.10000, 42.50593 +22.20000, 42.54408 +22.30000, 42.62038 +22.40000, 42.81113 +22.50000, 42.96373 +22.60000, 43.19263 +22.70000, 43.40245 +22.80000, 43.86025 +22.90000, 44.20360 +23.00000, 44.48972 +23.10000, 45.25272 +23.20000, 45.90127 +23.30000, 46.45444 +23.40000, 46.96946 +23.50000, 47.80876 +23.60000, 48.38101 +23.70000, 48.99140 +23.80000, 49.73532 +23.90000, 50.21220 +24.00000, 50.61277 +24.10000, 51.01334 +24.20000, 51.54744 +24.30000, 51.77634 +24.40000, 51.96709 +24.50000, 52.21506 +24.60000, 52.36766 +24.70000, 52.44396 +24.80000, 52.52026 +24.90000, 52.57749 +25.00000, 52.61564 +25.10000, 52.67286 +25.20000, 52.74916 +25.30000, 52.78731 +25.40000, 52.82546 +25.50000, 52.84453 +25.60000, 52.86361 +25.70000, 52.90176 +25.80000, 52.86361 +25.90000, 52.74916 +26.00000, 52.67286 +26.10000, 52.53934 +26.20000, 52.34859 +26.30000, 52.15784 +26.40000, 51.94801 +26.50000, 51.71912 +26.60000, 51.31854 +26.70000, 51.03242 +26.80000, 50.74629 +26.90000, 50.26942 +27.00000, 49.94515 +27.10000, 49.71625 +27.20000, 49.27753 +27.30000, 48.68620 +27.40000, 48.38101 +27.50000, 48.01858 +27.60000, 47.65616 +27.70000, 47.35096 +27.80000, 47.12206 +27.90000, 46.93131 +28.00000, 46.60704 +28.10000, 46.39721 +28.20000, 46.24462 +28.30000, 46.05387 +28.40000, 45.92034 +28.50000, 45.80589 +28.60000, 45.72959 +28.70000, 45.61514 +28.80000, 45.53884 +28.90000, 45.46254 +29.00000, 45.34809 +29.10000, 45.23364 +29.20000, 45.11920 +29.30000, 45.00475 +29.40000, 44.79492 +29.50000, 44.64232 +29.60000, 44.47065 +29.70000, 44.22267 +29.80000, 44.03193 +29.90000, 43.87933 diff --git a/tests/Mooring/lowe_and_langley_2006/Case 5.csv b/tests/Mooring/lowe_and_langley_2006/Case 5.csv new file mode 100644 index 00000000..2e16a805 --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 5.csv @@ -0,0 +1,292 @@ +0.10000, 41.36144 +0.20000, 41.34236 +0.30000, 41.36144 +0.40000, 41.39959 +0.50000, 41.49496 +0.60000, 41.72386 +0.70000, 41.89554 +0.80000, 42.08628 +0.90000, 42.56316 +1.00000, 42.90651 +1.10000, 43.28800 +1.20000, 43.76488 +1.30000, 45.30994 +1.40000, 45.46254 +1.50000, 45.99664 +1.60000, 46.95039 +1.70000, 47.59893 +1.80000, 48.15211 +1.90000, 48.93418 +2.00000, 49.75440 +2.10000, 50.30757 +2.20000, 50.82259 +2.30000, 51.35669 +2.40000, 51.71912 +2.50000, 52.00524 +2.60000, 52.19599 +2.70000, 52.48211 +2.80000, 52.63471 +2.90000, 52.76824 +3.00000, 52.92083 +3.10000, 53.01621 +3.20000, 53.07343 +3.30000, 53.13066 +3.40000, 53.16881 +3.50000, 53.20696 +3.60000, 53.20696 +3.70000, 53.14973 +3.80000, 53.11158 +3.90000, 53.03528 +4.00000, 52.97806 +4.10000, 52.78731 +4.20000, 52.59656 +4.30000, 52.44396 +4.40000, 52.15784 +4.50000, 51.92894 +4.60000, 51.68097 +4.70000, 51.29947 +4.80000, 51.03242 +4.90000, 50.76537 +5.00000, 50.47925 +5.10000, 50.04052 +5.20000, 49.73532 +5.30000, 49.44920 +5.40000, 48.91510 +5.50000, 48.59083 +5.60000, 48.38101 +5.70000, 48.15211 +5.80000, 47.80876 +5.90000, 47.61801 +6.00000, 47.38911 +6.10000, 47.16021 +6.20000, 47.02669 +6.30000, 46.89316 +6.40000, 46.79779 +6.50000, 46.64519 +6.60000, 46.58796 +6.70000, 46.51166 +6.80000, 46.39721 +6.90000, 46.32091 +7.00000, 46.22554 +7.10000, 46.13017 +7.20000, 45.95849 +7.30000, 45.82497 +7.40000, 45.67237 +7.50000, 45.42439 +7.60000, 45.25272 +7.70000, 45.06197 +7.80000, 44.87122 +7.90000, 44.54695 +8.00000, 44.37527 +8.10000, 44.16545 +8.20000, 43.82210 +8.30000, 43.61228 +8.40000, 43.44060 +8.50000, 43.26893 +8.60000, 42.98281 +8.70000, 42.83021 +8.80000, 42.67761 +8.90000, 42.44871 +9.00000, 42.31518 +9.10000, 42.20073 +9.20000, 41.99091 +9.30000, 41.87646 +9.40000, 41.78109 +9.50000, 41.66664 +9.60000, 41.47589 +9.70000, 41.34236 +9.80000, 41.20884 +9.90000, 41.09439 +10.40000, 41.11346 +10.50000, 41.26606 +10.60000, 41.51404 +10.70000, 41.70479 +10.80000, 41.97183 +10.90000, 42.23888 +11.00000, 42.92558 +11.10000, 43.45968 +11.20000, 43.95563 +11.30000, 44.79492 +11.40000, 45.44347 +11.50000, 46.05387 +11.60000, 46.70241 +11.70000, 47.71338 +11.80000, 48.36193 +11.90000, 48.95325 +12.00000, 49.88792 +12.10000, 50.44110 +12.20000, 50.93704 +12.30000, 51.41392 +12.40000, 52.06246 +12.50000, 52.34859 +12.60000, 52.57749 +12.70000, 52.80639 +12.80000, 52.93991 +12.90000, 53.03528 +13.00000, 53.11158 +13.10000, 53.20696 +13.20000, 53.26418 +13.30000, 53.30233 +13.40000, 53.32141 +13.50000, 53.30233 +13.60000, 53.24511 +13.70000, 53.18788 +13.80000, 53.09251 +13.90000, 52.99713 +14.00000, 52.88268 +14.10000, 52.67286 +14.20000, 52.50119 +14.30000, 52.34859 +14.40000, 52.02431 +14.50000, 51.83356 +14.60000, 51.58559 +14.70000, 51.35669 +14.80000, 50.89889 +14.90000, 50.61277 +15.00000, 50.40295 +15.10000, 49.86885 +15.20000, 49.54458 +15.30000, 49.27753 +15.40000, 49.01048 +15.50000, 48.60990 +15.60000, 48.36193 +15.70000, 48.15211 +15.80000, 47.82783 +15.90000, 47.61801 +16.00000, 47.44633 +16.10000, 47.27466 +16.20000, 47.10299 +16.30000, 47.00761 +16.40000, 46.87409 +16.50000, 46.72149 +16.60000, 46.64519 +16.70000, 46.58796 +16.80000, 46.53074 +16.90000, 46.39721 +17.00000, 46.32091 +17.10000, 46.24462 +17.20000, 46.05387 +17.30000, 45.92034 +17.40000, 45.80589 +17.50000, 45.65329 +17.60000, 45.36717 +17.70000, 45.10012 +17.80000, 44.87122 +17.90000, 44.56602 +18.00000, 44.37527 +18.10000, 44.16545 +18.20000, 43.97470 +18.30000, 43.66950 +18.40000, 43.49783 +18.50000, 43.34523 +18.60000, 43.07818 +18.70000, 42.88743 +18.80000, 42.69668 +18.90000, 42.56316 +19.00000, 42.31518 +19.10000, 42.18166 +19.20000, 42.06721 +19.30000, 41.87646 +19.40000, 41.78109 +19.50000, 41.68571 +19.60000, 41.51404 +19.70000, 41.38051 +19.80000, 41.28514 +19.90000, 41.18976 +20.30000, 41.13254 +20.40000, 41.18976 +20.50000, 41.34236 +20.60000, 41.51404 +20.70000, 41.83831 +20.80000, 42.12443 +20.90000, 42.48686 +21.00000, 43.05910 +21.10000, 43.53598 +21.20000, 44.05100 +21.30000, 44.56602 +21.40000, 45.48162 +21.50000, 46.14924 +21.60000, 46.77871 +21.70000, 47.80876 +21.80000, 48.59083 +21.90000, 49.29660 +22.00000, 49.94515 +22.10000, 50.68907 +22.20000, 51.14687 +22.30000, 51.50929 +22.40000, 52.02431 +22.50000, 52.34859 +22.60000, 52.57749 +22.70000, 52.74916 +22.80000, 52.93991 +22.90000, 53.03528 +23.00000, 53.13066 +23.10000, 53.24511 +23.20000, 53.30233 +23.30000, 53.32141 +23.40000, 53.32141 +23.50000, 53.32141 +23.60000, 53.32141 +23.70000, 53.30233 +23.80000, 53.20696 +23.90000, 53.11158 +24.00000, 52.99713 +24.10000, 52.90176 +24.20000, 52.67286 +24.30000, 52.50119 +24.40000, 52.31044 +24.50000, 51.92894 +24.60000, 51.66189 +24.70000, 51.37577 +24.80000, 50.97519 +24.90000, 50.66999 +25.00000, 50.38387 +25.10000, 50.11682 +25.20000, 49.65902 +25.30000, 49.37290 +25.40000, 49.06770 +25.50000, 48.66713 +25.60000, 48.43823 +25.70000, 48.20933 +25.80000, 47.98043 +25.90000, 47.63708 +26.00000, 47.44633 +26.10000, 47.27466 +26.20000, 47.08391 +26.30000, 46.95039 +26.40000, 46.83594 +26.50000, 46.75964 +26.60000, 46.64519 +26.70000, 46.56889 +26.80000, 46.49259 +26.90000, 46.35906 +27.00000, 46.28277 +27.10000, 46.22554 +27.20000, 45.99664 +27.30000, 45.82497 +27.40000, 45.67237 +27.50000, 45.50069 +27.60000, 45.23364 +27.70000, 45.06197 +27.80000, 44.85215 +27.90000, 44.66140 +28.00000, 44.33712 +28.10000, 44.14637 +28.20000, 43.93655 +28.30000, 43.63135 +28.40000, 43.44060 +28.50000, 43.28800 +28.60000, 43.15448 +28.70000, 42.84928 +28.80000, 42.63946 +28.90000, 42.52501 +29.00000, 42.31518 +29.10000, 42.16258 +29.20000, 42.02906 +29.30000, 41.93369 +29.40000, 41.76201 +29.50000, 41.66664 +29.60000, 41.57126 +29.70000, 41.39959 +29.80000, 41.26606 +29.90000, 41.22791 diff --git a/tests/Mooring/lowe_and_langley_2006/Case 6.csv b/tests/Mooring/lowe_and_langley_2006/Case 6.csv new file mode 100644 index 00000000..8bf90aff --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/Case 6.csv @@ -0,0 +1,299 @@ +0.10000, 51.77634 +0.20000, 51.54744 +0.30000, 51.39484 +0.40000, 51.20409 +0.50000, 51.05149 +0.60000, 50.80352 +0.70000, 50.66999 +0.80000, 50.51740 +0.90000, 50.26942 +1.00000, 50.13590 +1.10000, 50.02145 +1.20000, 49.92607 +1.30000, 49.73532 +1.40000, 49.62087 +1.50000, 49.52550 +1.60000, 49.35383 +1.70000, 49.27753 +1.80000, 49.20123 +1.90000, 49.12493 +2.00000, 48.95325 +2.10000, 48.85788 +2.20000, 48.72435 +2.30000, 48.49545 +2.40000, 48.34286 +2.50000, 48.19026 +2.60000, 47.99951 +2.70000, 47.67523 +2.80000, 47.35096 +2.90000, 46.98854 +3.00000, 46.64519 +3.10000, 46.39721 +3.20000, 46.07294 +3.30000, 45.76774 +3.40000, 45.38624 +3.50000, 45.08105 +3.60000, 44.89030 +3.70000, 44.50880 +3.80000, 44.26082 +3.90000, 43.99378 +4.00000, 43.59320 +4.10000, 43.28800 +4.20000, 43.00188 +4.30000, 42.75391 +4.40000, 42.41056 +4.50000, 42.18166 +4.60000, 41.97183 +4.70000, 41.60941 +4.80000, 41.39959 +4.90000, 41.20884 +5.00000, 40.99901 +5.10000, 40.75104 +5.20000, 40.57937 +5.30000, 40.44584 +5.40000, 40.23602 +5.50000, 40.14064 +5.60000, 40.06434 +5.70000, 40.04527 +5.80000, 40.08342 +5.90000, 40.15972 +6.00000, 40.31232 +6.10000, 40.57937 +6.20000, 40.82734 +6.30000, 41.13254 +6.40000, 41.47589 +6.50000, 42.00998 +6.60000, 42.41056 +6.70000, 42.86836 +6.80000, 43.74580 +6.90000, 44.41342 +7.00000, 45.06197 +7.10000, 45.61514 +7.20000, 46.47351 +7.30000, 47.00761 +7.40000, 47.50356 +7.50000, 48.28563 +7.60000, 48.72435 +7.70000, 49.12493 +7.80000, 49.48735 +7.90000, 49.86885 +8.00000, 50.15497 +8.10000, 50.42202 +8.20000, 50.84167 +8.30000, 51.08964 +8.40000, 51.28039 +8.50000, 51.47114 +8.60000, 51.73819 +8.70000, 51.89079 +8.80000, 52.04339 +8.90000, 52.27229 +9.00000, 52.36766 +9.10000, 52.46304 +9.20000, 52.55841 +9.30000, 52.59656 +9.40000, 52.59656 +9.50000, 52.59656 +9.60000, 52.57749 +9.70000, 52.50119 +9.80000, 52.42489 +9.90000, 52.27229 +10.00000, 52.15784 +10.10000, 52.04339 +10.20000, 51.89079 +10.30000, 51.71912 +10.40000, 51.60467 +10.50000, 51.45207 +10.60000, 51.22317 +10.70000, 51.07057 +10.80000, 50.89889 +10.90000, 50.74629 +11.00000, 50.51740 +11.10000, 50.36480 +11.20000, 50.25035 +11.30000, 50.05960 +11.40000, 49.92607 +11.50000, 49.79255 +11.60000, 49.69717 +11.70000, 49.54458 +11.80000, 49.43013 +11.90000, 49.27753 +12.00000, 49.06770 +12.10000, 48.91510 +12.20000, 48.76250 +12.30000, 48.57175 +12.40000, 48.22841 +12.50000, 48.01858 +12.60000, 47.77061 +12.70000, 47.38911 +12.80000, 47.14114 +12.90000, 46.81686 +13.00000, 46.53074 +13.10000, 46.14924 +13.20000, 45.93942 +13.30000, 45.57699 +13.40000, 45.17642 +13.50000, 44.96660 +13.60000, 44.60417 +13.70000, 44.27990 +13.80000, 43.91748 +13.90000, 43.68858 +14.00000, 43.44060 +14.10000, 43.11633 +14.20000, 42.88743 +14.30000, 42.65853 +14.40000, 42.35333 +14.50000, 42.14351 +14.60000, 41.95276 +14.70000, 41.76201 +14.80000, 41.49496 +14.90000, 41.32329 +15.00000, 41.17069 +15.10000, 40.84642 +15.20000, 40.63659 +15.30000, 40.50307 +15.40000, 40.38862 +15.50000, 40.31232 +15.60000, 40.23602 +15.70000, 40.21694 +15.80000, 40.29324 +15.90000, 40.35047 +16.00000, 40.46492 +16.10000, 40.69382 +16.20000, 40.99901 +16.30000, 41.22791 +16.40000, 41.70479 +16.50000, 42.35333 +16.60000, 42.84928 +16.70000, 43.34523 +16.80000, 43.87933 +16.90000, 44.69955 +17.00000, 45.27179 +17.10000, 45.78682 +17.20000, 46.64519 +17.30000, 47.14114 +17.40000, 47.63708 +17.50000, 48.09488 +17.60000, 48.72435 +17.70000, 49.20123 +17.80000, 49.63995 +17.90000, 50.02145 +18.00000, 50.32665 +18.10000, 50.55555 +18.20000, 50.76537 +18.30000, 51.07057 +18.40000, 51.26132 +18.50000, 51.45207 +18.60000, 51.71912 +18.70000, 51.89079 +18.80000, 52.06246 +18.90000, 52.15784 +19.00000, 52.34859 +19.10000, 52.46304 +19.20000, 52.55841 +19.30000, 52.59656 +19.40000, 52.59656 +19.50000, 52.57749 +19.60000, 52.52026 +19.70000, 52.46304 +19.80000, 52.40581 +19.90000, 52.31044 +20.00000, 52.11969 +20.10000, 51.98616 +20.20000, 51.89079 +20.30000, 51.66189 +20.40000, 51.50929 +20.50000, 51.31854 +20.60000, 51.14687 +20.70000, 50.91797 +20.80000, 50.76537 +20.90000, 50.61277 +21.00000, 50.42202 +21.10000, 50.28850 +21.20000, 50.13590 +21.30000, 50.02145 +21.40000, 49.83070 +21.50000, 49.71625 +21.60000, 49.63995 +21.70000, 49.48735 +21.80000, 49.31568 +21.90000, 49.16308 +22.00000, 49.04863 +22.10000, 48.83880 +22.20000, 48.68620 +22.30000, 48.51453 +22.40000, 48.20933 +22.50000, 47.99951 +22.60000, 47.78968 +22.70000, 47.56078 +22.80000, 47.16021 +22.90000, 46.93131 +23.00000, 46.68334 +23.10000, 46.20647 +23.20000, 45.82497 +23.30000, 45.53884 +23.40000, 45.29087 +23.50000, 44.90937 +23.60000, 44.66140 +23.70000, 44.39435 +23.80000, 44.01285 +23.90000, 43.76488 +24.00000, 43.51690 +24.10000, 43.30708 +24.20000, 42.96373 +24.30000, 42.73483 +24.40000, 42.50593 +24.50000, 42.16258 +24.60000, 41.91461 +24.70000, 41.68571 +24.80000, 41.41866 +24.90000, 41.24699 +25.00000, 41.03716 +25.10000, 40.86549 +25.20000, 40.59844 +25.30000, 40.42677 +25.40000, 40.33139 +25.50000, 40.17879 +25.60000, 40.15972 +25.70000, 40.15972 +25.80000, 40.15972 +25.90000, 40.27417 +26.00000, 40.42677 +26.10000, 40.63659 +26.20000, 40.96086 +26.30000, 41.28514 +26.40000, 41.64756 +26.50000, 42.08628 +26.60000, 42.75391 +26.70000, 43.26893 +26.80000, 43.84118 +26.90000, 44.64232 +27.00000, 45.19550 +27.10000, 45.74867 +27.20000, 46.58796 +27.30000, 47.33189 +27.40000, 47.80876 +27.50000, 48.36193 +27.60000, 48.89603 +27.70000, 49.27753 +27.80000, 49.63995 +27.90000, 49.98330 +28.00000, 50.36480 +28.10000, 50.59370 +28.20000, 50.84167 +28.30000, 51.22317 +28.40000, 51.43299 +28.50000, 51.58559 +28.60000, 51.73819 +28.70000, 52.04339 +28.80000, 52.25321 +28.90000, 52.38674 +29.00000, 52.53934 +29.10000, 52.59656 +29.20000, 52.67286 +29.30000, 52.71101 +29.40000, 52.73009 +29.50000, 52.69194 +29.60000, 52.65379 +29.70000, 52.55841 +29.80000, 52.44396 +29.90000, 52.38674 diff --git a/tests/Mooring/lowe_and_langley_2006/line.txt b/tests/Mooring/lowe_and_langley_2006/line.txt new file mode 100644 index 00000000..4e594f29 --- /dev/null +++ b/tests/Mooring/lowe_and_langley_2006/line.txt @@ -0,0 +1,30 @@ +MoorDyn input file for a flexible jumper (Lowe and Langley, 2006) +True Echo echo the input file data (flag) +----------------------- LINE TYPES ------------------------------------------ +TypeName Diam Mass/m EA BA/-zeta EI Cd Ca CdAx CaAx +(name) (m) (kg/m) (N) (N-s/-) (N-m^2) (-) (-) (-) (-) +main 0.396 165.0 500.0e6 -0.5 120.8e3 1.0 1.0 0.0 0.0 +---------------------- CONNECTION PROPERTIES -------------------------------- +ID Type X Y Z Mass Volume CdA Ca +(#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) +1 Fixed -100 0 -55 0 0 0 0 +2 Coupled 0 0 -5 0 0 0 0 +---------------------- LINES ---------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs +(#) (name) (#) (#) (m) (-) (-) +1 main 1 2 170 68 - +---------------------- OPTIONS ----------------------------------------- +0 writeLog Write a log file +0.001 dtM Model time step (s) +3.0e6 kBot bottom stiffness (Pa/m) +3.0e5 cBot bottom damping (Pa-s/m) +100 WtrDpth water depth (m) +1000.0 WtrDnsty water density (kg/m^3) +9.807 g gravity (m/s^2) +midpoint5 tScheme Time integration scheme +5.0 CdScaleIC Initial Condition generation drag factor +30 TmaxIC Initial Condition generation maximum time (s) +1.0 dtIC Initial Condition generation convergence tests (s) +5e-3 threshIC Initial Condition generation convergence threshold +1 WaveKin The wave kinematics are provided through the API (-) +------------------------- need this line -------------------------------------- diff --git a/tests/lowe_and_langley_2006.cpp b/tests/lowe_and_langley_2006.cpp new file mode 100644 index 00000000..90e423fd --- /dev/null +++ b/tests/lowe_and_langley_2006.cpp @@ -0,0 +1,321 @@ +/* + * Copyright (c) 2022 Jose Luis Cercos-Pita + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** @file lowe_and_langley_2006.cpp + * Validation against the Lowe and Langley OMAE 2006 paper. Their results have + * been digitalized with https://github.com/automeris-io/WebPlotDigitizer + */ + +#include "MoorDyn2.h" +#include +#include +#include +#include +#include +#include +#include +#define _USE_MATH_DEFINES +#include +#include + +using namespace std; + +/// Time step in the moton files +const double DT = 0.001; + +/** @brief Parse a line of a tabulated file + * @param line The line of text + * @return The vector of values + */ +vector +parse_tab_line(const char* line) +{ + vector fields; + const char del = ','; + stringstream sstream(line); + string word; + while (std::getline(sstream, word, del)) { + fields.push_back(stod(word.c_str())); + } + return fields; +} + +/** @brief Read a tabulated file + * @param filepath The tabulated file path + * @return 2D array + */ +vector> +read_tab_file(const char* filepath) +{ + vector> data; + fstream f; + f.open(filepath, ios::in); + if (!f.is_open()) + return data; + string line; + while (getline(f, line)) { + data.push_back(parse_tab_line(line.c_str())); + } + f.close(); + + return data; +} + +/** @brief Initialize the jumper + * @return The MoorDyn system, the line and the failead + */ +std::tuple +init() +{ + MoorDyn system = MoorDyn_Create("Mooring/lowe_and_langley_2006/line.txt"); + REQUIRE(system); + + unsigned int n_dof; + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); + + auto line = MoorDyn_GetLine(system, 1); + REQUIRE(line); + auto point = MoorDyn_GetPoint(system, 2); + REQUIRE(point); + + // Set the fairlead points, as they are in the config file + double r[3], u[3]; + REQUIRE(MoorDyn_GetPointPos(point, r) == MOORDYN_SUCCESS); + std::fill(u, u + 3, 0.0); + REQUIRE(MoorDyn_Init(system, r, u) == MOORDYN_SUCCESS); + + return {system, line, point}; +} + +TEST_CASE("Stationary") +{ + const double tol = 0.2; + const double top_ten_ref[3] = {11.40, 0.0, 45.71}; + const double bottom_ten_ref[3] = {-11.40, 0.0, 24.04}; + auto [system, line, point] = init(); + unsigned int n_segments; + REQUIRE(MoorDyn_GetLineN(line, &n_segments) == MOORDYN_SUCCESS); + + double top_ten[3], bottom_ten[3]; + REQUIRE(MoorDyn_GetPointForce(point, top_ten) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_GetLineNodeForce(line, 0, bottom_ten) == MOORDYN_SUCCESS); + for (unsigned int i = 0; i < 3; i++) { + REQUIRE(std::abs(top_ten_ref[i] + 1.0e-3 * top_ten[i]) < tol); + REQUIRE(std::abs(bottom_ten_ref[i] + 1.0e-3 * bottom_ten[i]) < tol); + } +} + +/** @brief Run a linear motion case + * @param case_id Either 1, 2 or 3 + */ +void +case123(const unsigned int case_id) +{ + REQUIRE(((case_id >= 1) && (case_id <= 3))); + const double tol = 1.0; + const double A = 10.0; + const double T = 27.0; + double dt = 0.005; + + stringstream ref_file; + ref_file << "Mooring/lowe_and_langley_2006/Case " << case_id << ".csv"; + auto ref_data = read_tab_file(ref_file.str().c_str()); + unsigned int ref_data_index = 0; + + auto [system, line, point] = init(); + unsigned int n_segments; + REQUIRE(MoorDyn_GetLineN(line, &n_segments) == MOORDYN_SUCCESS); + + double r0[3], u[3]; + REQUIRE(MoorDyn_GetPointPos(point, r0) == MOORDYN_SUCCESS); + std::fill(u, u + 3, 0.0); + + double t = 0.0; + const double t_ramp = 1.0 * T; + while (t < 80.0 + t_ramp) { + double f = t >= t_ramp ? 1.0 : t / t_ramp; + f = f * f * f * (6 * f * f - 15 * f + 10); + + double r[3], ten[3]; + REQUIRE(MoorDyn_GetPointPos(point, r) == MOORDYN_SUCCESS); + double x = r0[case_id - 1] + A * sin(2.0 * M_PI / T * (t + dt)); + x = r0[case_id - 1] + f * (x - r0[case_id - 1]); + u[case_id - 1] = (x - r[case_id - 1]) / dt; + REQUIRE(MoorDyn_Step(system, r, u, ten, &t, &dt) == MOORDYN_SUCCESS); + + const double t_ref = t - t_ramp; + if (t_ref >= ref_data[ref_data_index][0]) { + REQUIRE(MoorDyn_GetLineNodeForce( + line, n_segments, ten) == MOORDYN_SUCCESS); + const double ten_kn = 1.0e-3 * sqrt( + ten[0] * ten[0] + ten[1] * ten[1] + ten[2] * ten[2]); + REQUIRE(std::abs(ten_kn - ref_data[ref_data_index][1]) < tol); + ref_data_index++; + if (ref_data_index >= ref_data.size()) + break; + } + } + + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} + +TEST_CASE("Case 1") +{ + case123(1); +} + +TEST_CASE("Case 2") +{ + case123(2); +} + +TEST_CASE("Case 3") +{ + case123(3); +} + +#define Z 100.0 + +/** @brief Solve the linear wave theory on a point + * @param A Wave amplitude + * @param T Wave period + * @param phi Wave phase + * @param d Wave direction angle + * @param t Time + * @param r Point where wave shall be solved + * @param u Output velocity + * @param a Output acceleration + */ +void +wave(double A, double T, double phi, double d, double t, + const double* r, double* u, double* a) +{ + const double omega = 2.0 * M_PI / T; + const double k = omega * omega / 9.81; + + const double x = r[0] * cos(d) + r[1] * sin(d); + const double cs = cos(k * x - omega * t + phi); + const double ss = sin(k * x - omega * t + phi); + + const double ch = cosh(k * (r[2] + Z)) / cosh(k * Z); + const double sh = sinh(k * (r[2] + Z)) / cosh(k * Z); + + const double uA = omega * A; + const double aA = omega * uA; + + u[0] = uA * cs * ch * cos(d); + u[1] = uA * cs * ch * sin(d); + u[2] = uA * ss * sh; + a[0] = aA * ss * ch * cos(d); + a[1] = aA * ss * ch * sin(d); + a[2] = -aA * cs * sh; +} + +/** @brief Run a wave driven case + * @param case_id Either 4, 5 or 6 + */ +void +case456(const unsigned int case_id, double phi) +{ + REQUIRE(((case_id >= 4) && (case_id <= 6))); + const double tol = 1.0; + const double A = 5.0; + const double T = 10.0; + double dt = 0.005; + + stringstream ref_file; + ref_file << "Mooring/lowe_and_langley_2006/Case " << case_id << ".csv"; + auto ref_data = read_tab_file(ref_file.str().c_str()); + unsigned int ref_data_index = 0; + + auto [system, line, point] = init(); + unsigned int nwp; + REQUIRE(MoorDyn_ExternalWaveKinInit(system, &nwp) == MOORDYN_SUCCESS); + double *rwp = (double*)malloc(3 * nwp * sizeof(double)); + double *uwp = (double*)malloc(3 * nwp * sizeof(double)); + double *awp = (double*)malloc(3 * nwp * sizeof(double)); + REQUIRE((rwp && uwp && awp)); + + unsigned int n_segments; + REQUIRE(MoorDyn_GetLineN(line, &n_segments) == MOORDYN_SUCCESS); + + double r[3], u[3]; + REQUIRE(MoorDyn_GetPointPos(point, r) == MOORDYN_SUCCESS); + std::fill(u, u + 3, 0.0); + + double t = 0.0; + const double t_ramp = 2.0 * T; + while (t < 30.0 + t_ramp) { + double ten[3]; + + REQUIRE(MoorDyn_ExternalWaveKinGetCoordinates( + system, rwp) == MOORDYN_SUCCESS); + for (unsigned int i = 0; i < nwp; i++) { + wave(A, T, phi, (case_id - 4) * 0.25 * M_PI, t + 0.5 * dt, + rwp + 3 * i, uwp + 3 * i, awp + 3 * i); + } + REQUIRE(MoorDyn_ExternalWaveKinSet( + system, uwp, awp, t + 0.5 * dt) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_Step(system, r, u, ten, &t, &dt) == MOORDYN_SUCCESS); + + const double t_ref = t - t_ramp; + if (t_ref >= ref_data[ref_data_index][0]) { + REQUIRE(MoorDyn_GetLineNodeForce( + line, n_segments, ten) == MOORDYN_SUCCESS); + const double ten_kn = 1.0e-3 * sqrt( + ten[0] * ten[0] + ten[1] * ten[1] + ten[2] * ten[2]); + REQUIRE(std::abs(ten_kn - ref_data[ref_data_index][1]) < tol); + ref_data_index++; + if (ref_data_index >= ref_data.size()) + break; + } + } + + free(rwp); + free(uwp); + free(awp); + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); +} + +TEST_CASE("Case 4") +{ + case456(4, 230.0 * M_PI / 180.0); +} + +TEST_CASE("Case 5") +{ + case456(5, 165.0 * M_PI / 180.0); +} + +TEST_CASE("Case 6") +{ + case456(6, 0.0 * M_PI / 180.0); +} From bf70e25b9683e0dee43e7f8bc526cb2be5fc9ea5 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 12 Jun 2024 10:34:23 +0200 Subject: [PATCH 089/145] Dammit Windows! --- tests/lowe_and_langley_2006.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/lowe_and_langley_2006.cpp b/tests/lowe_and_langley_2006.cpp index 90e423fd..776c2314 100644 --- a/tests/lowe_and_langley_2006.cpp +++ b/tests/lowe_and_langley_2006.cpp @@ -33,6 +33,7 @@ * been digitalized with https://github.com/automeris-io/WebPlotDigitizer */ +#define _USE_MATH_DEFINES #include "MoorDyn2.h" #include #include @@ -41,7 +42,6 @@ #include #include #include -#define _USE_MATH_DEFINES #include #include From e9a153b84f6be7f898199cdbf2872d50a4242ec2 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 05:50:30 +0200 Subject: [PATCH 090/145] Move the CFL documentation to the right place --- docs/inputs.rst | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 478a6411..0037aa8d 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -165,8 +165,7 @@ parenthesis). As such, they are all optional settings, although some of them (su 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 (3.402823e+38) – desired mooring model maximum time step (s) - - CFL (0.5) – desired mooring model maximum CFL factor + - dtM (0.001) – desired mooring model time step (s) - g (9.80665) – gravitational constant (m/s^2) - rhoW (1025.0)– water density (kg/m^3) - WtrDpth (0.0) – water depth (m) @@ -554,10 +553,13 @@ indicate which version has that as the default. As such, they are all optional s 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 or the OpenFAST time step. + - 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 (3.402823e+38) – desired mooring model maximum time step (s). In + MoorDyn-F if this is left blank it defaults to the + :ref:`driver file ` dtC value or the OpenFAST time step. + - CFL (0.5) – Desired mooring model maximum Courant-Friedich-Lewy factor - tScheme (RK2): The time integrator. It should be one of Euler, LEuler, Heun, RK2, RK4, AB2, AB3, AB4, LAB2, LAB3, LAB4, BEuler\ *N*, Midpoint\ *N*, ACA\ *N*. Look at the @@ -594,11 +596,15 @@ The list of possible options is: 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. +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: + - CFL: In MoorDyn-F the time step is governed by the + :ref:`driver file ` dtC value or the OpenFAST time step. To + override it just the option dtM is available. - 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 From c5c7c22028b7e541384ee0e662f6596fa2b46ae8 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 05:52:26 +0200 Subject: [PATCH 091/145] MoorDyn 2 -> Moordyn-C version 2 --- docs/tschemes.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/tschemes.rst b/docs/tschemes.rst index cc48abe4..6723ae8a 100644 --- a/docs/tschemes.rst +++ b/docs/tschemes.rst @@ -2,8 +2,8 @@ Time Schemes ============ .. _tschemes: -MoorDyn 2 is deployed with several time schemes, with different features, -strengths and weaknesses. +MoorDyn-C version 2 is deployed with several time schemes, with different +features, strengths and weaknesses. They can be deivided into 2 main categories: Explicit and implicit ones. From a64ce708fba61e109351aa5474e0cfb5d9005db9 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 05:58:24 +0200 Subject: [PATCH 092/145] Added a note to clarify that time schemes are only available on MDC --- docs/tschemes.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/docs/tschemes.rst b/docs/tschemes.rst index 6723ae8a..f969f891 100644 --- a/docs/tschemes.rst +++ b/docs/tschemes.rst @@ -5,6 +5,11 @@ Time Schemes MoorDyn-C version 2 is deployed with several time schemes, with different features, strengths and weaknesses. +.. note:: +MoorDyn-F only uses the Runge-Kutta 2 (RK2) time scheme in the interest +of efficiency for OpenFAST simulations. +Time scheme specification is not an option in the MoorDyn-F input files. + They can be deivided into 2 main categories: Explicit and implicit ones. Explicit: From 63d8ddf1a520e20c805f15bd07ce61be8dfa2cd0 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 05:58:41 +0200 Subject: [PATCH 093/145] Added the Wilson scheme to the list --- docs/inputs.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 0037aa8d..da8e7785 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -562,7 +562,7 @@ The list of possible options is: - CFL (0.5) – Desired mooring model maximum Courant-Friedich-Lewy factor - tScheme (RK2): The time integrator. It should be one of Euler, LEuler, Heun, RK2, RK4, AB2, AB3, AB4, LAB2, LAB3, LAB4, - BEuler\ *N*, Midpoint\ *N*, ACA\ *N*. Look at the + BEuler\ *N*, Midpoint\ *N*, ACA\ *N*, Wilson\ *N*. Look at the :ref:`time schemes documentation ` to learn more about this. - g (9.81): The gravity acceleration (m/s^2) - rho (1025): The water density (kg/m^3) From 9055bb381bd81c86aeadb8c1c95d59865e7b5f2e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 06:02:58 +0200 Subject: [PATCH 094/145] Typo that twisted MDF and MDC --- docs/inputs.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index da8e7785..92169634 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -566,7 +566,7 @@ The list of possible options is: :ref:`time schemes documentation ` to learn more about this. - 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. + - WtrDpth (0.0): The water depth (m). In MoorDyn-C 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 threshold amount of time the system must be converged for to be @@ -615,8 +615,8 @@ The following MoorDyn-C options are not supported by MoorDyn-F: - 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 + - Seafloor file: MoorDyn-C 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. From 44c8497a9b3127c949542186edbd9ed27404db8c Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 09:09:22 +0200 Subject: [PATCH 095/145] Typo on the name --- source/Time.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Time.cpp b/source/Time.cpp index 3fff30b9..bf0ef085 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -854,7 +854,7 @@ create_time_scheme(const std::string& name, out = new AndersonEulerScheme(log, waves, iters, 0.5); } catch (std::invalid_argument) { stringstream s; - s << "Invalid Midpoint name format '" << name << "'"; + s << "Invalid Anderson name format '" << name << "'"; throw moordyn::invalid_value_error(s.str().c_str()); } } else if (str::startswith(str::lower(name), "aca")) { From 37a218a28b1240c7e31e1b4e5758927be56a0338 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 14 Jun 2024 09:09:36 +0200 Subject: [PATCH 096/145] Documented the new time schemes --- docs/features.rst | 143 ++++++++++++++++++++++++++++++++++++++++++ docs/index.rst | 1 - docs/inputs.rst | 17 +++-- docs/theory.rst | 156 +++------------------------------------------- docs/tschemes.rst | 116 ++++++++++++++++++++++++++++++++-- 5 files changed, 269 insertions(+), 164 deletions(-) create mode 100644 docs/features.rst diff --git a/docs/features.rst b/docs/features.rst new file mode 100644 index 00000000..033a1497 --- /dev/null +++ b/docs/features.rst @@ -0,0 +1,143 @@ +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.' `_ + +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,” + in Proceedings of the 35th International Conference on Ocean, Offshore and Arctic Engineering, Busan, South Korea, 2016. + `_ + + `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 + International Offshore Wind Technical Conference, San Francisco, California, Nov. 2018. `_ + +Overview of MoorDyn v2 (bodies, rods, and line failures): + + `Hall, Matthew, “MoorDyn V2: New Capabilities in Mooring System Components and Load Cases.” In Proceedings of the ASME 2020 39th International + Conference on Ocean, Offshore and Arctic Engineering. virtual conference, 2020. `_ + +Seabed friction and bathymetry approach used in v2: + + `Housner, Stein, Ericka Lozon, Bruce Martin, Dorian Brefort, and Matthew Hall, “Seabed Bathymetry and Friction Modeling in MoorDyn.” Journal of + Physics: Conference Series 2362, no. 1, Nov 2022: 012018. `_ + +Implementation of bending stiffness modeling for power cables: + + `Hall, Matthew, Senu Sirnivas, and Yi-Hsiang Yu, “Implementation and Verification of Cable Bending Stiffness in MoorDyn.” In ASME 2021 3rd International Offshore Wind + Technical Conference, V001T01A011. Virtual, Online: American Society of Mechanical Engineers, 2021. `_ + +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. `_ + +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. `_ + +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 + - KISSFFT: https://github.com/mborgerding/kissfft diff --git a/docs/index.rst b/docs/index.rst index 17add039..43879b5b 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -16,7 +16,6 @@ MoorDyn - Lumped-Mass Mooring Dynamics inputs structure api_c - troubleshooting waterkinematics theory diff --git a/docs/inputs.rst b/docs/inputs.rst index 92169634..cec6606e 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -497,8 +497,7 @@ triggered by a time or attachment tension threshold, which ever comes first. Use multiple failures for a given point, but duplicate failure configurations will be ignored. If two lines attached to a point are listed to fail (failure 1 for example), then after the failure the lines will remain attached to each other by a free point. In this multi line case, if any line -reaches the tension threshold then the failure will be triggered. The theory behind failures can be -found :ref:`here `. +reaches the tension threshold then the failure will be triggered. .. code-block:: none @@ -688,13 +687,13 @@ number looks like [OBJECT#][SUFFIX], i.e. ROD1SUB. 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) +- 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: diff --git a/docs/theory.rst b/docs/theory.rst index 2a4b038d..939579fc 100644 --- a/docs/theory.rst +++ b/docs/theory.rst @@ -1,151 +1,9 @@ -Features and References -======================= -.. _theory: +Theoretical aspects +=================== +.. _theory_global: -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. +.. toctree:: -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.' `_ - -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,” - in Proceedings of the 35th International Conference on Ocean, Offshore and Arctic Engineering, Busan, South Korea, 2016. - `_ - - `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 - International Offshore Wind Technical Conference, San Francisco, California, Nov. 2018. `_ - -Overview of MoorDyn v2 (bodies, rods, and line failures): - - `Hall, Matthew, “MoorDyn V2: New Capabilities in Mooring System Components and Load Cases.” In Proceedings of the ASME 2020 39th International - Conference on Ocean, Offshore and Arctic Engineering. virtual conference, 2020. `_ - -Seabed friction and bathymetry approach used in v2: - - `Housner, Stein, Ericka Lozon, Bruce Martin, Dorian Brefort, and Matthew Hall, “Seabed Bathymetry and Friction Modeling in MoorDyn.” Journal of - Physics: Conference Series 2362, no. 1, Nov 2022: 012018. `_ - -Implementation of bending stiffness modeling for power cables: - - `Hall, Matthew, Senu Sirnivas, and Yi-Hsiang Yu, “Implementation and Verification of Cable Bending Stiffness in MoorDyn.” In ASME 2021 3rd International Offshore Wind - Technical Conference, V001T01A011. Virtual, Online: American Society of Mechanical Engineers, 2021. `_ - -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. `_ - -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. `_ - -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 - - KISSFFT: https://github.com/mborgerding/kissfft + troubleshooting + tschemes + features diff --git a/docs/tschemes.rst b/docs/tschemes.rst index f969f891..a063494c 100644 --- a/docs/tschemes.rst +++ b/docs/tschemes.rst @@ -6,9 +6,9 @@ MoorDyn-C version 2 is deployed with several time schemes, with different features, strengths and weaknesses. .. note:: -MoorDyn-F only uses the Runge-Kutta 2 (RK2) time scheme in the interest -of efficiency for OpenFAST simulations. -Time scheme specification is not an option in the MoorDyn-F input files. + MoorDyn-F only uses the Runge-Kutta 2 (RK2) time scheme in the interest + of efficiency for OpenFAST simulations. + Time scheme specification is not an option in the MoorDyn-F input files. They can be deivided into 2 main categories: Explicit and implicit ones. @@ -152,12 +152,115 @@ an iterative process in which the time derivatives are progressively improved. The implicit time schemes enjoy a way better stability. Even more, the Newmark scheme is unconditionally stable. Then, what is the catch? Well, they can turn unstable on the internal iterative process. The half good news is that, by -construstion, relaxation can be applied on the internal iterative process. +construction, relaxation can be applied on the internal iterative process. Hereby an arbitrarily large time step can be considered, provided that a sufficiently large number of substeps are configured. See :ref:`the relaxation process ` below. +The number of substeps is set as a suffix number on the time scheme name (see +:ref:`the version 2 options `. +For instance, setting a "beuler5" time scheme options means that a +Backward-Euler scheme, with 5 substeps, will be considered. +The number of substeps might be any integer bigger than 0. + +Backward-Euler +^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + beuler5 tscheme 5 substeps Backward Euler scheme + +As discussed above, the backward Euler scheme is formulated as: + +.. math:: + r(t_{n+1}) = r(t_n) + \Delta t \frac{\mathrm{d} r}{\mathrm{d} t}(t_{n+1}) + +Backward Euler schemes are usually very stable due to the large numerical +dissipation they ussually introduce on the process. +However, its good stability features are so far hampered by the fact that the +derivative is evaluated at the end of the time step, which would drive the +inner iterative process to a divergent stage. + +Midpoint +^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + midpoint5 tscheme 5 substeps Midpoint scheme + +The midpoint scheme is evaluated as: + +.. math:: + r(t_{n+1}) = r(t_n) + \Delta t \frac{\mathrm{d} r}{\mathrm{d} t}(t_{n+1/2}) + +i.e. the derivative is evaluated on the center of the time step. +Midpoint schemes are popular because their great conservation properties when +modelling Hamiltonian systems. +The numerical tests seems to show that the Midpoint scheme exposes the bests +performance of all time schemes, being able to keep the stability and get a +great accuracy with relatively low number of substeps. + +Backward-Euler with Anderson's acceleration +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + anderson5 tscheme 5 substeps Backward Euler accelerated scheme + +This is the same scheme than the Backward-Euler scheme, but with +`Anderson accelration `_. +Unfortunately, to be able to enjoy the acceleration a large number of substeps +is usually required, making this scheme actually quite useless. + +Average Constant Acceleration +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + aca5 tscheme 5 substeps Average Constant Acceleration scheme + +This is the most popular +`Newmark-Beta scheme `_. +It is unconditionally stable for the kind of systems considered on MoorDyn. +Unfortunately it is affected by the same problem than the Backward-Euler +scheme, i.e. the derivatives are evaluated at the end of the time step, which +might result on divergent inner iterative processes. + +Wilson-theta scheme +^^^^^^^^^^^^^^^^^^^ + +Usage: + +.. code-block:: none + + ---------------------- OPTIONS ----------------------------------------- + wilson5 tscheme 5 substeps Wilson-theta scheme + +The Wilson-theta scheme is some sort of exacerbated Backward Euler scheme, i.e. +the derivative is evaluated beyond the time step itself: + +.. math:: + r(t_{n+1}) = r(t_n) + \Delta t \frac{\mathrm{d} r}{\mathrm{d} t}(t_{n+1+\theta}) + +In MoorDyn-C the popular value :math:`\theta = 1.37` is considered. +This scheme is trying to get the Backward-Euler characteristic dissipation +to a higher level. +Unfortunately, it is again affected by the eventual divergent inner iterative +processes. + Semi-implicit relaxation ------------------------ .. _relaxation: @@ -316,4 +419,7 @@ With such a set of constants the resulting speedup can be plotted: .. figure:: relaxation_005.png :alt: Backward's Euler speedup -As expected, the larger the number of iterations, the better the speedup. +As expected, the larger the number of iterations, the larger speedup. + +On MoorDyn-C each semi-implicit time scheme has its own relaxation constants, +obtained numerically to achieve good stability features From b27b57ed760036e5b4f02374969422f7fa9fac74 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 24 Jun 2024 09:11:19 +0200 Subject: [PATCH 097/145] Restructuring the documentation --- docs/conf.py | 4 +++- docs/features.rst | 8 ++++++++ docs/index.rst | 3 +-- docs/theory.rst | 1 + 4 files changed, 13 insertions(+), 3 deletions(-) diff --git a/docs/conf.py b/docs/conf.py index e304f416..f54d38cf 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -80,7 +80,9 @@ # # need to run pip install sphinx_rtd_theme to use locally html_theme = 'sphinx_rtd_theme' -# html_theme_options = {'style_nav_header_background': 'slateblue'} +html_theme_options = { + 'collapse_navigation': False +} # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, diff --git a/docs/features.rst b/docs/features.rst index 033a1497..2a4b038d 100644 --- a/docs/features.rst +++ b/docs/features.rst @@ -1,3 +1,11 @@ +Features and References +======================= +.. _theory: + +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 -------- diff --git a/docs/index.rst b/docs/index.rst index 43879b5b..3939166f 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -8,8 +8,7 @@ MoorDyn - Lumped-Mass Mooring Dynamics .. _index: .. toctree:: - :maxdepth: 5 - :hidden: + :maxdepth: 2 compiling drivers diff --git a/docs/theory.rst b/docs/theory.rst index 939579fc..58f8d85d 100644 --- a/docs/theory.rst +++ b/docs/theory.rst @@ -3,6 +3,7 @@ Theoretical aspects .. _theory_global: .. toctree:: + :maxdepth: 1 troubleshooting tschemes From da6a618283e3d8b6c53dda11e03decc4808b0bc0 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 24 Jun 2024 17:31:47 -0600 Subject: [PATCH 098/145] Add old dynamic relax, tweak to default cfl, docs fixes --- docs/inputs.rst | 27 +++-- source/MoorDyn2.cpp | 273 ++++++++++++++++++++++++++++++++------------ source/MoorDyn2.hpp | 17 ++- 3 files changed, 229 insertions(+), 88 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index cec6606e..a5f53bda 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -179,11 +179,6 @@ default value provided in parentheses) is: - ThreshIC (0.001) – convergence threshold for IC generation, acceptable relative difference between three successive fairlead tension measurements (-) -The internal time step is first taken from the dtM option, and then adjusted -according to the CFL factor, which is the ratio between the timestep and the -natural period, computed considering the math described on -:ref:`the troubleshooting section `. - 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. @@ -558,14 +553,16 @@ The list of possible options is: - dtM (3.402823e+38) – desired mooring model maximum time step (s). In MoorDyn-F if this is left blank it defaults to the :ref:`driver file ` dtC value or the OpenFAST time step. - - CFL (0.5) – Desired mooring model maximum Courant-Friedich-Lewy factor + - CFL (0.5) – Desired mooring model maximum Courant-Friedich-Lewy factor. CFL is the ratio + between the time step and the natural period, computed considering the math described in + :ref:`the troubleshooting section `. - tScheme (RK2): The time integrator. It should be one of Euler, LEuler, Heun, RK2, RK4, AB2, AB3, AB4, LAB2, LAB3, LAB4, BEuler\ *N*, Midpoint\ *N*, ACA\ *N*, Wilson\ *N*. Look at the :ref:`time schemes documentation ` to learn more about this. - 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-C the bathymetry file path can be inputted here. + - 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 threshold amount of time the system must be converged for to be @@ -593,7 +590,18 @@ The list of possible options is: - 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 ` + - SeafloorFile: A path to the :ref:`bathymetry file ` + - ICgenDynamic (0): MoorDyn-C switch for using older dynamic relaxation method (same as MoorDyn-F). + If this is enabled initial conditions are calculated with scaled drag according to CdScaleIC. + The new stationary solver in MoorDyn-C is more stable and more precise than the dynamic solver, + but it can take longer to reach equilibrium. + +A note about time steps in MoorDyn-C: The internal time step is first taken from the dtM option. If +no CFL factor is provided, then the user provided time step is used to calculate CFL and MoorDyn-C +runs using the user time step. If no time step is provided, then the user provided CFL factor is +used to calculate the time step and MoorDyn-C uses this calculated time step. If both the time step +and CFL are provided, MoorDyn-C uses the more restrictive time step between user provided and CFL +calculated. 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 @@ -614,12 +622,13 @@ The following MoorDyn-C options are not supported by MoorDyn-F: - 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-C accepts a bathymetry file path as an alternative to + - SeafloorFile: 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. + - ICgenDynamic: MoorDyn-F does not have a stationary solver for initial conditions The following options from MoorDyn-F are not supported by MoorDyn-C: diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 262b1f5a..411c0bf4 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -90,6 +90,7 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) , cfl(0.5) , dtOut(0.0) , _t_integrator(NULL) + , ICgenDynamic(0) , env(std::make_shared()) , GroundBody(NULL) , waves(nullptr) @@ -297,6 +298,8 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) ix += 3; } + if (dtM0 < (0.9 * (std::numeric_limits::max)())) cfl = (std::numeric_limits::max)(); // Is 90% of max sufficient tolerance for this check? + // Compute the timestep for (auto obj : LineList) dtM0 = (std::min)(dtM0, obj->cfl2dt(cfl)); @@ -320,25 +323,8 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // Initialize the system state _t_integrator->SetCFL(cfl); - // _t_integrator->Init(); // Let the stationary solution deal with this - - // ------------------ do dynamic relaxation IC gen -------------------- - if (!skip_ic) { - LOGMSG << "Finalizing ICs using dynamic relaxation (" << ICDfac - << "X normal drag)" << endl; - } - - // boost drag coefficients to speed static equilibrium convergence - // This is actually useless on the current implementation - for (auto obj : LineList) - obj->scaleDrag(ICDfac); - for (auto obj : PointList) - obj->scaleDrag(ICDfac); - for (auto obj : RodList) - obj->scaleDrag(ICDfac); - for (auto obj : BodyList) - obj->scaleDrag(ICDfac); + // ------------------ do IC gen -------------------- // vector to store tensions for analyzing convergence vector FairTens(LineList.size(), 0.0); @@ -354,84 +340,217 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) real best_score = (std::numeric_limits::max)(); real best_score_t = 0.0; - // //dtIC set to fraction of input so convergence is over dtIC - StationaryScheme t_integrator(_log, waves); - t_integrator.SetGround(GroundBody); - for (auto obj : BodyList) - t_integrator.AddBody(obj); - for (auto obj : RodList) - t_integrator.AddRod(obj); - for (auto obj : PointList) - t_integrator.AddPoint(obj); - for (auto obj : LineList) - t_integrator.AddLine(obj); - t_integrator.SetCFL((std::min)(cfl, 1.0)); - t_integrator.Init(); - auto n_states = t_integrator.NStates(); - while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt - // Integrate one ICD timestep (ICdt) - real t_target = ICdt; - real dt; - t_integrator.Next(); - while ((dt = t_target) > 0.0) { - if (dtM0 < dt) - dt = dtM0; - moordyn::error_id err = MOORDYN_SUCCESS; - string err_msg; - try { - t_integrator.Step(dt); - error = t_integrator.Error(); - if (!t) - error0 = error; - t = t_integrator.GetTime(); - t_target -= dt; + // dtIC set to fraction of input so convergence is over dtIC (as described in docs) + const unsigned int convergence_iters = 9; // 10 iterations, indexed 0-9 + ICdt = ICdt / (convergence_iters+1); + + if (ICgenDynamic) { + + _t_integrator->Init(); + + // boost drag coefficients to speed static equilibrium convergence + if (!skip_ic) LOGMSG << "Finalizing ICs using dynamic solve (" << ICDfac << "X normal drag)" << endl; + for (auto obj : LineList) + obj->scaleDrag(ICDfac); + for (auto obj : PointList) + obj->scaleDrag(ICDfac); + for (auto obj : RodList) + obj->scaleDrag(ICDfac); + for (auto obj : BodyList) + obj->scaleDrag(ICDfac); + + // vector to store tensions for analyzing convergence + vector FairTens(LineList.size(), 0.0); + + vector FairTensLast_col(convergence_iters, 0.0); + for (unsigned int i = 0; i < convergence_iters; i++) + FairTensLast_col[i] = 1.0 * i; + vector> FairTensLast(LineList.size(), FairTensLast_col); + + unsigned int iic = 1; // To match MDF indexing + real t = 0; + bool converged = true; + real max_error = 0.0; + unsigned int max_error_line = 0; + // The function is enclosed in parenthesis to avoid Windows min() and max() + // macros break it + // See + // https://stackoverflow.com/questions/1825904/error-c2589-on-stdnumeric-limitsdoublemin + real best_score = (std::numeric_limits::max)(); + real best_score_t = 0.0; + unsigned int best_score_line = 0; + + // //dtIC set to fraction of input so convergence is over dtIC + ICdt = ICdt / (convergence_iters+1); + while (((ICTmax-t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt + // Integrate one ICD timestep (ICdt) + real t_target = ICdt; + real dt; + _t_integrator->Next(); + while ((dt = t_target) > 0.0) { + if (dtM0 < dt) + dt = dtM0; + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + try { + _t_integrator->Step(dt); + t = _t_integrator->GetTime(); + t_target -= dt; + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + LOGERR << "t = " << t << " s" << endl; + return err; + } + } + + // Roll previous fairlead tensions for comparison + for (unsigned int lf = 0; lf < LineList.size(); lf++) { + for (int pt = convergence_iters - 1; pt > 0; pt--) + FairTensLast[lf][pt] = FairTensLast[lf][pt - 1]; + FairTensLast[lf][0] = FairTens[lf]; } - MOORDYN_CATCHER(err, err_msg); - if (err != MOORDYN_SUCCESS) { - LOGERR << "t = " << t << " s" << endl; - return err; + + // go through points to get fairlead forces + for (unsigned int lf = 0; lf < LineList.size(); lf++) + FairTens[lf] = + LineList[lf]->getNodeTen(LineList[lf]->getN()).norm(); + + // check for convergence (compare current tension at each fairlead with + // previous convergence_iters-1 values) + if (iic > convergence_iters) { + // check for any non-convergence, and continue to the next time step + // if any occurs + converged = true; + max_error = 0.0; + for (unsigned int lf = 0; lf < LineList.size(); lf++) { + for (unsigned int pt = 0; pt < convergence_iters; pt++) { + const real error = + abs(FairTens[lf] / FairTensLast[lf][pt] - 1.0); + if (error > max_error) { + max_error = error; + max_error_line = LineList[lf]->number; + } + } + } + if (max_error < best_score) { + best_score = max_error; + best_score_t = t; + best_score_line = max_error_line; + } + if (max_error > ICthresh) { + converged = false; + LOGDBG << "Dynamic relaxation t = " << t << "s (time step " + << iic << "), error = " << 100.0 * max_error + << "% on line " << max_error_line << " \r"; + } + + if (converged) + break; } + + iic++; } - if (error < best_score) { - best_score = error; - best_score_t = t; + if (!skip_ic) { + if (converged) { + LOGMSG << "Fairlead tensions converged" << endl; + } else { + LOGWRN << "Fairlead tensions did not converge" << endl; + } + LOGMSG << "Remaining error after " << t << " s = " << 100.0 * max_error + << "% on line " << max_error_line << endl; + if (!converged) { + LOGMSG << "Best score at " << best_score_t + << " s = " << 100.0 * best_score << "% on line " + << best_score_line << endl; + } } + } else { - const real error_rel = error / error0; - const real error_deriv = std::abs(error_prev - error) / error_prev; - if (!error || (error_rel < ICthresh) || (error_deriv < ICthresh)) - break; - error_prev = error; + if (!skip_ic) LOGMSG << "Finalizing ICs using static solve" << endl; + + StationaryScheme t_integrator(_log, waves); + t_integrator.SetGround(GroundBody); + + for (auto obj : BodyList) + t_integrator.AddBody(obj); + for (auto obj : RodList) + t_integrator.AddRod(obj); + for (auto obj : PointList) + t_integrator.AddPoint(obj); + for (auto obj : LineList) + t_integrator.AddLine(obj); + t_integrator.SetCFL((std::min)(cfl, 1.0)); + t_integrator.Init(); + auto n_states = t_integrator.NStates(); + while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt + // Integrate one ICD timestep (ICdt) + real t_target = ICdt; + real dt; + t_integrator.Next(); + while ((dt = t_target) > 0.0) { + if (dtM0 < dt) + dt = dtM0; + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + try { + t_integrator.Step(dt); + error = t_integrator.Error(); + if (!t) + error0 = error; + t = t_integrator.GetTime(); + t_target -= dt; + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + LOGERR << "t = " << t << " s" << endl; + return err; + } + } - LOGDBG << "Stationary solution t = " << t << "s, " - << "error avg = " << error / n_states << " m/s2, " - << "error change = " << 100.0 * error_deriv << "% \r"; - } + if (error < best_score) { + best_score = error; + best_score_t = t; + } - if (!skip_ic) { - LOGMSG << "Remaining error after " << t << " s = " - << error / n_states << " m/s2" << endl; - LOGMSG << "Best score at " << best_score_t - << " s = " << best_score / n_states << " m/s2" << endl; + const real error_rel = error / error0; + const real error_deriv = std::abs(error_prev - error) / error_prev; + if (!error || (error_rel < ICthresh) || (error_deriv < ICthresh)) + break; + error_prev = error; + + LOGDBG << "Stationary solution t = " << t << "s, " + << "error avg = " << error / n_states << " m/s2, " + << "error change = " << 100.0 * error_deriv << "% \r"; + } + + _t_integrator->SetState(t_integrator.GetState()); + if (!skip_ic) { + LOGMSG << "Remaining error after " << t << " s = " + << error / n_states << " m/s2" << endl; + LOGMSG << "Best score at " << best_score_t + << " s = " << best_score / n_states << " m/s2" << endl; + } } + // restore drag coefficients to normal values and restart time counter of // each object _t_integrator->SetTime(0.0); - _t_integrator->SetState(t_integrator.GetState()); + for (auto obj : LineList) { - obj->scaleDrag(1.0 / ICDfac); + if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); obj->setTime(0.0); } for (auto obj : PointList) - obj->scaleDrag(1.0 / ICDfac); + if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); for (auto obj : RodList) { - obj->scaleDrag(1.0 / ICDfac); + if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); obj->setTime(0.0); } for (auto obj : BodyList) - obj->scaleDrag(1.0 / ICDfac); + if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); // store passed WaveKin value to enable waves in simulation if applicable // (they're not enabled during IC gen) @@ -2064,7 +2183,9 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) this->seafloor = make_shared(_log); std::string filepath = entries[0]; this->seafloor->setup(env, filepath); - } else + } else if (name == "ICgenDynamic") + ICgenDynamic = atof(entries[0].c_str()); + else LOGWRN << "Warning: Unrecognized option '" << name << "'" << endl; } diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index 4c331f77..634de293 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -501,6 +501,8 @@ class MoorDyn final : public io::IO real ICTmax; // threshold for relative change in tensions to call it converged real ICthresh; + // use dynamic (1) or stationary (0) inital condition solver + int ICgenDynamic; // temporary wave kinematics flag used to store input value while keeping // env.WaveKin=0 for IC gen moordyn::waves::waves_settings WaveKinTemp; @@ -670,14 +672,23 @@ class MoorDyn final : public io::IO } vector flines; + int i = 0; while (f.good()) { string fline; getline(f, fline); - moordyn::str::rtrim(fline); - flines.push_back(fline); + if (i>2) { // skip first three lines as headers + moordyn::str::rtrim(fline); + flines.push_back(fline); + } + i++; } f.close(); + if (i < 5) { + LOGERR << "Error: Not enough curve data in curve file" << endl; + return MOORDYN_INVALID_INPUT; + } + for (auto fline : flines) { vector entries = moordyn::str::split(fline, ' '); if (entries.size() < 2) { @@ -692,7 +703,7 @@ class MoorDyn final : public io::IO LOGDBG << "(" << x.back() << ", " << y.back() << ")" << std::endl; } - LOGMSG << "OK" << std::endl; + LOGMSG << (i-3) << " lines of curve successfully loaded" << std::endl; return MOORDYN_SUCCESS; } From 71196204d498627bfc4e0d247e674f11fa887222 Mon Sep 17 00:00:00 2001 From: RyanDavies19 <101124339+RyanDavies19@users.noreply.github.com> Date: Mon, 24 Jun 2024 17:51:31 -0600 Subject: [PATCH 099/145] Small wording change in inputs.rst --- docs/inputs.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index a5f53bda..a5c55c35 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -600,7 +600,7 @@ A note about time steps in MoorDyn-C: The internal time step is first taken from no CFL factor is provided, then the user provided time step is used to calculate CFL and MoorDyn-C runs using the user time step. If no time step is provided, then the user provided CFL factor is used to calculate the time step and MoorDyn-C uses this calculated time step. If both the time step -and CFL are provided, MoorDyn-C uses the more restrictive time step between user provided and CFL +and CFL are provided, MoorDyn-C uses the smaller time step between user provided and CFL calculated. In MoorDyn-F, the default values for g, rhoW, and WtrDpth are the values From 9decd13392aaf12d3b9dfc7969c5c22a1f525c01 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 25 Jun 2024 09:43:54 +0200 Subject: [PATCH 100/145] Set the legacy IC as the default one (just for backward compatibility) --- source/MoorDyn2.cpp | 458 ++++++++++--------- source/MoorDyn2.hpp | 57 ++- tests/Mooring/lowe_and_langley_2006/line.txt | 1 + tests/Mooring/pendulum.txt | 1 + tests/Mooring/time_schemes.txt | 1 + tests/Mooring/wavekin_2/wavekin_3.txt | 8 +- 6 files changed, 290 insertions(+), 236 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 411c0bf4..6ddc3cb4 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -90,7 +90,7 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) , cfl(0.5) , dtOut(0.0) , _t_integrator(NULL) - , ICgenDynamic(0) + , ICgenDynamic(true) , env(std::make_shared()) , GroundBody(NULL) , waves(nullptr) @@ -185,6 +185,223 @@ moordyn::MoorDyn::~MoorDyn() delete GetLogger(); } +moordyn::error_id +moordyn::MoorDyn::icLegacy() +{ + // dtIC set to fraction of input so convergence is over dtIC (as described in docs) + const unsigned int convergence_iters = 9; // 10 iterations, indexed 0-9 + ICdt = ICdt / (convergence_iters+1); + + _t_integrator->Init(); + + LOGMSG << "Finalizing ICs using dynamic solve (" << ICDfac + << "X normal drag)" << endl; + for (auto obj : LineList) + obj->scaleDrag(ICDfac); + for (auto obj : PointList) + obj->scaleDrag(ICDfac); + for (auto obj : RodList) + obj->scaleDrag(ICDfac); + for (auto obj : BodyList) + obj->scaleDrag(ICDfac); + + // vector to store tensions for analyzing convergence + vector FairTens(LineList.size(), 0.0); + + vector FairTensLast_col(convergence_iters, 0.0); + for (unsigned int i = 0; i < convergence_iters; i++) + FairTensLast_col[i] = 1.0 * i; + vector> FairTensLast(LineList.size(), FairTensLast_col); + + unsigned int iic = 1; // To match MDF indexing + real t = 0; + bool converged = true; + real max_error = 0.0; + unsigned int max_error_line = 0; + real best_score = (std::numeric_limits::max)(); + real best_score_t = 0.0; + unsigned int best_score_line = 0; + + ICdt = ICdt / (convergence_iters+1); + while ((ICTmax - t) > (std::numeric_limits::min)()) { + // Integrate one ICD timestep (ICdt) + real t_target = ICdt; + real dt; + _t_integrator->Next(); + while ((dt = t_target) > 0.0) { + if (dtM0 < dt) + dt = dtM0; + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + try { + _t_integrator->Step(dt); + t = _t_integrator->GetTime(); + t_target -= dt; + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + LOGERR << "t = " << t << " s" << endl; + return err; + } + } + + // Roll previous fairlead tensions for comparison + for (unsigned int lf = 0; lf < LineList.size(); lf++) { + for (int pt = convergence_iters - 1; pt > 0; pt--) + FairTensLast[lf][pt] = FairTensLast[lf][pt - 1]; + FairTensLast[lf][0] = FairTens[lf]; + } + + // go through points to get fairlead forces + for (unsigned int lf = 0; lf < LineList.size(); lf++) + FairTens[lf] = + LineList[lf]->getNodeTen(LineList[lf]->getN()).norm(); + + // check for convergence (compare current tension at each fairlead with + // previous convergence_iters-1 values) + if (iic > convergence_iters) { + // check for any non-convergence, and continue to the next time step + // if any occurs + converged = true; + max_error = 0.0; + for (unsigned int lf = 0; lf < LineList.size(); lf++) { + for (unsigned int pt = 0; pt < convergence_iters; pt++) { + const real error = + abs(FairTens[lf] / FairTensLast[lf][pt] - 1.0); + if (error > max_error) { + max_error = error; + max_error_line = LineList[lf]->number; + } + } + } + if (max_error < best_score) { + best_score = max_error; + best_score_t = t; + best_score_line = max_error_line; + } + if (max_error > ICthresh) { + converged = false; + LOGDBG << "Dynamic relaxation t = " << t << "s (time step " + << iic << "), error = " << 100.0 * max_error + << "% on line " << max_error_line << " \r"; + } + + if (converged) + break; + } + + iic++; + } + + if (converged) { + LOGMSG << "Fairlead tensions converged" << endl; + } else { + LOGWRN << "Fairlead tensions did not converge" << endl; + } + LOGMSG << "Remaining error after " << t << " s = " << 100.0 * max_error + << "% on line " << max_error_line << endl; + if (!converged) { + LOGMSG << "Best score at " << best_score_t + << " s = " << 100.0 * best_score << "% on line " + << best_score_line << endl; + } + + + // We are setting the timer again later, but better doing it here as well, + // so no regressions might happens on the subinstances setTime() callings + _t_integrator->SetTime(0.0); + + // restore drag coefficients to normal values and restart time counter of + // each object + for (auto obj : LineList) { + obj->scaleDrag(1.0 / ICDfac); + obj->setTime(0.0); + } + for (auto obj : PointList) + obj->scaleDrag(1.0 / ICDfac); + for (auto obj : RodList) { + obj->scaleDrag(1.0 / ICDfac); + obj->setTime(0.0); + } + for (auto obj : BodyList) + obj->scaleDrag(1.0 / ICDfac); + return MOORDYN_SUCCESS; +} + +moordyn::error_id +moordyn::MoorDyn::icStationary() +{ + real t = 0; + real error_prev = (std::numeric_limits::max)(); + real error = (std::numeric_limits::max)(); + real error0 = error; + real best_score = (std::numeric_limits::max)(); + real best_score_t = 0.0; + + LOGMSG << "Finalizing ICs using static solve" << endl; + + StationaryScheme t_integrator(_log, waves); + t_integrator.SetGround(GroundBody); + for (auto obj : BodyList) + t_integrator.AddBody(obj); + for (auto obj : RodList) + t_integrator.AddRod(obj); + for (auto obj : PointList) + t_integrator.AddPoint(obj); + for (auto obj : LineList) + t_integrator.AddLine(obj); + t_integrator.SetCFL((std::min)(cfl, 1.0)); + t_integrator.Init(); + auto n_states = t_integrator.NStates(); + while ((ICTmax - t) > (std::numeric_limits::min)()) { + // Integrate one ICD timestep (ICdt) + real t_target = ICdt; + real dt; + t_integrator.Next(); + while ((dt = t_target) > 0.0) { + if (dtM0 < dt) + dt = dtM0; + moordyn::error_id err = MOORDYN_SUCCESS; + string err_msg; + try { + t_integrator.Step(dt); + error = t_integrator.Error(); + if (!t) + error0 = error; + t = t_integrator.GetTime(); + t_target -= dt; + } + MOORDYN_CATCHER(err, err_msg); + if (err != MOORDYN_SUCCESS) { + LOGERR << "t = " << t << " s" << endl; + return err; + } + } + + if (error < best_score) { + best_score = error; + best_score_t = t; + } + + const real error_rel = error / error0; + const real error_deriv = std::abs(error_prev - error) / error_prev; + if (!error || (error_rel < ICthresh) || (error_deriv < ICthresh)) + break; + error_prev = error; + + LOGDBG << "Stationary solution t = " << t << "s, " + << "error avg = " << error / n_states << " m/s2, " + << "error change = " << 100.0 * error_deriv << "% \r"; + } + + _t_integrator->SetState(t_integrator.GetState()); + LOGMSG << "Remaining error after " << t << " s = " + << error / n_states << " m/s2" << endl; + LOGMSG << "Best score at " << best_score_t + << " s = " << best_score / n_states << " m/s2" << endl; + return MOORDYN_SUCCESS; +} + moordyn::error_id moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) { @@ -298,7 +515,8 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) ix += 3; } - if (dtM0 < (0.9 * (std::numeric_limits::max)())) cfl = (std::numeric_limits::max)(); // Is 90% of max sufficient tolerance for this check? + if (dtM0 < (0.9 * (std::numeric_limits::max)())) + cfl = (std::numeric_limits::max)(); // Is 90% of max sufficient tolerance for this check? // Compute the timestep for (auto obj : LineList) @@ -325,233 +543,19 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) _t_integrator->SetCFL(cfl); // ------------------ do IC gen -------------------- - - // vector to store tensions for analyzing convergence - vector FairTens(LineList.size(), 0.0); - - real t = 0; - real error_prev = (std::numeric_limits::max)(); - real error = (std::numeric_limits::max)(); - real error0 = error; - // The function is enclosed in parenthesis to avoid Windows min() and max() - // macros break it - // See - // https://stackoverflow.com/questions/1825904/error-c2589-on-stdnumeric-limitsdoublemin - real best_score = (std::numeric_limits::max)(); - real best_score_t = 0.0; - - // dtIC set to fraction of input so convergence is over dtIC (as described in docs) - const unsigned int convergence_iters = 9; // 10 iterations, indexed 0-9 - ICdt = ICdt / (convergence_iters+1); - - if (ICgenDynamic) { - - _t_integrator->Init(); - - // boost drag coefficients to speed static equilibrium convergence - if (!skip_ic) LOGMSG << "Finalizing ICs using dynamic solve (" << ICDfac << "X normal drag)" << endl; - for (auto obj : LineList) - obj->scaleDrag(ICDfac); - for (auto obj : PointList) - obj->scaleDrag(ICDfac); - for (auto obj : RodList) - obj->scaleDrag(ICDfac); - for (auto obj : BodyList) - obj->scaleDrag(ICDfac); - - // vector to store tensions for analyzing convergence - vector FairTens(LineList.size(), 0.0); - - vector FairTensLast_col(convergence_iters, 0.0); - for (unsigned int i = 0; i < convergence_iters; i++) - FairTensLast_col[i] = 1.0 * i; - vector> FairTensLast(LineList.size(), FairTensLast_col); - - unsigned int iic = 1; // To match MDF indexing - real t = 0; - bool converged = true; - real max_error = 0.0; - unsigned int max_error_line = 0; - // The function is enclosed in parenthesis to avoid Windows min() and max() - // macros break it - // See - // https://stackoverflow.com/questions/1825904/error-c2589-on-stdnumeric-limitsdoublemin - real best_score = (std::numeric_limits::max)(); - real best_score_t = 0.0; - unsigned int best_score_line = 0; - - // //dtIC set to fraction of input so convergence is over dtIC - ICdt = ICdt / (convergence_iters+1); - while (((ICTmax-t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt - // Integrate one ICD timestep (ICdt) - real t_target = ICdt; - real dt; - _t_integrator->Next(); - while ((dt = t_target) > 0.0) { - if (dtM0 < dt) - dt = dtM0; - moordyn::error_id err = MOORDYN_SUCCESS; - string err_msg; - try { - _t_integrator->Step(dt); - t = _t_integrator->GetTime(); - t_target -= dt; - } - MOORDYN_CATCHER(err, err_msg); - if (err != MOORDYN_SUCCESS) { - LOGERR << "t = " << t << " s" << endl; - return err; - } - } - - // Roll previous fairlead tensions for comparison - for (unsigned int lf = 0; lf < LineList.size(); lf++) { - for (int pt = convergence_iters - 1; pt > 0; pt--) - FairTensLast[lf][pt] = FairTensLast[lf][pt - 1]; - FairTensLast[lf][0] = FairTens[lf]; - } - - // go through points to get fairlead forces - for (unsigned int lf = 0; lf < LineList.size(); lf++) - FairTens[lf] = - LineList[lf]->getNodeTen(LineList[lf]->getN()).norm(); - - // check for convergence (compare current tension at each fairlead with - // previous convergence_iters-1 values) - if (iic > convergence_iters) { - // check for any non-convergence, and continue to the next time step - // if any occurs - converged = true; - max_error = 0.0; - for (unsigned int lf = 0; lf < LineList.size(); lf++) { - for (unsigned int pt = 0; pt < convergence_iters; pt++) { - const real error = - abs(FairTens[lf] / FairTensLast[lf][pt] - 1.0); - if (error > max_error) { - max_error = error; - max_error_line = LineList[lf]->number; - } - } - } - if (max_error < best_score) { - best_score = max_error; - best_score_t = t; - best_score_line = max_error_line; - } - if (max_error > ICthresh) { - converged = false; - LOGDBG << "Dynamic relaxation t = " << t << "s (time step " - << iic << "), error = " << 100.0 * max_error - << "% on line " << max_error_line << " \r"; - } - - if (converged) - break; - } - - iic++; - } - - if (!skip_ic) { - if (converged) { - LOGMSG << "Fairlead tensions converged" << endl; - } else { - LOGWRN << "Fairlead tensions did not converge" << endl; - } - LOGMSG << "Remaining error after " << t << " s = " << 100.0 * max_error - << "% on line " << max_error_line << endl; - if (!converged) { - LOGMSG << "Best score at " << best_score_t - << " s = " << 100.0 * best_score << "% on line " - << best_score_line << endl; - } - } + if (!skip_ic) { + moordyn::error_id err; + if (ICgenDynamic) + err = icLegacy(); + else + err = icStationary(); + if (err != MOORDYN_SUCCESS) + return err; } else { - - if (!skip_ic) LOGMSG << "Finalizing ICs using static solve" << endl; - - StationaryScheme t_integrator(_log, waves); - t_integrator.SetGround(GroundBody); - - for (auto obj : BodyList) - t_integrator.AddBody(obj); - for (auto obj : RodList) - t_integrator.AddRod(obj); - for (auto obj : PointList) - t_integrator.AddPoint(obj); - for (auto obj : LineList) - t_integrator.AddLine(obj); - t_integrator.SetCFL((std::min)(cfl, 1.0)); - t_integrator.Init(); - auto n_states = t_integrator.NStates(); - while (((ICTmax - t) > 0.00000001) && (!skip_ic)) { // tol of 0.00000001 should be smaller than anything anyone puts in as a ICdt - // Integrate one ICD timestep (ICdt) - real t_target = ICdt; - real dt; - t_integrator.Next(); - while ((dt = t_target) > 0.0) { - if (dtM0 < dt) - dt = dtM0; - moordyn::error_id err = MOORDYN_SUCCESS; - string err_msg; - try { - t_integrator.Step(dt); - error = t_integrator.Error(); - if (!t) - error0 = error; - t = t_integrator.GetTime(); - t_target -= dt; - } - MOORDYN_CATCHER(err, err_msg); - if (err != MOORDYN_SUCCESS) { - LOGERR << "t = " << t << " s" << endl; - return err; - } - } - - if (error < best_score) { - best_score = error; - best_score_t = t; - } - - const real error_rel = error / error0; - const real error_deriv = std::abs(error_prev - error) / error_prev; - if (!error || (error_rel < ICthresh) || (error_deriv < ICthresh)) - break; - error_prev = error; - - LOGDBG << "Stationary solution t = " << t << "s, " - << "error avg = " << error / n_states << " m/s2, " - << "error change = " << 100.0 * error_deriv << "% \r"; - } - - _t_integrator->SetState(t_integrator.GetState()); - if (!skip_ic) { - LOGMSG << "Remaining error after " << t << " s = " - << error / n_states << " m/s2" << endl; - LOGMSG << "Best score at " << best_score_t - << " s = " << best_score / n_states << " m/s2" << endl; - } + _t_integrator->Init(); } - - - // restore drag coefficients to normal values and restart time counter of - // each object _t_integrator->SetTime(0.0); - for (auto obj : LineList) { - if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); - obj->setTime(0.0); - } - for (auto obj : PointList) - if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); - for (auto obj : RodList) { - if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); - obj->setTime(0.0); - } - for (auto obj : BodyList) - if (ICgenDynamic) obj->scaleDrag(1.0 / ICDfac); - // store passed WaveKin value to enable waves in simulation if applicable // (they're not enabled during IC gen) env->waterKinOptions.waveMode = WaveKinTemp; @@ -863,7 +867,7 @@ MoorDyn::saveVTK(const char* filename) const moordyn::error_id moordyn::MoorDyn::ReadInFile() { - unsigned int i = 0; + int i = 0; // We are really interested in looking for the writeLog option, to start // logging as soon as possible @@ -2184,7 +2188,7 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) std::string filepath = entries[0]; this->seafloor->setup(env, filepath); } else if (name == "ICgenDynamic") - ICgenDynamic = atof(entries[0].c_str()); + ICgenDynamic = bool(atof(entries[0].c_str())); else LOGWRN << "Warning: Unrecognized option '" << name << "'" << endl; } diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index 634de293..923e153c 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -397,38 +397,85 @@ class MoorDyn final : public io::IO */ moordyn::error_id ReadInFile(); + /** @brief Read the input file and store it as a set of strings, one per + * line + * @param in_txt The output list of strings + * @return MOORDYN_SUCCESS If the input file is correctly loaded and all + * the objects are consistently set, an error code otherwise + * (see @ref moordyn_errors) + * @see ::ReadInFile() + */ moordyn::error_id readFileIntoBuffers(vector& in_txt); + /** @brief Get the file line index where a section starts + * @param in_txt The list of strings that contains the input file lines + * @param sectionName The valid section name strings + * @return The line index, -1 if the section cannot be found + * @see ::ReadInFile() + * @see ::readFileIntoBuffers() + */ int findStartOfSection(vector& in_txt, vector sectionName); - /** @brief Helper function to cread a new line property given a line from + /** @brief Helper function to read a new line property given a line from * the input file. * * @param inputText a string from the Line Properties section of input file + * @return The line properties */ LineProps* readLineProps(string inputText); - /** @brief Helper function to cread a new rod property given a line from + /** @brief Helper function to read a new rod property given a line from * the input file. * * @param inputText a string from the Rod Properties section of input file + * @return The rod properties */ RodProps* readRodProps(string inputText); - /** @brief Helper function to cread a new rod given a line from + /** @brief Helper function to read a new rod given a line from * the input file. * * @param inputText a string from the Rod List section of input file + * @return The rod object */ Rod* readRod(string inputText); + /** @brief Helper function to read a new body given a line from + * the input file. + * + * @param inputText a string from the Body List section of input file + * @return The body object + */ Body* readBody(string inputText); + /** @brief Helper function to read an option given a line from + * the input file. + * + * @param in_txt The list of strings that contains the input file lines + * @param index The option line index + */ void readOptionsLine(vector& in_txt, int index); + /** @brief Check that the provided entries match the expected ones + * + * If a wrong number of entries is provided an error is printed out + * @param entries Provided entries + * @param supposedNumberOfEntries Expected number of entries + */ bool checkNumberOfEntriesInLine(vector entries, int supposedNumberOfEntries); + /** @brief Compute an initial condition using the stationary solver + * @see ::ICgenDynamic + */ + moordyn::error_id icStationary(); + + /** @brief Compute an initial condition using the legacy upscaled drag + * dynamic solver + * @see ::ICgenDynamic + */ + moordyn::error_id icLegacy(); + /** @brief Get the forces * @param f The forces array * @return MOORDYN_SUCCESS If the forces are correctly set, an error code @@ -501,8 +548,8 @@ class MoorDyn final : public io::IO real ICTmax; // threshold for relative change in tensions to call it converged real ICthresh; - // use dynamic (1) or stationary (0) inital condition solver - int ICgenDynamic; + // use dynamic (true) or stationary (false) inital condition solver + bool ICgenDynamic; // temporary wave kinematics flag used to store input value while keeping // env.WaveKin=0 for IC gen moordyn::waves::waves_settings WaveKinTemp; diff --git a/tests/Mooring/lowe_and_langley_2006/line.txt b/tests/Mooring/lowe_and_langley_2006/line.txt index 4e594f29..d21d6766 100644 --- a/tests/Mooring/lowe_and_langley_2006/line.txt +++ b/tests/Mooring/lowe_and_langley_2006/line.txt @@ -26,5 +26,6 @@ midpoint5 tScheme Time integration scheme 30 TmaxIC Initial Condition generation maximum time (s) 1.0 dtIC Initial Condition generation convergence tests (s) 5e-3 threshIC Initial Condition generation convergence threshold +0 ICgenDynamic IC generator (0 = stationary, 1 = legacy upscale dynamics) 1 WaveKin The wave kinematics are provided through the API (-) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/pendulum.txt b/tests/Mooring/pendulum.txt index 21a67f9e..d47bceba 100644 --- a/tests/Mooring/pendulum.txt +++ b/tests/Mooring/pendulum.txt @@ -23,4 +23,5 @@ RK4 tScheme The time integration Scheme (-) 1.0 dtIC time interval for analyzing convergence during IC gen (s) 10000.0 TmaxIC max time for ic gen (s) 1e-4 threshIC threshold for IC convergence (-) +0 ICgenDynamic IC generator (0 = stationary, 1 = legacy upscale dynamics) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/time_schemes.txt b/tests/Mooring/time_schemes.txt index a3b25ac9..71989dde 100644 --- a/tests/Mooring/time_schemes.txt +++ b/tests/Mooring/time_schemes.txt @@ -24,4 +24,5 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 1.0 dtIC time interval for analyzing convergence during IC gen (s) 10.0 TmaxIC max time for ic gen (s) 1e-4 threshIC threshold for IC convergence (-) +0 ICgenDynamic IC generator (0 = stationary, 1 = legacy upscale dynamics) ------------------------- need this line -------------------------------------- diff --git a/tests/Mooring/wavekin_2/wavekin_3.txt b/tests/Mooring/wavekin_2/wavekin_3.txt index 17522e74..759efaa2 100644 --- a/tests/Mooring/wavekin_2/wavekin_3.txt +++ b/tests/Mooring/wavekin_2/wavekin_3.txt @@ -7,8 +7,8 @@ chain 0.252 390 1.674e9 -1.0 0 1.37 1.0 0. ---------------------- POINT PROPERTIES -------------------------------- ID Type X Y Z Mass Volume CdA Ca (#) (-) (m) (m) (m) (kg) (mˆ3) (m^2) (-) -1 Fixed -400 0.0 -50.0 0 0 0 0 -2 Fixed 0.0 0.0 -2.0 0 0 0 0 +1 Fixed -400 0.0 -50.0 0 0 0 0 +2 Fixed 0.0 0.0 -2.0 0 0 0 0 ---------------------- LINES ---------------------------------------- ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs (#) (name) (#) (#) (m) (-) (-) @@ -21,11 +21,11 @@ ID LineType AttachA AttachB UnstrLen NumSegs LineOutputs 1025.0 WtrDnsty water density (kg/m^3) 50 WtrDpth water depth (m) 1.0 dtIC time interval for analyzing convergence during IC gen (s) -0.0 TmaxIC max time for ic gen (s) +0.0 TmaxIC max time for ic gen (s) 4.0 CdScaleIC factor by which to scale drag coefficients during dynamic relaxation (-) 1.0e-3 threshIC threshold for IC convergence (-) 0.5 FrictionCoefficient general bottom friction coefficient, as a start (-) 3 WaveKin the wave elevations are provided in a grid (-) -0.15 dtWave the time step for the waves (s) +0.15 dtWave the time step for the waves (s) 1 Currents the water currents are provided in a grid (-) ------------------------- need this line -------------------------------------- From 67dddc78da4a8e96c7fb3465e49a5ef937a2ed1e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 25 Jun 2024 09:55:41 +0200 Subject: [PATCH 101/145] Legacy IC is performing quite bad, I set stationary as the default one again --- source/MoorDyn2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 6ddc3cb4..c0037786 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -90,7 +90,7 @@ moordyn::MoorDyn::MoorDyn(const char* infilename, int log_level) , cfl(0.5) , dtOut(0.0) , _t_integrator(NULL) - , ICgenDynamic(true) + , ICgenDynamic(false) , env(std::make_shared()) , GroundBody(NULL) , waves(nullptr) From 4463b479b8afd3abc28af6dd50488349cf8207ab Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 25 Jun 2024 10:10:57 +0200 Subject: [PATCH 102/145] It seems the test might fail on Windows, let's reduce the time step --- tests/midpoint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/midpoint.cpp b/tests/midpoint.cpp index 1b493447..e5987fab 100644 --- a/tests/midpoint.cpp +++ b/tests/midpoint.cpp @@ -216,7 +216,7 @@ TEST_CASE("Complex system simulation with midpoint5") // Change the time scheme REQUIRE(MoorDyn_SetTimeScheme(system, "midpoint5") == MOORDYN_SUCCESS); - REQUIRE(MoorDyn_SetCFL(system, 0.7) == MOORDYN_SUCCESS); + REQUIRE(MoorDyn_SetCFL(system, 0.5) == MOORDYN_SUCCESS); double dtM; REQUIRE(MoorDyn_GetDt(system, &dtM) == MOORDYN_SUCCESS); std::cout << "New time step = " << dtM << " s" << std::endl; From a8f86a4ccaccf24f96f91e4e2fa6293073c29b56 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 25 Jun 2024 10:42:52 -0600 Subject: [PATCH 103/145] Docs update for OpenFAST PR 2280 --- docs/inputs.rst | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index a5c55c35..d977a1f4 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -640,7 +640,10 @@ The following options from MoorDyn-F are not supported by MoorDyn-C: - CV (200.0): Same as FricDamp in MoorDyn-C. - inertialF (0): Toggle to include inertial components in the returned forces from coupled bodies and rods. Transients in the acceleration passed into MoorDy-F by OpenFAST can result - in large non-physical forces and moments which can cause instability in the model [0: on, 1: off] + in large non-physical forces and moments which can cause instability in the model [0: no, + 1: yes, 2: yes with ramp to inertialF_rampT] + - inertialF_rampT (30.0): Ramp time for inertial forces to reduce coupled object instability (s). + This is ignored unless inertialF = 2 Outputs ^^^^^^^ From c0b5b6765f926139cb78d5c9fc0fc269035243b6 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 26 Jun 2024 07:39:07 +0200 Subject: [PATCH 104/145] Some times there are coupled entities but there are not motions --- tests/.mdf_verification/verify.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/.mdf_verification/verify.py b/tests/.mdf_verification/verify.py index 05844549..14c39ef9 100644 --- a/tests/.mdf_verification/verify.py +++ b/tests/.mdf_verification/verify.py @@ -287,7 +287,7 @@ def plot(ref, data, fpath): # Get the NDoFs and check if the motions are right ndofs = moordyn.NCoupledDOF(system) motions = None - if md["InputsMode"]: + if md["InputsMode"] and md["InputsFile"]: motions = interpolate_motions(read_motions(md["InputsFile"]), md) assert motions.shape[0] - 1 == ndofs # Run the simulation From b9fb4f3550c68c57daf1aea5a1a4cf87fce13328 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 26 Jun 2024 06:38:55 +0200 Subject: [PATCH 105/145] Get the MoorDyn version on the legacy compilation systems --- compile/DLL/makefile | 11 +++++++++++ compile/DYLIB/makefile | 9 +++++++++ compile/SO/makefile | 21 +++++++++++++++++---- 3 files changed, 37 insertions(+), 4 deletions(-) diff --git a/compile/DLL/makefile b/compile/DLL/makefile index 70d9fdab..42709b3a 100644 --- a/compile/DLL/makefile +++ b/compile/DLL/makefile @@ -23,6 +23,17 @@ LFLAGS = -shared -static-libgcc -static-libstdc++ -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -g -Wall -Wextra -DMoorDyn_EXPORTS -fPIC -I../../source/ +# Automagically collect the library version +# This should still work fine with mingw, or even in modern Windows with bash +# I have not tested it anyway +CMAKEROOT := ../../CMakeLists.txt +MOORDYN_MAJOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MAJOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_MINOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MINOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_PATCH_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_PATCH_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +CFLAGS += -DMOORDYN_MAJOR_VERSION=$(MOORDYN_MAJOR_VERSION) +CFLAGS += -DMOORDYN_MINOR_VERSION=$(MOORDYN_MINOR_VERSION) +CFLAGS += -DMOORDYN_PATCH_VERSION=$(MOORDYN_PATCH_VERSION) + CFLAGS += $(COPTS) LFLAGS += $(LOPTS) diff --git a/compile/DYLIB/makefile b/compile/DYLIB/makefile index da4df230..0a4f018e 100644 --- a/compile/DYLIB/makefile +++ b/compile/DYLIB/makefile @@ -28,6 +28,15 @@ LFLAGS = -shared -DOSX -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -static -g -Wall -Wextra -DOSX -DMoorDyn_EXPORTS -fPIC -I../../source/ +# Automagically collect the library version +CMAKEROOT := ../../CMakeLists.txt +MOORDYN_MAJOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MAJOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_MINOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MINOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_PATCH_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_PATCH_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +CFLAGS += -DMOORDYN_MAJOR_VERSION=$(MOORDYN_MAJOR_VERSION) +CFLAGS += -DMOORDYN_MINOR_VERSION=$(MOORDYN_MINOR_VERSION) +CFLAGS += -DMOORDYN_PATCH_VERSION=$(MOORDYN_PATCH_VERSION) + CFLAGS += $(COPTS) LFLAGS += $(LOPTS) diff --git a/compile/SO/makefile b/compile/SO/makefile index d10d0c64..93ea9040 100644 --- a/compile/SO/makefile +++ b/compile/SO/makefile @@ -24,6 +24,15 @@ LFLAGS = -shared -static-libgcc -static-libstdc++ -DLINUX -DMoorDyn_EXPORTS -fPIC CFLAGS = -c -O3 -g -Wall -Wextra -DLINUX -DMoorDyn_EXPORTS -fPIC -I../../source/ +# Automagically collect the library version +CMAKEROOT := ../../CMakeLists.txt +MOORDYN_MAJOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MAJOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_MINOR_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_MINOR_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +MOORDYN_PATCH_VERSION=$(shell cat ${CMAKEROOT} | grep "set(MOORDYN_PATCH_VERSION" | cut -d " " -f 2 | cut -d ")" -f 1) +CFLAGS += -DMOORDYN_MAJOR_VERSION=$(MOORDYN_MAJOR_VERSION) +CFLAGS += -DMOORDYN_MINOR_VERSION=$(MOORDYN_MINOR_VERSION) +CFLAGS += -DMOORDYN_PATCH_VERSION=$(MOORDYN_PATCH_VERSION) + CFLAGS += $(COPTS) LFLAGS += $(LOPTS) @@ -41,12 +50,16 @@ DIRGUARD = @mkdir -p $(@D) all: libmoordyn.so -libmoordyn.so: libmoordyn.so.2.0.0 +libmoordyn.so: libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION) + rm -f libmoordyn.so + ln -s libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION) libmoordyn.so + +libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION): libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION).$(MOORDYN_PATCH_VERSION) rm -f libmoordyn.so - ln -s libmoordyn.so.2.0.0 libmoordyn.so + ln -s libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION).$(MOORDYN_PATCH_VERSION) libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION) -libmoordyn.so.2.0.0: $(OBJECTS) - $(CXX) $(LFLAGS) -o libmoordyn.so.2.0.0 $(OBJECTS) +libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION).$(MOORDYN_PATCH_VERSION): $(OBJECTS) + $(CXX) $(LFLAGS) -o libmoordyn.so.$(MOORDYN_MAJOR_VERSION).$(MOORDYN_MINOR_VERSION).$(MOORDYN_PATCH_VERSION) $(OBJECTS) %.o: ../../source/%.cpp $(HEADERS) ${CXX} $(CPPFLAGS) -o $@ $< From d8425559851fa26e9ab8a10313265c3111aa7145 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 28 Jun 2024 13:10:49 +0200 Subject: [PATCH 106/145] fix: Read first the writelog option, and then anything else --- source/MoorDyn2.cpp | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index c0037786..be5b49a4 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -869,14 +869,13 @@ moordyn::MoorDyn::ReadInFile() { int i = 0; - // We are really interested in looking for the writeLog option, to start - // logging as soon as possible vector in_txt; if (readFileIntoBuffers(in_txt) != MOORDYN_SUCCESS) { - // BREAK return MOORDYN_INVALID_INPUT_FILE; } - // Skip until we find the options header line + + // We are really interested in looking for the writeLog option, to start + // logging as soon as possible if ((i = findStartOfSection(in_txt, { "OPTIONS" })) != -1) { LOGDBG << " Reading options:" << endl; // Parse options until the next header or the end of the file @@ -890,16 +889,30 @@ moordyn::MoorDyn::ReadInFile() const string name = entries[1]; if (name == "writeLog") { - env->writeLog = atoi(entries[0].c_str()); + env->writeLog = atoi(value.c_str()); const moordyn::error_id err = SetupLog(); if (err != MOORDYN_SUCCESS) return err; + break; + } + } + } + // Now we can read all the options + if ((i = findStartOfSection(in_txt, { "OPTIONS" })) != -1) { + LOGDBG << " Reading options:" << endl; + // Parse options until the next header or the end of the file + while ((in_txt[i].find("---") == string::npos) && (i < in_txt.size())) { + vector entries = moordyn::str::split(in_txt[i], ' '); + if (entries.size() < 2) { i++; + continue; + } + const string name = entries[1]; - } else { + if (name != "writeLog") { readOptionsLine(in_txt, i); - i++; } + i++; } } From cc222d455c9029bbf55a4cd9b820e7f63c7a20be Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Fri, 28 Jun 2024 13:11:33 +0200 Subject: [PATCH 107/145] fix: The quaternions shall be renormalized to get the rotation matrix --- source/Body.cpp | 10 +++++----- source/Misc.hpp | 2 +- source/Rod.cpp | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/source/Body.cpp b/source/Body.cpp index a7019532..5c043a61 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -127,7 +127,7 @@ Body::setup(int number_in, v6 = vec6::Zero(); // calculate orientation matrix based on latest angles - OrMat = r7.quat.toRotationMatrix(); + OrMat = r7.quat.normalized().toRotationMatrix(); LOGDBG << "Set up Body " << number << ", type " << TypeName(type) << ". " << endl; @@ -288,13 +288,13 @@ Body::setDependentStates() // do 3d details of Rod ref point vec tmpr, tmprd; + // set first three entires (end A translation) of rRod and rdRod transformKinematics(r6RodRel[i](Eigen::seqN(0, 3)), OrMat, r7.pos, v6, tmpr, - tmprd); // set first three entires (end A - // translation) of rRod and rdRod + tmprd); // does the above function need to take in all 6 elements of r6RodRel?? rRod(Eigen::seqN(0, 3)) = tmpr; rdRod(Eigen::seqN(0, 3)) = tmprd; @@ -430,7 +430,7 @@ Body::updateFairlead(real time) a6 = rdd_ves; // calculate orientation matrix based on latest angles - OrMat = r7.quat.toRotationMatrix(); + OrMat = r7.quat.normalized().toRotationMatrix(); // set positions of any dependent points and rods setDependentStates(); @@ -465,7 +465,7 @@ Body::setState(XYZQuat pos, vec6 vel) } // calculate orientation matrix based on latest angles - OrMat = r7.quat.toRotationMatrix(); + OrMat = r7.quat.normalized().toRotationMatrix(); // set positions of any dependent points and rods setDependentStates(); diff --git a/source/Misc.hpp b/source/Misc.hpp index 13c6421f..f9d64570 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -173,7 +173,7 @@ inline vec3 canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) { // From issue #163: https://github.com/FloatingArrayDesign/MoorDyn/issues/163 - mat3 coeff = quat.toRotationMatrix(); + mat3 coeff = quat.normalized().toRotationMatrix(); vec3 res{}; using Index = int; using Scalar = real; diff --git a/source/Rod.cpp b/source/Rod.cpp index 6d868602..ba81f539 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -452,7 +452,7 @@ Rod::setState(XYZQuat pos, vec6 vel) // update Rod direction unit vector (simply equal to last three entries of // r6) - const mat OrMat = r7.quat.toRotationMatrix(); + const mat OrMat = r7.quat.normalized().toRotationMatrix(); q = OrMat * q0; } @@ -537,7 +537,7 @@ Rod::setKinematics(vec6 r_in, vec6 rd_in) // update Rod direction unit vector (presumably these were set elsewhere for // pinned Rods) // TODO - don't recalculate OrMat here - const mat OrMat = r7.quat.toRotationMatrix(); + const mat OrMat = r7.quat.normalized().toRotationMatrix(); q = OrMat * q0; } @@ -554,7 +554,7 @@ Rod::setDependentStates() if (N > 0) { // set end B nodes only if the rod isn't zero length // TODO - determine if q has been calculated here - q = r7.quat.toRotationMatrix() * q0; + q = r7.quat.normalized().toRotationMatrix() * q0; const vec rRel = UnstrLen * q; r[N] = r[0] + rRel; const vec w = v6.tail<3>(); From 2cff8b96ca9f906b7414ffc5a528198521dee191 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Mon, 1 Jul 2024 07:27:48 +0200 Subject: [PATCH 108/145] test: Excentrical body test --- tests/CMakeLists.txt | 2 +- tests/Mooring/body_tests/floatingBodies.txt | 30 ++ tests/bodies.cpp | 400 +++++++------------- 3 files changed, 170 insertions(+), 262 deletions(-) create mode 100644 tests/Mooring/body_tests/floatingBodies.txt diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 392cdc05..5987e7a7 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -35,12 +35,12 @@ set(CPP_TESTS seafloor wavekin wavekin_7 - bodies ) set(CATCH2_TESTS math_tests testDecomposeString + bodies beam conveying_fluid polyester diff --git a/tests/Mooring/body_tests/floatingBodies.txt b/tests/Mooring/body_tests/floatingBodies.txt new file mode 100644 index 00000000..e430baf2 --- /dev/null +++ b/tests/Mooring/body_tests/floatingBodies.txt @@ -0,0 +1,30 @@ +--------------------- MoorDyn Input File ------------------------------------------------------- +Testing body kinematics when body origin != COM +---------------------- ROD TYPES ------------------------------------ +TypeName Diam Mass/m Cd Ca CdEnd CaEnd +(name) (m) (kg/m) (-) (-) (-) (-) +buoy 1 1.0e1 0.0 0.0 0.0 0.0 +---------------------------- BODIES ----------------------------------------------------- +ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca +(#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) +1 free 0 0 20 0.0 0 0 0 0 0 0 0 0 +2 free 0 10 20 0.0 0 0 0 0|-10|0 0 0 0 0 +---------------------- RODS ---------------------------------------- +ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs +(#) (name) (#/key) (m) (m) (m) (m) (m) (m) (-) (-) +1 buoy Body1 0 0 -2 0 0.0 2 10 pvf +2 buoy Body2 0 -10 -2 0 -10.0 2 10 pvf +-------------------------- SOLVER OPTIONS--------------------------------------------------- +2 writeLog - Write a log file +0.0 g - No gravity +0.001 dtM - time step to use in mooring integration +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +70 WtrDpth - water depth +3.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen +0.015 threshIC - threshold for IC convergence +0.0 TmaxIC - threshold for IC convergence +0.01 dtIC - Time lapse between convergence tests (s) +0 Currents - Whether or not to pull in currents +0 WaveKin - Whether or not to pull in waves +--------------------------- need this line ------------------------------------------------- diff --git a/tests/bodies.cpp b/tests/bodies.cpp index 83928458..c1758c43 100644 --- a/tests/bodies.cpp +++ b/tests/bodies.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include "util.h" @@ -75,6 +76,33 @@ write_system_vtk(MoorDyn in_system, double time, SeriesWriter* series_writer) return true; } + +bool +write_system_vtk(moordyn::MoorDyn& system, + double time, + SeriesWriter* series_writer) +{ + if (series_writer == nullptr) { + return true; + } + // if (system.GetLines().empty()) { + // return true; + // } + std::stringstream filename; + std::stringstream element_name; + element_name << "vtk_system"; + auto& vtp_series = series_writer->getSeries(element_name.str()); + auto step_num = vtp_series.time_steps.size(); + + filename << element_name.str() << "." << step_num << ".vtm"; + std::string full_path = "../../vtk_out/" + filename.str(); + // std::cout << "*** Saving on '" << full_path << "'..." << + // std::endl; + vtp_series.time_steps.push_back({ filename.str(), time }); + system.saveVTK(full_path.c_str()); + return true; +} + #else class SeriesWriter; @@ -162,24 +190,21 @@ followTrajectory(MoorDyn& system, std::vector f(x.size()); double dt = trajectory.times[i + 1] - trajectory.times[i]; err = MoorDyn_Step(system, x.data(), dx.data(), f.data(), &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err - << endl; + if (err != MOORDYN_SUCCESS) return false; - } - if (!write_system_vtk(system, t, series_writer)) { + if (!write_system_vtk(system, t, series_writer)) return false; - } } return true; } +#define series_writer NULL + /** * @brief Uses a line between a point on the body and a coupled point to rotate * the body around * - * * The point on the body starts at (1, 0, 0) relative to the body. * Then we drag the point to (0, 0, 1) to rotate the body -90 degrees around the * y-axis Then we drag the point to (0, 1, 0) to rotate the body -90 degrees @@ -188,34 +213,15 @@ followTrajectory(MoorDyn& system, * * The final result of this should be that the body gets rotated -90 degrees * around the x-axis. - * - * - * @param series_writer - * @return true - * @return false */ -bool -rotatingBody(SeriesWriter* series_writer) +TEST_CASE("Rotating body") { - int err; - cout << endl << " => " << __PRETTY_FUNC_NAME__ << "..." << endl; - MoorDyn system = MoorDyn_Create("Mooring/body_tests/rotatingBody.txt"); - if (!system) { - cerr << "Failure Creating the Mooring system" << endl; - return false; - } + REQUIRE(system); unsigned int n_dof; - err = MoorDyn_NCoupledDOF(system, &n_dof); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure getting NCoupledDOF: " << err << endl; - return false; - } - if (n_dof != 3) { - cerr << "Expected 3 DOFs but got " << n_dof << endl; - return false; - } + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 3); const moordyn::vec3 body_center{ 0, 0, 5 }; const moordyn::real radius = 2.0; @@ -223,29 +229,17 @@ rotatingBody(SeriesWriter* series_writer) moordyn::vec3 dx{ 0, 0, 0 }; double f[3]; - err = MoorDyn_Init(system, x.data(), dx.data()); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err << endl; - return false; - } + REQUIRE(MoorDyn_Init(system, x.data(), dx.data()) == MOORDYN_SUCCESS); MoorDynPoint point = MoorDyn_GetPoint(system, 8); - - if (!write_system_vtk(system, 0, series_writer)) { - return false; - } + REQUIRE(point); + REQUIRE(write_system_vtk(system, 0, series_writer)); double t = 0, dt = 0.1; // do one outer time step just to make sure everything is settled - err = MoorDyn_Step(system, x.data(), dx.data(), f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err << endl; - return false; - } - - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Step( + system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); double start_t = t; // goes from (2, 0, 0) to (0, 0, 2) in 2 seconds @@ -257,36 +251,24 @@ rotatingBody(SeriesWriter* series_writer) x = body_center + (radius * moordyn::vec3{ cos(angle), 0, sin(angle) }); return x; }); - if (!followTrajectory(system, trajectory, t, series_writer)) { - return false; - } + REQUIRE(followTrajectory(system, trajectory, t, series_writer)); start_t = t; x = body_center + moordyn::vec3(0.0, 0.0, 0.05 + radius); dx = moordyn::vec3(0, 0, 0.0); // give 0.5 seconds to settle at the top while (t < start_t + 0.5) { - err = MoorDyn_Step(system, x.data(), dx.data(), f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err - << endl; - return false; - } - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Step( + system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); } moordyn::vec3 point_pos; - MoorDyn_GetPointPos(point, point_pos.data()); + REQUIRE(MoorDyn_GetPointPos(point, point_pos.data()) == MOORDYN_SUCCESS); { moordyn::vec3 rel_pos = point_pos - body_center; moordyn::vec3 expected_pos{ 0, 0, 1.0 }; - if (!allclose(rel_pos, expected_pos, 0.1, 0.15)) { - cerr << "Point 8 relative to body center should be " - << expected_pos.transpose() << " but was " - << rel_pos.transpose() << " at t = " << t << endl; - } + REQUIRE(allclose(rel_pos, expected_pos, 0.1, 0.15)); } start_t = t; @@ -300,36 +282,24 @@ rotatingBody(SeriesWriter* series_writer) x = body_center + (radius * moordyn::vec3{ 0, sin(angle), cos(angle) }); return x; }); - if (!followTrajectory(system, trajectory2, t, series_writer)) { - return false; - } + REQUIRE(followTrajectory(system, trajectory2, t, series_writer)); start_t = t; x = body_center + moordyn::vec3(0.0, radius + 0.05, 0); dx = moordyn::vec3(0, 0.0, 0.0); // give 0.5 seconds to settle at the top while (t < start_t + 0.5) { - err = MoorDyn_Step(system, x.data(), dx.data(), f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err - << endl; - return false; - } - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Step( + system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); } - MoorDyn_GetPointPos(point, point_pos.data()); + REQUIRE(MoorDyn_GetPointPos(point, point_pos.data()) == MOORDYN_SUCCESS); { moordyn::vec3 rel_pos = point_pos - body_center; moordyn::vec3 expected_pos{ 0, 1.0, 0.0 }; - if (!allclose(rel_pos, expected_pos, 0.1, 0.15)) { - cerr << "Point 8 relative to body center should be " - << expected_pos.transpose() << " but was " - << rel_pos.transpose() << " at t = " << t << endl; - } + REQUIRE(allclose(rel_pos, expected_pos, 0.1, 0.15)); } start_t = t; @@ -343,41 +313,31 @@ rotatingBody(SeriesWriter* series_writer) x = body_center + (radius * moordyn::vec3{ sin(angle), cos(angle), 0 }); return x; }); - if (!followTrajectory(system, trajectory3, t, series_writer)) { - return false; - } + REQUIRE(followTrajectory(system, trajectory3, t, series_writer)); start_t = t; x = body_center + moordyn::vec3(radius + 0.05, 0, 0); dx = moordyn::vec3(0, 0.0, 0.0); // give 0.1 seconds to settle at the top while (t < start_t + 0.5) { - err = MoorDyn_Step(system, x.data(), dx.data(), f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err - << endl; - return false; - } - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Step( + system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); } - MoorDyn_GetPointPos(point, point_pos.data()); + REQUIRE(MoorDyn_GetPointPos(point, point_pos.data()) == MOORDYN_SUCCESS); { moordyn::vec3 rel_pos = point_pos - body_center; moordyn::vec3 expected_pos{ 1.0, 0.0, 0.0 }; - if (!allclose(rel_pos, expected_pos, 0.1, 0.15)) { - cerr << "Point 8 relative to body center should be " - << expected_pos.transpose() << "but was " - << rel_pos.transpose() << " at t=" << t << endl; - } + REQUIRE(allclose(rel_pos, expected_pos, 0.1, 0.15)); } auto body = MoorDyn_GetBody(system, 1); + REQUIRE(body); moordyn::vec6 r, rd; - MoorDyn_GetBodyState(body, r.data(), rd.data()); + REQUIRE(MoorDyn_GetBodyState( + body, r.data(), rd.data()) == MOORDYN_SUCCESS); // We want axis-angle representation, and it's easier to compute that from // quaternion so we convert back to quaternion auto xyz_quat = moordyn::XYZQuat::fromVec6(r); @@ -386,14 +346,9 @@ rotatingBody(SeriesWriter* series_writer) double angle = moordyn::rad2deg * 2 * acos(q.w()); double denom = (sqrt(1 - q.w() * q.w())); moordyn::vec3 axis{ q.x() / denom, q.y() / denom, q.z() / denom }; - if (!(abs(axis.x()) > 0.85 && abs(axis.y()) < 0.2 && - abs(axis.z()) < 0.2)) { // if we are just checking axis direction then - // +/- does not matter - cerr << "The final rotation of the body in angle axis form should " - "have an axis in the x direction, but axis is " - << axis.transpose() << endl; - return false; - } + REQUIRE((abs(axis.x()) > 0.85 && + abs(axis.y()) < 0.2 && + abs(axis.z()) < 0.2)); // normalize angle between +180 and -180 while (angle > 180.) { angle -= 360; @@ -401,29 +356,17 @@ rotatingBody(SeriesWriter* series_writer) while (angle < -180) { angle += 360; } - if (!(abs(angle - 90) < 10)) { - cerr << "The final rotation of the body in angle-axis form should " - "have a angle near 90 degrees but angle is " - << angle << endl; - return false; - } + REQUIRE(abs(angle - 90) < 10); cout << "Body r = " << r.transpose() << endl; cout << "Axis-Angle rotation: axis = " << axis.transpose() << ", angle = " << angle << " degrees" << endl; - err = MoorDyn_Close(system); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure closing Moordyn: " << err << endl; - return false; - } - - return true; + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); } /** * @brief Compares inertial deflection of a pinned body to analytical solution * - * * The coupled pinned body that is massless and volumeless with a rod fixed to * it is moved with constant acceleration in a vaccum (0 water density). The * resulting avg inertial deflection should match an analytical solution of @@ -434,76 +377,43 @@ rotatingBody(SeriesWriter* series_writer) * * This only tests the inertial properties of pinned bodies, other tests deal * with hydrodynamics and general body properties - * - * - * @param series_writer - * @return true - * @return false */ -bool -pinnedBody(SeriesWriter* series_writer) +TEST_CASE("Pinned body") { - int err; - cout << endl << " => " << __PRETTY_FUNC_NAME__ << "..." << endl; - MoorDyn system = MoorDyn_Create("Mooring/body_tests/pinnedBody.txt"); - if (!system) { - cerr << "Failure Creating the Mooring system" << endl; - return false; - } + REQUIRE(system); unsigned int n_dof; - err = MoorDyn_NCoupledDOF(system, &n_dof); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure getting NCoupledDOF: " << err << endl; - return false; - } - if (n_dof != - 6) { // rotational DOF are ignored by MDC, same as a coupled pinned rods - cerr << "Expected 6 DOFs but got " << n_dof << endl; - return false; - } + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof ==6); moordyn::vec6 x{ 0, 0, -5, 0, 0, 0 }; moordyn::vec6 xd{ 0, 0, 0, 0, 0, 0 }; double f[6]; - err = MoorDyn_Init(system, x.data(), xd.data()); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err << endl; - return false; - } - - if (!write_system_vtk(system, 0, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Init(system, x.data(), xd.data()) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, 0, series_writer)); auto body = MoorDyn_GetBody(system, 1); + REQUIRE(body); moordyn::vec6 r, rd; vector roll; int i = 0, j = 0; double t = 0.0, dt = 0.01, accel = 0.5; bool local_min_max; - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(write_system_vtk(system, t, series_writer)); while (t < 50.0) { x[1] = 0.5 * accel * pow(t, 2); xd[1] = accel * t; - err = MoorDyn_Step(system, x.data(), xd.data(), f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err - << endl; - return false; - } - if (!write_system_vtk(system, t, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Step( + system, x.data(), xd.data(), f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); - MoorDyn_GetBodyState(body, r.data(), rd.data()); + REQUIRE(MoorDyn_GetBodyState( + body, r.data(), rd.data()) == MOORDYN_SUCCESS); roll.push_back(r[3]); if (i >= 30) { // after the simulation has run for a few time steps @@ -522,120 +432,88 @@ pinnedBody(SeriesWriter* series_writer) } double theta = atan(-accel / 9.80665); double average = reduce(roll.begin(), roll.end()) / roll.size(); - if (abs(average - theta) > 0.001) { - cerr << "Pinned body inertial deflection should be " << theta - << " but it is " << average << endl; - return false; - } - - err = MoorDyn_Close(system); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure closing Moordyn: " << err << endl; - return false; - } + REQUIRE(abs(average - theta) <= 0.001); - cout << setprecision(4) << "Average roll is " << average << endl; - cout << setprecision(4) << "Theoretical roll is " << theta << endl; + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); - return true; + // NOTE: jlcercos has dropped setprecision since it was not restored to the + // default value afterwards, which might impair the subsequent exexutions + cout << "Average roll is " << average << endl; + cout << "Theoretical roll is " << theta << endl; } -bool -bodyDrag(SeriesWriter* series_writer) +TEST_CASE("Body drag") { - int err; - cout << endl << " => " << __PRETTY_FUNC_NAME__ << "..." << endl; - MoorDyn system = MoorDyn_Create("Mooring/body_tests/bodyDrag.txt"); - if (!system) { - cerr << "Failure Creating the Mooring system" << endl; - return false; - } + REQUIRE(system); unsigned int n_dof; - err = MoorDyn_NCoupledDOF(system, &n_dof); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure getting NCoupledDOF: " << err << endl; - return false; - } - if (n_dof != 0) { - cerr << "Expected 0 DOFs but got " << n_dof << endl; - return false; - } + REQUIRE(MoorDyn_NCoupledDOF(system, &n_dof) == MOORDYN_SUCCESS); + REQUIRE(n_dof == 0); double f[3]; - err = MoorDyn_Init(system, nullptr, nullptr); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring initialization: " << err << endl; - return false; - } - - if (!write_system_vtk(system, 0, series_writer)) { - return false; - } + REQUIRE(MoorDyn_Init(system, nullptr, nullptr) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, 0, series_writer)); double t = 0, dt = 0.1; double max_t = 5; while (t < max_t) { // do one outer time step just to make sure everything is settled - err = MoorDyn_Step(system, nullptr, nullptr, f, &t, &dt); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure during the mooring dynamics: " << err << endl; - return false; - } - - if (!write_system_vtk(system, t, series_writer)) { - return false; - } - } - - err = MoorDyn_Close(system); - if (err != MOORDYN_SUCCESS) { - cerr << "Failure closing Moordyn: " << err << endl; - return false; + REQUIRE(MoorDyn_Step( + system, nullptr, nullptr, f, &t, &dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); } - return true; + REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); } -/** @brief Runs all the test - * @return 0 if the tests have ran just fine. The index of the failing test - * otherwise - */ -int -main(int, char**) +TEST_CASE("Excentric body") { - try { - // SeriesWriter series_writer; - if (!rotatingBody(NULL)) { - // series_writer.writeJson("../../vtk_out/"); - return 3; - } - // series_writer.writeJson("../../vtk_out/"); + moordyn::MoorDyn system{ "Mooring/body_tests/floatingBodies.txt" }; - } catch (std::exception& e) { - cerr << "rotatingBody failed with exception " << e.what() << endl; - return 3; + double f[3]; + double initial_angular_vel = 0.2; + auto bodies = system.GetBodies(); + { + auto body = bodies.at(0); + const auto [pos, vel] = body->getState(); + const moordyn::vec6 new_vel = + moordyn::vec6(0.0, 0.0, 0.0, initial_angular_vel, 0.0, 0.0); + body->setState(pos, new_vel); } - - try { - // SeriesWriter series_writer; - if (!pinnedBody(NULL)) { - // series_writer.writeJson("../../vtk_out/"); - return 3; + { + auto body = bodies.at(1); + const auto [pos, vel] = body->getState(); + const moordyn::vec6 new_vel = moordyn::vec6( + 0.0, 0.0, 10 * initial_angular_vel, initial_angular_vel, 0.0, 0.0); + body->setState(pos, new_vel); + } + + REQUIRE(system.Init(nullptr, nullptr) == MOORDYN_SUCCESS); + + double t = 0, dt = 0.25; + double t_max = 10.0; + + // I do this just so that my first vtk output includes correct forces and + // stuff + double small_dt = 1e-6; + REQUIRE(system.Step(NULL, NULL, f, t, small_dt) == MOORDYN_SUCCESS); + REQUIRE(write_system_vtk(system, t, series_writer)); + while ((t_max - t) > (0.1 * dt)) { + REQUIRE(system.Step(NULL, NULL, f, t, dt) == MOORDYN_SUCCESS); + { + const auto body = bodies.at(1); + const auto [pos, vel] = body->getState(); + const moordyn::vec3 global_pos = pos.pos; + const moordyn::real expected_y = 10 * cos(initial_angular_vel * t); + const moordyn::real expected_z = + 20 + 10 * sin(initial_angular_vel * t); + const auto err_y = global_pos.y() - expected_y; + const auto err_z = global_pos.z() - expected_z; + REQUIRE((abs(err_y) <= 1e-4 && abs(err_z) <= 1e-4)); } - // series_writer.writeJson("../../vtk_out/"); - } catch (std::exception& e) { - cerr << "pinnedBody failed with exception " << e.what() << endl; - return 3; + REQUIRE(write_system_vtk(system, t, series_writer)); } - - if (!bodyDrag(NULL)) { - return 2; - } - - cout << "bodies.cpp passed successfully" << endl; - return 0; } From 7fa5aa06f1ac186f735212e09500159154a1e595 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jul 2024 09:04:30 +0200 Subject: [PATCH 109/145] feat(body): Add centripetal forces for rotating bodies --- source/Body.cpp | 4 ++++ source/Misc.hpp | 4 ++-- source/Point.cpp | 8 ++++++++ source/Point.hpp | 17 +++++++++++++++++ source/Rod.cpp | 14 ++++++++++++++ source/Rod.hpp | 37 ++++++++++++++++++++++++++++++++++++- 6 files changed, 81 insertions(+), 3 deletions(-) diff --git a/source/Body.cpp b/source/Body.cpp index 5c043a61..3efb40ab 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -269,6 +269,7 @@ Body::setDependentStates() rPoint, rdPoint); //<<< should double check this function + // pass above to the point and get it to calculate the forces try { attachedP[i]->setKinematics(rPoint, rdPoint); @@ -588,6 +589,7 @@ Body::doRHS() vec6 F6_i; mat6 M6_i; attached->getNetForceAndMass(F6_i, M6_i, r7.pos); + F6_i(Eigen::seqN(0, 3)) += attached->getCentripetalForce(r7.pos, v6); // sum quantitites F6net += F6_i; @@ -601,6 +603,8 @@ Body::doRHS() vec6 F6_i; mat6 M6_i; attached->getNetForceAndMass(F6_i, M6_i, r7.pos); + F6_i(Eigen::seqN(0, 3)) += attached->getCentripetalForce(r7.pos, v6); + // // calculate relative location of rod about body center in // global orientation double rRod_i[3]; diff --git a/source/Misc.hpp b/source/Misc.hpp index f9d64570..2514ca72 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -829,8 +829,8 @@ getH(vec r) { mat H; // clang-format off - H << 0, r[2], -r[1], - -r[2], 0, r[0], + H << 0, r[2], -r[1], + -r[2], 0, r[0], r[1], -r[0], 0; // clang-format on return H; diff --git a/source/Point.cpp b/source/Point.cpp index aea793e2..dd71b82f 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -315,6 +315,14 @@ Point::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody) M_out = translateMass(rRel, M); } +vec +Point::getCentripetalForce(vec rRef, vec w) const +{ + const vec rRel = r - rRef; + + return w.squaredNorm() * (M * rRel); +} + moordyn::error_id Point::doRHS() { diff --git a/source/Point.hpp b/source/Point.hpp index 466b5498..afec6448 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -373,6 +373,23 @@ class Point final : public io::IO, public SuperCFL mat6& M_out, vec rBody = vec::Zero()); + /** @brief Calculate the centripetal force on a body + * @param rBody The body position + * @param vBody The body angular velocity + * @return Centripetal force on the body + */ + vec getCentripetalForce(vec rBody, vec vBody) const; + + /** @brief Calculate the centripetal force on a body + * @param rBody The body position + * @param vBody The body velocity + * @return Centripetal force on the body + */ + inline vec getCentripetalForce(vec rBody, vec6 vBody) const + { + return getCentripetalForce(rBody, (vec)(vBody.tail<3>())); + } + /** @brief Calculates the forces and mass on the point, including from * attached lines * diff --git a/source/Rod.cpp b/source/Rod.cpp index ba81f539..1e8436d3 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -816,6 +816,20 @@ Rod::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rRef) */ } +vec +Rod::getCentripetalForce(vec rRef, vec w) const +{ + if (!N) + return vec::Zero(); + + vec F = vec::Zero(); + for (unsigned int i = 0; i <= N; i++) { + const vec rRel = r[i] - rRef; + F += w.squaredNorm() * (M[i] * rRel); + } + return F; +} + real calcSubSeg(vec p1, vec p2, real surface_height, real diameter) { diff --git a/source/Rod.hpp b/source/Rod.hpp index 3eb7a999..074a6361 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -431,6 +431,24 @@ class Rod final : public io::IO, public SuperCFL */ inline void setTime(real time) { t = time; } + /** @brief Get the body kinematics + * @param pos The output position + * @param vel The output velocity + */ + inline void getState(XYZQuat& pos, vec6& vel) const + { + pos = r7; + vel = v6; + } + + /** @brief Get the body kinematics + * @return Position and velocity + */ + inline std::pair getState() const + { + return std::make_pair(r7, v6); + } + /** @brief Set the rod state * * for a free Rod, there are 12 states: @@ -520,7 +538,7 @@ class Rod final : public io::IO, public SuperCFL * parent body * @param Fnet_out Output Force about body ref point * @param M_out Output Mass matrix about body ref point - * @param rBody The body position. If NULL, {0, 0, 0} is considered + * @param rBody The body position */ void getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody); @@ -534,6 +552,23 @@ class Rod final : public io::IO, public SuperCFL getNetForceAndMass(Fnet_out, M_out, r[0]); } + /** @brief Calculate the centripetal force on a body + * @param rBody The body position + * @param vBody The body angular velocity + * @return Centripetal force on the body + */ + vec getCentripetalForce(vec rBody, vec vBody) const; + + /** @brief Calculate the centripetal force on a body + * @param rBody The body position + * @param vBody The body velocity + * @return Centripetal force on the body + */ + inline vec getCentripetalForce(vec rBody, vec6 vBody) const + { + return getCentripetalForce(rBody, (vec)(vBody.tail<3>())); + } + /** @brief This is the big function that calculates the forces on the rod, * including from attached lines */ From 13c55c2a9c781759b03fed6603f44d71da714b8e Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jul 2024 09:05:53 +0200 Subject: [PATCH 110/145] test: Test the centripetal force on a simple case --- .../{floatingBodies.txt => orbitalBody.txt} | 11 ++++-- tests/bodies.cpp | 37 ++++++++++--------- 2 files changed, 26 insertions(+), 22 deletions(-) rename tests/Mooring/body_tests/{floatingBodies.txt => orbitalBody.txt} (75%) diff --git a/tests/Mooring/body_tests/floatingBodies.txt b/tests/Mooring/body_tests/orbitalBody.txt similarity index 75% rename from tests/Mooring/body_tests/floatingBodies.txt rename to tests/Mooring/body_tests/orbitalBody.txt index e430baf2..5f07b1a3 100644 --- a/tests/Mooring/body_tests/floatingBodies.txt +++ b/tests/Mooring/body_tests/orbitalBody.txt @@ -7,17 +7,20 @@ buoy 1 1.0e1 0.0 0.0 0.0 0.0 ---------------------------- BODIES ----------------------------------------------------- ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca (#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) -1 free 0 0 20 0.0 0 0 0 0 0 0 0 0 +1 free 0 10 20 0.0 0 0 0 0|-10|0 0 0 0 0 2 free 0 10 20 0.0 0 0 0 0|-10|0 0 0 0 0 +----------------------- POINTS ---------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Body1 0.0 -10 0 40.0 0 0 0 ---------------------- RODS ---------------------------------------- ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs (#) (name) (#/key) (m) (m) (m) (m) (m) (m) (-) (-) -1 buoy Body1 0 0 -2 0 0.0 2 10 pvf -2 buoy Body2 0 -10 -2 0 -10.0 2 10 pvf +1 buoy Body2 0 -10 -2 0 -10.0 2 10 pvf -------------------------- SOLVER OPTIONS--------------------------------------------------- 2 writeLog - Write a log file 0.0 g - No gravity -0.001 dtM - time step to use in mooring integration +1e-3 dtM - time step to use in mooring integration 3.0e6 kb - bottom stiffness 3.0e5 cb - bottom damping 70 WtrDpth - water depth diff --git a/tests/bodies.cpp b/tests/bodies.cpp index c1758c43..e6e1186a 100644 --- a/tests/bodies.cpp +++ b/tests/bodies.cpp @@ -470,23 +470,18 @@ TEST_CASE("Body drag") TEST_CASE("Excentric body") { - moordyn::MoorDyn system{ "Mooring/body_tests/floatingBodies.txt" }; + moordyn::MoorDyn system{ "Mooring/body_tests/orbitalBody.txt" }; double f[3]; - double initial_angular_vel = 0.2; + const double radius = 10.0; + const double omega = 0.2; + const moordyn::vec r0 = moordyn::vec(0, 0, 20.0); auto bodies = system.GetBodies(); + for (auto body : bodies) { - auto body = bodies.at(0); - const auto [pos, vel] = body->getState(); - const moordyn::vec6 new_vel = - moordyn::vec6(0.0, 0.0, 0.0, initial_angular_vel, 0.0, 0.0); - body->setState(pos, new_vel); - } - { - auto body = bodies.at(1); const auto [pos, vel] = body->getState(); const moordyn::vec6 new_vel = moordyn::vec6( - 0.0, 0.0, 10 * initial_angular_vel, initial_angular_vel, 0.0, 0.0); + 0.0, 0.0, radius * omega, omega, 0.0, 0.0); body->setState(pos, new_vel); } @@ -502,16 +497,22 @@ TEST_CASE("Excentric body") REQUIRE(write_system_vtk(system, t, series_writer)); while ((t_max - t) > (0.1 * dt)) { REQUIRE(system.Step(NULL, NULL, f, t, dt) == MOORDYN_SUCCESS); + for (auto body : bodies) { - const auto body = bodies.at(1); const auto [pos, vel] = body->getState(); const moordyn::vec3 global_pos = pos.pos; - const moordyn::real expected_y = 10 * cos(initial_angular_vel * t); - const moordyn::real expected_z = - 20 + 10 * sin(initial_angular_vel * t); - const auto err_y = global_pos.y() - expected_y; - const auto err_z = global_pos.z() - expected_z; - REQUIRE((abs(err_y) <= 1e-4 && abs(err_z) <= 1e-4)); + const moordyn::vec q = (global_pos - r0) / radius; + const moordyn::real w = atan2(q.z(), q.y()) / t; + const auto err_r = (global_pos - r0).norm() - radius; + const auto err_w = atan2(q.z(), q.y()) / t - omega; + + // Check that we are orbiting at the right radius + REQUIRE(abs(err_r) <= 1e-6 * radius); + // Check that we are orbiting at the right velocity + // NOTE: While orbiting around the rod the angular speed is really + // stable. The same cannot be said of the orbital kinematics around + // the point, where the velocity can be almost 0.3 rad/s + REQUIRE(abs(err_w) <= 2e-1 * omega); } REQUIRE(write_system_vtk(system, t, series_writer)); From 8c0b8b0ebedeecf6f283504ca90dd617383c7291 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jul 2024 09:47:45 +0200 Subject: [PATCH 111/145] test: Strip the VTK from the test and attach two points to the body to get a more stable orbit --- tests/Mooring/body_tests/orbitalBody.txt | 3 +- tests/bodies.cpp | 96 ++---------------------- 2 files changed, 7 insertions(+), 92 deletions(-) diff --git a/tests/Mooring/body_tests/orbitalBody.txt b/tests/Mooring/body_tests/orbitalBody.txt index 5f07b1a3..e13f19f9 100644 --- a/tests/Mooring/body_tests/orbitalBody.txt +++ b/tests/Mooring/body_tests/orbitalBody.txt @@ -12,7 +12,8 @@ ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* ----------------------- POINTS ---------------------------------------------- Node Type X Y Z M V CdA CA (-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) -1 Body1 0.0 -10 0 40.0 0 0 0 +1 Body1 0.0 -10 -2 20.0 0 0 0 +2 Body1 0.0 -10 2 20.0 0 0 0 ---------------------- RODS ---------------------------------------- ID RodType Attachment Xa Ya Za Xb Yb Zb NumSegs RodOutputs (#) (name) (#/key) (m) (m) (m) (m) (m) (m) (-) (-) diff --git a/tests/bodies.cpp b/tests/bodies.cpp index e6e1186a..17bb1fc7 100644 --- a/tests/bodies.cpp +++ b/tests/bodies.cpp @@ -45,75 +45,10 @@ #include #include #include - #include "util.h" using namespace std; -#ifdef USE_VTK - -bool -write_system_vtk(MoorDyn in_system, double time, SeriesWriter* series_writer) -{ - // if no series writer, we do nothing but pretend to work - if (series_writer == NULL) { - return true; - } - - moordyn::MoorDyn* system = (moordyn::MoorDyn*)(in_system); - std::stringstream filename; - std::stringstream element_name; - element_name << "vtk_system"; - auto& vtp_series = series_writer->getSeries(element_name.str()); - auto step_num = vtp_series.time_steps.size(); - - filename << element_name.str() << "." << step_num << ".vtm"; - std::string full_path = "../../vtk_out/" + filename.str(); - // std::cout << "*** Saving on '" << full_path << "'..." << - // std::endl; - vtp_series.time_steps.push_back({ filename.str(), time }); - system->saveVTK(full_path.c_str()); - return true; -} - - -bool -write_system_vtk(moordyn::MoorDyn& system, - double time, - SeriesWriter* series_writer) -{ - if (series_writer == nullptr) { - return true; - } - // if (system.GetLines().empty()) { - // return true; - // } - std::stringstream filename; - std::stringstream element_name; - element_name << "vtk_system"; - auto& vtp_series = series_writer->getSeries(element_name.str()); - auto step_num = vtp_series.time_steps.size(); - - filename << element_name.str() << "." << step_num << ".vtm"; - std::string full_path = "../../vtk_out/" + filename.str(); - // std::cout << "*** Saving on '" << full_path << "'..." << - // std::endl; - vtp_series.time_steps.push_back({ filename.str(), time }); - system.saveVTK(full_path.c_str()); - return true; -} - -#else -class SeriesWriter; - -bool -write_system_vtk(MoorDyn in_system, double time, SeriesWriter* series_writer) -{ - return true; -} - -#endif - /** * @brief Represents a number of times and data for coupled DOFs * @@ -166,7 +101,6 @@ struct Trajectory * @param trajectory The trajectory to use for the coupled DOFs * @param t Reference to the time, makes it easier to integrate into program * flow - * @param series_writer Used to write out vtk series * @return true Success * @return false Failure */ @@ -174,8 +108,7 @@ template bool followTrajectory(MoorDyn& system, const Trajectory& trajectory, - double& t, - SeriesWriter* series_writer) + double& t) { int err; @@ -192,15 +125,10 @@ followTrajectory(MoorDyn& system, err = MoorDyn_Step(system, x.data(), dx.data(), f.data(), &t, &dt); if (err != MOORDYN_SUCCESS) return false; - - if (!write_system_vtk(system, t, series_writer)) - return false; } return true; } -#define series_writer NULL - /** * @brief Uses a line between a point on the body and a coupled point to rotate * the body around @@ -233,13 +161,11 @@ TEST_CASE("Rotating body") MoorDynPoint point = MoorDyn_GetPoint(system, 8); REQUIRE(point); - REQUIRE(write_system_vtk(system, 0, series_writer)); double t = 0, dt = 0.1; // do one outer time step just to make sure everything is settled REQUIRE(MoorDyn_Step( system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); double start_t = t; // goes from (2, 0, 0) to (0, 0, 2) in 2 seconds @@ -251,7 +177,7 @@ TEST_CASE("Rotating body") x = body_center + (radius * moordyn::vec3{ cos(angle), 0, sin(angle) }); return x; }); - REQUIRE(followTrajectory(system, trajectory, t, series_writer)); + REQUIRE(followTrajectory(system, trajectory, t)); start_t = t; x = body_center + moordyn::vec3(0.0, 0.0, 0.05 + radius); @@ -260,7 +186,6 @@ TEST_CASE("Rotating body") while (t < start_t + 0.5) { REQUIRE(MoorDyn_Step( system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); } moordyn::vec3 point_pos; @@ -282,7 +207,7 @@ TEST_CASE("Rotating body") x = body_center + (radius * moordyn::vec3{ 0, sin(angle), cos(angle) }); return x; }); - REQUIRE(followTrajectory(system, trajectory2, t, series_writer)); + REQUIRE(followTrajectory(system, trajectory2, t)); start_t = t; x = body_center + moordyn::vec3(0.0, radius + 0.05, 0); @@ -291,7 +216,6 @@ TEST_CASE("Rotating body") while (t < start_t + 0.5) { REQUIRE(MoorDyn_Step( system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); } REQUIRE(MoorDyn_GetPointPos(point, point_pos.data()) == MOORDYN_SUCCESS); @@ -313,7 +237,7 @@ TEST_CASE("Rotating body") x = body_center + (radius * moordyn::vec3{ sin(angle), cos(angle), 0 }); return x; }); - REQUIRE(followTrajectory(system, trajectory3, t, series_writer)); + REQUIRE(followTrajectory(system, trajectory3, t)); start_t = t; x = body_center + moordyn::vec3(radius + 0.05, 0, 0); @@ -322,7 +246,6 @@ TEST_CASE("Rotating body") while (t < start_t + 0.5) { REQUIRE(MoorDyn_Step( system, x.data(), dx.data(), f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); } REQUIRE(MoorDyn_GetPointPos(point, point_pos.data()) == MOORDYN_SUCCESS); @@ -392,7 +315,6 @@ TEST_CASE("Pinned body") double f[6]; REQUIRE(MoorDyn_Init(system, x.data(), xd.data()) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, 0, series_writer)); auto body = MoorDyn_GetBody(system, 1); REQUIRE(body); @@ -402,15 +324,12 @@ TEST_CASE("Pinned body") double t = 0.0, dt = 0.01, accel = 0.5; bool local_min_max; - REQUIRE(write_system_vtk(system, t, series_writer)); - while (t < 50.0) { x[1] = 0.5 * accel * pow(t, 2); xd[1] = accel * t; REQUIRE(MoorDyn_Step( system, x.data(), xd.data(), f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); REQUIRE(MoorDyn_GetBodyState( body, r.data(), rd.data()) == MOORDYN_SUCCESS); @@ -454,7 +373,6 @@ TEST_CASE("Body drag") double f[3]; REQUIRE(MoorDyn_Init(system, nullptr, nullptr) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, 0, series_writer)); double t = 0, dt = 0.1; double max_t = 5; @@ -462,7 +380,6 @@ TEST_CASE("Body drag") // do one outer time step just to make sure everything is settled REQUIRE(MoorDyn_Step( system, nullptr, nullptr, f, &t, &dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); } REQUIRE(MoorDyn_Close(system) == MOORDYN_SUCCESS); @@ -494,7 +411,6 @@ TEST_CASE("Excentric body") // stuff double small_dt = 1e-6; REQUIRE(system.Step(NULL, NULL, f, t, small_dt) == MOORDYN_SUCCESS); - REQUIRE(write_system_vtk(system, t, series_writer)); while ((t_max - t) > (0.1 * dt)) { REQUIRE(system.Step(NULL, NULL, f, t, dt) == MOORDYN_SUCCESS); for (auto body : bodies) @@ -512,9 +428,7 @@ TEST_CASE("Excentric body") // NOTE: While orbiting around the rod the angular speed is really // stable. The same cannot be said of the orbital kinematics around // the point, where the velocity can be almost 0.3 rad/s - REQUIRE(abs(err_w) <= 2e-1 * omega); + REQUIRE(abs(err_w) <= 1e-6 * omega); } - - REQUIRE(write_system_vtk(system, t, series_writer)); } } From c4ffd668610e02316d17e411535b4f9a086b2787 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jul 2024 10:27:31 +0200 Subject: [PATCH 112/145] build: MinGW needs the DECLDIR on Body::setState --- source/Body.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Body.hpp b/source/Body.hpp index d123f1de..26b00c20 100644 --- a/source/Body.hpp +++ b/source/Body.hpp @@ -369,7 +369,7 @@ class Body final : public io::IO, public SuperCFL * @param r The position * @param rd The velocity */ - void setState(XYZQuat r, vec6 rd); + void DECLDIR setState(XYZQuat r, vec6 rd); /** @brief calculate the forces and state derivatives of the body * From bcdf7fe0b84551c2e9f69ceac17d9f7c3f6a6e06 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 2 Jul 2024 10:47:52 +0200 Subject: [PATCH 113/145] fix: Freeze when writeLog is not the first option --- source/MoorDyn2.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index be5b49a4..ca14d00d 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -895,6 +895,7 @@ moordyn::MoorDyn::ReadInFile() return err; break; } + i++; } } // Now we can read all the options From 7dd2a4c46d0e2b043f9a08c99d75b18b631b4030 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jul 2024 06:54:10 +0200 Subject: [PATCH 114/145] fix: Centripetal force for parallel axes shall be null --- source/Point.cpp | 2 +- source/Rod.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/source/Point.cpp b/source/Point.cpp index dd71b82f..177e7ed7 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -320,7 +320,7 @@ Point::getCentripetalForce(vec rRef, vec w) const { const vec rRel = r - rRef; - return w.squaredNorm() * (M * rRel); + return -M * (w.cross(w.cross(rRel))); } moordyn::error_id diff --git a/source/Rod.cpp b/source/Rod.cpp index 1e8436d3..e8dc3108 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -825,7 +825,7 @@ Rod::getCentripetalForce(vec rRef, vec w) const vec F = vec::Zero(); for (unsigned int i = 0; i <= N; i++) { const vec rRel = r[i] - rRef; - F += w.squaredNorm() * (M[i] * rRel); + F -= M[i] * (w.cross(w.cross(rRel))); } return F; } From 50a919ea6bd35bdad9de68b7d6d5a80bad6f4966 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jul 2024 07:11:01 +0200 Subject: [PATCH 115/145] fix: Rebranding to include centripetal forces on getNetForceAndMass --- source/Body.cpp | 7 ++----- source/Point.cpp | 12 +++--------- source/Point.hpp | 35 ++++++++++++++++------------------- source/Rod.cpp | 18 +++--------------- source/Rod.hpp | 45 ++++++++++++++++++++++++++------------------- 5 files changed, 50 insertions(+), 67 deletions(-) diff --git a/source/Body.cpp b/source/Body.cpp index 3efb40ab..59310fb1 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -588,8 +588,7 @@ Body::doRHS() // orientation) vec6 F6_i; mat6 M6_i; - attached->getNetForceAndMass(F6_i, M6_i, r7.pos); - F6_i(Eigen::seqN(0, 3)) += attached->getCentripetalForce(r7.pos, v6); + attached->getNetForceAndMass(F6_i, M6_i, r7.pos, v6); // sum quantitites F6net += F6_i; @@ -602,9 +601,7 @@ Body::doRHS() // orientation) vec6 F6_i; mat6 M6_i; - attached->getNetForceAndMass(F6_i, M6_i, r7.pos); - F6_i(Eigen::seqN(0, 3)) += attached->getCentripetalForce(r7.pos, v6); - + attached->getNetForceAndMass(F6_i, M6_i, r7.pos, v6); // // calculate relative location of rod about body center in // global orientation double rRod_i[3]; diff --git a/source/Point.cpp b/source/Point.cpp index 177e7ed7..e2eb2979 100644 --- a/source/Point.cpp +++ b/source/Point.cpp @@ -299,7 +299,7 @@ Point::getStateDeriv() }; void -Point::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody) +Point::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody, vec6 vBody) { doRHS(); @@ -310,19 +310,13 @@ Point::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody) // convert segment net force into 6dof force about body ref point Fnet_out(Eigen::seqN(0, 3)) = Fnet; Fnet_out(Eigen::seqN(3, 3)) = rRel.cross(Fnet); + // add the centripetal force + Fnet_out(Eigen::seqN(0, 3)) += getCentripetalForce(rBody, vBody.tail<3>()); // convert segment mass matrix to 6by6 mass matrix about body ref point M_out = translateMass(rRel, M); } -vec -Point::getCentripetalForce(vec rRef, vec w) const -{ - const vec rRel = r - rRef; - - return -M * (w.cross(w.cross(rRel))); -} - moordyn::error_id Point::doRHS() { diff --git a/source/Point.hpp b/source/Point.hpp index afec6448..0e2eb07c 100644 --- a/source/Point.hpp +++ b/source/Point.hpp @@ -367,28 +367,13 @@ class Point final : public io::IO, public SuperCFL * parent body * @param Fnet_out Output Force about body ref point * @param M_out Output Mass matrix about body ref point - * @param rBody The body position. If NULL, {0, 0, 0} is considered - */ - void getNetForceAndMass(vec6& Fnet_out, - mat6& M_out, - vec rBody = vec::Zero()); - - /** @brief Calculate the centripetal force on a body - * @param rBody The body position - * @param vBody The body angular velocity - * @return Centripetal force on the body - */ - vec getCentripetalForce(vec rBody, vec vBody) const; - - /** @brief Calculate the centripetal force on a body * @param rBody The body position * @param vBody The body velocity - * @return Centripetal force on the body */ - inline vec getCentripetalForce(vec rBody, vec6 vBody) const - { - return getCentripetalForce(rBody, (vec)(vBody.tail<3>())); - } + void getNetForceAndMass(vec6& Fnet_out, + mat6& M_out, + vec rBody = vec::Zero(), + vec6 vBody = vec6::Zero()); /** @brief Calculates the forces and mass on the point, including from * attached lines @@ -436,6 +421,18 @@ class Point final : public io::IO, public SuperCFL */ void saveVTK(const char* filename) const; #endif + + private: + /** @brief Calculate the centripetal force on a body + * @param r The body position + * @param w The body angular velocity + * @return Centripetal force on the body + */ + inline vec getCentripetalForce(vec r, vec w) const + { + return -M * (w.cross(w.cross(this->r - r))); + } + }; } // ::moordyn diff --git a/source/Rod.cpp b/source/Rod.cpp index e8dc3108..06c0c04f 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -741,7 +741,7 @@ Rod::getFnet() const // calculate the aggregate 6DOF rigid-body force and mass data of the rod void -Rod::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rRef) +Rod::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rRef, vec6 vRef) { // rBody is the location of the body reference point. A NULL pointer value // means the end A coordinates should be used instead. @@ -765,6 +765,8 @@ Rod::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rRef) // shift net forces and add the existing moments const vec f3net = F6net(Eigen::seqN(0, 3)); Fnet_out(Eigen::seqN(3, 3)) = F6net(Eigen::seqN(3, 3)) + rRel.cross(f3net); + // add the centripetal force + Fnet_out(Eigen::seqN(0, 3)) += getCentripetalForce(rRef, vRef.tail<3>()); // shift mass matrix to be about ref point M_out = translateMass6(rRel, M6net); @@ -816,20 +818,6 @@ Rod::getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rRef) */ } -vec -Rod::getCentripetalForce(vec rRef, vec w) const -{ - if (!N) - return vec::Zero(); - - vec F = vec::Zero(); - for (unsigned int i = 0; i <= N; i++) { - const vec rRel = r[i] - rRef; - F -= M[i] * (w.cross(w.cross(rRel))); - } - return F; -} - real calcSubSeg(vec p1, vec p2, real surface_height, real diameter) { diff --git a/source/Rod.hpp b/source/Rod.hpp index 074a6361..d426183f 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -539,8 +539,12 @@ class Rod final : public io::IO, public SuperCFL * @param Fnet_out Output Force about body ref point * @param M_out Output Mass matrix about body ref point * @param rBody The body position + * @param vBody The body velocity */ - void getNetForceAndMass(vec6& Fnet_out, mat6& M_out, vec rBody); + void getNetForceAndMass(vec6& Fnet_out, + mat6& M_out, + vec rBody, + vec6 vBody); /** @brief Calculate the force and mass contributions of the point on the * parent body @@ -549,24 +553,7 @@ class Rod final : public io::IO, public SuperCFL */ inline void getNetForceAndMass(vec6& Fnet_out, mat6& M_out) { - getNetForceAndMass(Fnet_out, M_out, r[0]); - } - - /** @brief Calculate the centripetal force on a body - * @param rBody The body position - * @param vBody The body angular velocity - * @return Centripetal force on the body - */ - vec getCentripetalForce(vec rBody, vec vBody) const; - - /** @brief Calculate the centripetal force on a body - * @param rBody The body position - * @param vBody The body velocity - * @return Centripetal force on the body - */ - inline vec getCentripetalForce(vec rBody, vec6 vBody) const - { - return getCentripetalForce(rBody, (vec)(vBody.tail<3>())); + getNetForceAndMass(Fnet_out, M_out, r[0], vec6::Zero()); } /** @brief This is the big function that calculates the forces on the rod, @@ -615,6 +602,26 @@ class Rod final : public io::IO, public SuperCFL */ void saveVTK(const char* filename) const; #endif + + private: + /** @brief Calculate the centripetal force on a body + * @param r The body position + * @param w The body angular velocity + * @return Centripetal force on the body + */ + inline vec getCentripetalForce(vec r, vec w) const + { + if (!N) + return vec::Zero(); + + vec F = vec::Zero(); + for (unsigned int i = 0; i <= N; i++) { + F -= M[i] * (w.cross(w.cross(this->r[i] - r))); + } + return F; + } + + }; } // ::moordyn From 8b6896758efba5e861fb944c92ab2501b60459bc Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 4 Jul 2024 06:08:11 +0200 Subject: [PATCH 116/145] fix: Add a centripetal force to bodies with a excentric COG --- source/Body.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/source/Body.cpp b/source/Body.cpp index 59310fb1..8acdc640 100644 --- a/source/Body.cpp +++ b/source/Body.cpp @@ -558,6 +558,11 @@ Body::doRHS() F6net(Eigen::seqN(0, 3)) = Fgrav; F6net(Eigen::seqN(3, 3)) = body_rCGrotated.cross(Fgrav); + // Centrifugal force due to COM not being at body origin + const vec w = v6.tail<3>(); + F6net.head<3>() -= + M.topLeftCorner(3, 3) * (w.cross(w.cross(body_rCGrotated))); + // --------------------------------- apply wave kinematics // ------------------------------------ From 1c59dcab1240920f346b684913956e77123c82e1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 8 Jul 2024 03:12:22 +0000 Subject: [PATCH 117/145] Bump pypa/cibuildwheel from 2.19.1 to 2.19.2 Bumps [pypa/cibuildwheel](https://github.com/pypa/cibuildwheel) from 2.19.1 to 2.19.2. - [Release notes](https://github.com/pypa/cibuildwheel/releases) - [Changelog](https://github.com/pypa/cibuildwheel/blob/main/docs/changelog.md) - [Commits](https://github.com/pypa/cibuildwheel/compare/v2.19.1...v2.19.2) --- updated-dependencies: - dependency-name: pypa/cibuildwheel dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] --- .github/workflows/python-wheels-manylinux-arch.yml | 2 +- .github/workflows/python-wheels.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/python-wheels-manylinux-arch.yml b/.github/workflows/python-wheels-manylinux-arch.yml index 85974297..d58a514d 100644 --- a/.github/workflows/python-wheels-manylinux-arch.yml +++ b/.github/workflows/python-wheels-manylinux-arch.yml @@ -53,7 +53,7 @@ jobs: platforms: all - name: Build wheels - uses: pypa/cibuildwheel@v2.19.1 + uses: pypa/cibuildwheel@v2.19.2 with: output-dir: dist env: diff --git a/.github/workflows/python-wheels.yml b/.github/workflows/python-wheels.yml index 31e415eb..2dce4243 100644 --- a/.github/workflows/python-wheels.yml +++ b/.github/workflows/python-wheels.yml @@ -81,7 +81,7 @@ jobs: if: runner.os == 'Linux' - name: Build wheels - uses: pypa/cibuildwheel@v2.19.1 + uses: pypa/cibuildwheel@v2.19.2 with: output-dir: dist env: From 4feaebacd9557519de44d751fdd5280b86147198 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 3 Jul 2024 12:17:07 +0200 Subject: [PATCH 118/145] fix: EulerZYX -> EulerXYZ on moordyn::Euler2Quat() --- source/Misc.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/Misc.hpp b/source/Misc.hpp index 2514ca72..54832b3e 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -262,9 +262,9 @@ inline quaternion Euler2Quat(const vec3& angles) { using AngleAxis = Eigen::AngleAxis; - quaternion q = AngleAxis(angles.x(), vec3::UnitX()) * + quaternion q = AngleAxis(angles.z(), vec3::UnitZ()) * AngleAxis(angles.y(), vec3::UnitY()) * - AngleAxis(angles.z(), vec3::UnitZ()); + AngleAxis(angles.x(), vec3::UnitX()); return q; } From 5f670e79a4c4b5749414820e31d87524345f6cdf Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 4 Jul 2024 06:39:28 +0200 Subject: [PATCH 119/145] fix: accelerations of Coupled/fixed bodies/rods when there are several isntances of them --- source/Body.hpp | 16 +++++++++++++--- source/MoorDyn2.cpp | 44 ++++++++++++-------------------------------- source/MoorDyn2.hpp | 6 ------ source/Rod.hpp | 12 ++++++++++-- 4 files changed, 35 insertions(+), 43 deletions(-) diff --git a/source/Body.hpp b/source/Body.hpp index 26b00c20..456ffcfe 100644 --- a/source/Body.hpp +++ b/source/Body.hpp @@ -248,7 +248,17 @@ class Body final : public io::IO, public SuperCFL * @throw moordyn::invalid_value_error If the body is of type * moordyn::Body::FREE */ - void initializeUnfreeBody(vec6 r = vec6::Zero(), vec6 rd = vec6::Zero(), vec6 rdd = vec6::Zero()); + void initializeUnfreeBody(vec6 r = vec6::Zero(), + vec6 rd = vec6::Zero(), + vec6 rdd = vec6::Zero()); + + /** @brief Get the last setted velocity for an unfree body + * + * For free bodies the behaviour is undetermined + * + * @return The velocity (6 dof) + */ + inline vec6 getUnfreeVel() const { return rd_ves; } /** @brief Initialize the FREE point state * @return The 6-dof position (first) and the 6-dof velocity (second) @@ -349,11 +359,11 @@ class Body final : public io::IO, public SuperCFL * boundary conditions (body kinematics) for the proceeding time steps * @param r The input position * @param rd The input velocity - * @param rdd The input velocity + * @param rdd The input acceleration * @throw moordyn::invalid_value_error If the body is not of type * moordyn::Body::COUPLED or moordyn::Body::FIXED */ - void initiateStep(vec6 r_in, vec6 rd_in, vec6 rdd_in); + void initiateStep(vec6 r, vec6 rd, vec6 rdd); /** @brief Sets the kinematics based on the position and velocity of the * fairlead. diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index ca14d00d..a6a89a37 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -433,14 +433,10 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) << x[ix + 1] << ", " << x[ix + 2] << "..." << endl; // BUG: These conversions will not be needed in the future - vec6 r, rd, rdd; + vec6 r, rd; if (BodyList[l]->type == Body::COUPLED){ moordyn::array2vec6(x + ix, r); moordyn::array2vec6(xd + ix, rd); - // determine acceleration - rdd = (rd - rd_b) / dtM0; - rd_b = rd; - ix += 6; } else { // for pinned body 3 entries will be taken @@ -449,13 +445,9 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) r(Eigen::seqN(0, 3)) = r3; moordyn::array2vec(xd + ix, rd3); rd(Eigen::seqN(0, 3)) = rd3; - // determine acceleration - rdd(Eigen::seqN(0, 3)) = (rd3 - rd3_b) / dtM0; - rd3_b = rd3; - ix += 3; } - BodyList[l]->initializeUnfreeBody(r, rd, rdd); + BodyList[l]->initializeUnfreeBody(r, rd, vec6::Zero()); } for (auto l : CpldRodIs) { @@ -466,10 +458,6 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // for cantilevered rods 6 entries will be taken moordyn::array2vec6(x + ix, r); moordyn::array2vec6(xd + ix, rd); - // determine acceleration - rdd = (rd - rd_r) / dtM0; - rd_r = rd; - ix += 6; } else { // for pinned rods 3 entries will be taken @@ -478,13 +466,9 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) r(Eigen::seqN(0, 3)) = r3; moordyn::array2vec(xd + ix, rd3); rd(Eigen::seqN(0, 3)) = rd3; - // determine acceleration - rdd(Eigen::seqN(0, 3)) = (rd3 - rd3_r) / dtM0; - rd3_r = rd3; - ix += 3; } - RodList[l]->initiateStep(r, rd, rdd); + RodList[l]->initiateStep(r, rd, vec6::Zero()); RodList[l]->updateFairlead(0.0); // call this just to set up the output file header RodList[l]->initialize(); @@ -655,13 +639,12 @@ moordyn::MoorDyn::Step(const double* x, for (auto l : CpldBodyIs) { // BUG: These conversions will not be needed in the future vec6 r, rd, rdd; + const vec6 rd_b = BodyList[l]->getUnfreeVel(); if (BodyList[l]->type == Body::COUPLED){ moordyn::array2vec6(x + ix, r); moordyn::array2vec6(xd + ix, rd); // determine acceleration - rdd = (rd - rd_b) / dtM0; - rd_b = rd; - + rdd = (rd - rd_b) / dt; ix += 6; } else { // for pinned body 3 entries will be taken @@ -671,23 +654,21 @@ moordyn::MoorDyn::Step(const double* x, moordyn::array2vec(xd + ix, rd3); rd(Eigen::seqN(0, 3)) = rd3; // determine acceleration - rdd(Eigen::seqN(0, 3)) = (rd3 - rd3_b) / dt; - rd3_b = rd3; - + rdd(Eigen::seqN(0, 3)) = (rd3 - rd_b.head<3>()) / dt; ix += 3; } - BodyList[l]->initiateStep(r, rd, rdd); // acceleration required for inertial terms + // acceleration required for inertial terms + BodyList[l]->initiateStep(r, rd, rdd); } for (auto l : CpldRodIs) { vec6 r, rd, rdd; + const vec6 rd_r = RodList[l]->getUnfreeVel(); if (RodList[l]->type == Rod::COUPLED) { // for cantilevered rods 6 entries will be taken moordyn::array2vec6(x + ix, r); moordyn::array2vec6(xd + ix, rd); // determine acceleration rdd = (rd - rd_r) / dt; - rd_r = rd; - ix += 6; } else { // for pinned rods 3 entries will be taken @@ -697,12 +678,11 @@ moordyn::MoorDyn::Step(const double* x, moordyn::array2vec(xd + ix, rd3); rd(Eigen::seqN(0, 3)) = rd3; // determine acceleration - rdd(Eigen::seqN(0, 3)) = (rd3 - rd3_r) / dt; - rd3_r = rd3; - + rdd(Eigen::seqN(0, 3)) = (rd3 - rd_r.head<3>()) / dt; ix += 3; } - RodList[l]->initiateStep(r, rd, rdd); // acceleration required for inertial terms + // acceleration required for inertial terms + RodList[l]->initiateStep(r, rd, rdd); } for (auto l : CpldPointIs) { vec r, rd; diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index 923e153c..599a8234 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -627,12 +627,6 @@ class MoorDyn final : public io::IO /// (if using env.WaveKin=1) unsigned int npW; - /// Previous time step velocity for calculating coupled point acceleration (first time step assumed stationary) - vec6 rd_b = vec6::Zero(); // body - vec6 rd_r = vec6::Zero(); // coupled rod - vec3 rd3_r = vec3::Zero(); // coupled pinned rod - vec3 rd3_b = vec3::Zero(); // coupled pinned body - /// main output file ofstream outfileMain; diff --git a/source/Rod.hpp b/source/Rod.hpp index d426183f..0107914c 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -473,13 +473,21 @@ class Rod final : public io::IO, public SuperCFL * boundary conditions (rod kinematics) for the proceeding time steps * @param r The input position * @param rd The input velocity - * @param rdd The input velocity + * @param rdd The input acceleration * @throw moordyn::invalid_value_error If the rod is not of type * moordyn::Rod::COUPLED or moordyn::Rod::CPLDPIN * @note If the rod is of type moordyn::Rod::CPLDPIN, then just 3 components * of @p r and @p rd are considered */ - void initiateStep(vec6 r_in, vec6 rd_in, vec6 rdd_in); + void initiateStep(vec6 r, vec6 rd, vec6 rdd); + + /** @brief Get the last setted velocity for an unfree rod + * + * For free rods the behaviour is undetermined + * + * @return The velocity (6 dof) + */ + inline vec6 getUnfreeVel() const { return rd_ves; } /** @brief Sets the kinematics * From d0ea9e127e05ecc2016e948968520bb57209d8bd Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 4 Jul 2024 08:28:28 +0200 Subject: [PATCH 120/145] fix: Odd treatment was meant for indexes from 1 to 3, not 0 to 2, and the matrix indexes were transposed --- source/Misc.hpp | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/source/Misc.hpp b/source/Misc.hpp index 54832b3e..b12c3034 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -190,9 +190,9 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // s2s3 -c2s1s3 + c1c3 -c2c1s3 - s1c3 // -s2c3 c2s1c3 + c1s3 c2c1c3 - s1s3 // Note: s2 is always positive. - Scalar s2 = Eigen::numext::hypot(coeff(j, i), coeff(k, i)); - if (odd) { - res[0] = atan2(coeff(j, i), coeff(k, i)); + Scalar s2 = Eigen::numext::hypot(coeff(i, j), coeff(i, k)); + if (!odd) { + res[0] = atan2(coeff(i, j), coeff(i, k)); // s2 is always positive, so res[1] will be within the canonical [0, // pi] range res[1] = atan2(s2, coeff(i, i)); @@ -211,7 +211,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // arguments to atan2, while the calculation of the third angle does // not need special adjustment since it uses the adjusted res[0] as // the input and produces a correct result. - res[0] = atan2(-coeff(j, i), -coeff(k, i)); + res[0] = atan2(-coeff(i, j), -coeff(i, k)); res[1] = -atan2(s2, coeff(i, i)); } // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first @@ -225,8 +225,8 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // Thus: m11.c1 - m21.s1 = c3 & m12.c1 - m22.s1 = s3 Scalar s1 = sin(res[0]); Scalar c1 = cos(res[0]); - res[2] = atan2(c1 * coeff(j, k) - s1 * coeff(k, k), - c1 * coeff(j, j) - s1 * coeff(k, j)); + res[2] = atan2(c1 * coeff(k, j) - s1 * coeff(k, k), + c1 * coeff(j, j) - s1 * coeff(j, k)); } else { // Tait-Bryan angles (all three axes are different; typically used for // yaw-pitch-roll calculations). The i, j, k indices enable addressing @@ -236,17 +236,17 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // c2c3 s2s1c3 - c1s3 s2c1c3 + s1s3 // c2s3 s2s1s3 + c1c3 s2c1s3 - s1c3 // -s2 c2s1 c2c1 - res[0] = atan2(coeff(j, k), coeff(k, k)); - Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(i, j)); + res[0] = atan2(coeff(k, j), coeff(k, k)); + Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(j, i)); // c2 is always positive, so the following atan2 will always return a // result in the correct canonical middle angle range [-pi/2, pi/2] - res[1] = atan2(-coeff(i, k), c2); + res[1] = atan2(-coeff(k, i), c2); Scalar s1 = sin(res[0]); Scalar c1 = cos(res[0]); - res[2] = atan2(s1 * coeff(k, i) - c1 * coeff(j, i), - c1 * coeff(j, j) - s1 * coeff(k, j)); + res[2] = atan2(s1 * coeff(i, k) - c1 * coeff(i, j), + c1 * coeff(j, j) - s1 * coeff(j, k)); } - if (!odd) { + if (odd) { res = -res; } return res; @@ -255,7 +255,8 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) inline vec3 Quat2Euler(const quaternion& q) { - return canonicalEulerAngles(q, 0, 1, 2); // 0, 1, 2 correspond to axes leading to XYZ rotation + // 0, 1, 2 correspond to axes leading to XYZ rotation + return canonicalEulerAngles(q, 0, 1, 2); } inline quaternion From fce77568d66b2c220c1e6b0a3a9c2c31f4b00955 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 4 Jul 2024 08:58:45 +0200 Subject: [PATCH 121/145] test: Test the rotations --- .github/workflows/python-wrapper.yml | 2 +- tests/Mooring/rotations/nwu.txt | 44 +++++++++++ tests/test_generator.py | 2 - tests/test_minimal.py | 3 +- tests/test_rotations.py | 108 +++++++++++++++++++++++++++ 5 files changed, 154 insertions(+), 5 deletions(-) create mode 100644 tests/Mooring/rotations/nwu.txt create mode 100644 tests/test_rotations.py diff --git a/.github/workflows/python-wrapper.yml b/.github/workflows/python-wrapper.yml index da136713..ed80d237 100644 --- a/.github/workflows/python-wrapper.yml +++ b/.github/workflows/python-wrapper.yml @@ -31,7 +31,7 @@ jobs: id: setup-python - name: Install Python dependencies - run: pip install --upgrade build pytest + run: pip install --upgrade build pytest numpy scipy - name: Install VTK run: | diff --git a/tests/Mooring/rotations/nwu.txt b/tests/Mooring/rotations/nwu.txt new file mode 100644 index 00000000..6ab64ee9 --- /dev/null +++ b/tests/Mooring/rotations/nwu.txt @@ -0,0 +1,44 @@ +--------------------- MoorDyn Input File ------------------------------------------------------- +Testing the rotations assuming the NWU angles criteria, i.e. the bow is +pointing towards the x axis, the portside towards the y axis and the z axis +upwards. +To check the rotations we set 3 points pointing on the positive x, y and z + +The rotations are thus consistent with the EulerXYZ criteria: + + - Roll: rotates around x axis, in such a way the starboard side (-y dir) goes + down + - Pitch: rotates around y axis, in such a way the bow (+x dir) goes down + - Yaw: rotates around y axis, in such a way the bow (+x dir) goes to the + portside + +The rotations can be contatenated on a straight forward way, i.e. you can get +the current state and just compute the velocity as the difference. e.g. + +double r[6], rd[6]; +const auto [r, tmp] = MoorDyn_GetBodyState(body, r, rd); +const double r_next[6] = {x, y, z, roll, pitch, yaw}; +for (unsigned int i = 0; i < 6; i++) { + rd[i] = (r_next[i] - r[i]) / dt; +} +MoorDyn_Step(system, r, rd, t, dt); +---------------------------- BODIES ----------------------------------------------------- +ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca +(#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-) +1 coupled 0 0 0 0 0 0 0 0 0 0 0 0 +----------------------- POINTS ---------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Body1 1 0 0 0 0 0 0 +2 Body1 0 1 0 0 0 0 0 +3 Body1 0 0 1 0 0 0 0 +-------------------------- SOLVER OPTIONS--------------------------------------------------- +0 writeLog - Write a log file +0.0 g - No gravity +1.0 dtM - time step to use in mooring integration +3.0e6 kb - bottom stiffness +3.0e5 cb - bottom damping +100 WtrDpth - water depth +0.0 TmaxIC - threshold for IC convergence +euler tScheme - Just one step per time step +--------------------------- need this line ------------------------------------------------- diff --git a/tests/test_generator.py b/tests/test_generator.py index 2589449d..f6d3bc79 100644 --- a/tests/test_generator.py +++ b/tests/test_generator.py @@ -1,6 +1,4 @@ import sys -print('HERE') -print(sys.path) from unittest import TestCase, main as unittest_main import moordyn diff --git a/tests/test_minimal.py b/tests/test_minimal.py index 7d668109..fe610a0f 100644 --- a/tests/test_minimal.py +++ b/tests/test_minimal.py @@ -1,5 +1,4 @@ import sys -print(sys.path) from unittest import TestCase, main as unittest_main import os import tempfile @@ -45,6 +44,7 @@ def test_one_iter(self): cwd = os.getcwd() os.chdir(tmp_folder) system = moordyn.Create() + os.chdir(cwd) x = [] for i in range(4, 7): point = moordyn.GetPoint(system, i) @@ -55,7 +55,6 @@ def test_one_iter(self): self.assertEqual(moordyn.NCoupledDOF(system), 9, "Wrong number of coupled DOFs") self.assertEqual(moordyn.GetNumberLines(system), 3) - os.chdir(cwd) v[0] = 0.1 forces = moordyn.Step(system, x, v, 0.0, 0.5) print(forces) diff --git a/tests/test_rotations.py b/tests/test_rotations.py new file mode 100644 index 00000000..12c4a2ea --- /dev/null +++ b/tests/test_rotations.py @@ -0,0 +1,108 @@ +import sys +from unittest import TestCase, main as unittest_main +import os +import moordyn +from scipy.spatial.transform import Rotation as R +import numpy as np +from test_minimal import setup_case + + +ENUREF = [[1, 0, 0], + [0, 1, 0], + [0, 0, 1]] +ANGLE = 5 + + +def rotate_vecs(vecs, angles, seq='xyz', degrees=True): + r = R.from_euler(seq, angles, degrees=degrees) + return [r.apply(vec) for vec in vecs] + + +def compare_vecs(vecs, refs, tol=1e-5): + assert len(vecs) == len(refs) + for i in range(len(vecs)): + assert len(vecs[i]) == len(refs[i]) + for j in range(len(vecs[i])): + assert abs(vecs[i][j] - refs[i][j]) < 1e-5 + + +def abseuler2releuler(org, dst, seq='xyz', degrees=True): + r0 = R.from_euler(seq, org, degrees=degrees).inv() + r1 = R.from_euler(seq, dst, degrees=degrees) + return (r1 * r0).as_euler(seq, degrees=degrees) + + +def rotate_moordyn(system, roll, pitch, yaw, t, dt=1.0, degrees=True): + if degrees: + roll = np.radians(roll) + pitch = np.radians(pitch) + yaw = np.radians(yaw) + pts = [moordyn.GetPoint(system, i + 1) for i in range(3)] + body = moordyn.GetBody(system, 1) + r, _ = moordyn.GetBodyState(body) + u = [0] * 3 + [roll / dt, pitch / dt, yaw / dt] + moordyn.Step(system, r, u, t, dt) + t += dt + r = [moordyn.GetPointPos(pt) for pt in pts] + return r, t + + +class RotationTests(TestCase): + def setUp(self): + pass + + def test_nwu(self): + tmp_folder = setup_case("rotations/nwu.txt") + cwd = os.getcwd() + os.chdir(tmp_folder) + system = moordyn.Create() + os.chdir(cwd) + pts = [moordyn.GetPoint(system, i + 1) for i in range(3)] + r = [0] * 6 + u = [0] * 6 + moordyn.Init(system, r, u) + # Check the intial condition + compare_vecs([moordyn.GetPointPos(pt) for pt in pts], ENUREF) + t = 0 + # Roll test + r, t = rotate_moordyn(system, ANGLE, 0, 0, t) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='x')) + assert(r[1][2] > 0.0) # Portside up, i.e. starboard down + r, t = rotate_moordyn(system, -ANGLE, 0, 0, t) + compare_vecs(r, ENUREF) + # Pitch test + r, t = rotate_moordyn(system, 0, ANGLE, 0, t) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='y')) + assert(r[0][2] < 0.0) # Bow down + r, t = rotate_moordyn(system, 0, -ANGLE, 0, t) + compare_vecs(r, ENUREF) + # Yaw test + r, t = rotate_moordyn(system, 0, 0, ANGLE, t) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='z')) + assert(r[0][1] > 0.0) # Bow to portside + r, t = rotate_moordyn(system, 0, 0, -ANGLE, t) + compare_vecs(r, ENUREF) + + # Test the angles order. For that we are rotating it in all directions + # simultaneously + r, t = rotate_moordyn(system, ANGLE, ANGLE, ANGLE, t) + compare_vecs(r, rotate_vecs(ENUREF, [ANGLE, ANGLE, ANGLE])) + r, t = rotate_moordyn(system, -ANGLE, -ANGLE, -ANGLE, t) + compare_vecs(r, ENUREF) + + # Test the rotations concatenations. To do that we are again rotating on + # the 3 axis simultaneously. However, this time we rotate twice, so the + # final angle shall be 2*ANGLE in all directions + rotate_moordyn(system, ANGLE, ANGLE, ANGLE, t) + r, t = rotate_moordyn(system, ANGLE, ANGLE, ANGLE, t) + roll, pitch, yaw = abseuler2releuler([ANGLE, ANGLE, ANGLE], + [2 * ANGLE, 2 * ANGLE, 2 * ANGLE]) + compare_vecs(r, rotate_vecs(rotate_vecs(ENUREF, [ANGLE, ANGLE, ANGLE]), + [roll, pitch, yaw])) + compare_vecs(r, rotate_vecs(ENUREF, [2 * ANGLE, 2 * ANGLE, 2 * ANGLE])) + + moordyn.Close(system) + + +if __name__ == '__main__': + unittest_main() From 1634d176124f49c23a0a1d2928c82e502b0d730b Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Thu, 4 Jul 2024 11:49:41 +0200 Subject: [PATCH 122/145] test: Typo on the config file description --- tests/Mooring/rotations/nwu.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/Mooring/rotations/nwu.txt b/tests/Mooring/rotations/nwu.txt index 6ab64ee9..945f79ad 100644 --- a/tests/Mooring/rotations/nwu.txt +++ b/tests/Mooring/rotations/nwu.txt @@ -9,7 +9,7 @@ The rotations are thus consistent with the EulerXYZ criteria: - Roll: rotates around x axis, in such a way the starboard side (-y dir) goes down - Pitch: rotates around y axis, in such a way the bow (+x dir) goes down - - Yaw: rotates around y axis, in such a way the bow (+x dir) goes to the + - Yaw: rotates around z axis, in such a way the bow (+x dir) goes to the portside The rotations can be contatenated on a straight forward way, i.e. you can get From a62b60fd4a7801e8fff4a6f2b4922e772bd25ce7 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 9 Jul 2024 06:55:55 +0200 Subject: [PATCH 123/145] fix: EulerXYZ intrinsic angles instead of extrinsic --- instrinsic_angles.patch | 119 ++++++++++++++++++++++++++++++++++++++++ source/Misc.hpp | 36 ++++++------ tests/test_rotations.py | 10 ++-- 3 files changed, 142 insertions(+), 23 deletions(-) create mode 100644 instrinsic_angles.patch diff --git a/instrinsic_angles.patch b/instrinsic_angles.patch new file mode 100644 index 00000000..c780b2e6 --- /dev/null +++ b/instrinsic_angles.patch @@ -0,0 +1,119 @@ +diff --git a/source/Misc.hpp b/source/Misc.hpp +index b12c303..77d6b33 100644 +--- a/source/Misc.hpp ++++ b/source/Misc.hpp +@@ -168,11 +168,11 @@ EqualRealNos(const real a1, const real a2) + return std::abs(a1 - a2) <= fraction * tol; + } + +- +-inline vec3 ++inline vec3 + canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + { +- // From issue #163: https://github.com/FloatingArrayDesign/MoorDyn/issues/163 ++ // From issue #163: ++ // https://github.com/FloatingArrayDesign/MoorDyn/issues/163 + mat3 coeff = quat.normalized().toRotationMatrix(); + vec3 res{}; + using Index = int; +@@ -190,9 +190,9 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + // s2s3 -c2s1s3 + c1c3 -c2c1s3 - s1c3 + // -s2c3 c2s1c3 + c1s3 c2c1c3 - s1s3 + // Note: s2 is always positive. +- Scalar s2 = Eigen::numext::hypot(coeff(i, j), coeff(i, k)); +- if (!odd) { +- res[0] = atan2(coeff(i, j), coeff(i, k)); ++ Scalar s2 = Eigen::numext::hypot(coeff(j, i), coeff(k, i)); ++ if (odd) { ++ res[0] = atan2(coeff(j, i), coeff(k, i)); + // s2 is always positive, so res[1] will be within the canonical [0, + // pi] range + res[1] = atan2(s2, coeff(i, i)); +@@ -211,7 +211,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + // arguments to atan2, while the calculation of the third angle does + // not need special adjustment since it uses the adjusted res[0] as + // the input and produces a correct result. +- res[0] = atan2(-coeff(i, j), -coeff(i, k)); ++ res[0] = atan2(-coeff(j, i), -coeff(k, i)); + res[1] = -atan2(s2, coeff(i, i)); + } + // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first +@@ -225,8 +225,8 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + // Thus: m11.c1 - m21.s1 = c3 & m12.c1 - m22.s1 = s3 + Scalar s1 = sin(res[0]); + Scalar c1 = cos(res[0]); +- res[2] = atan2(c1 * coeff(k, j) - s1 * coeff(k, k), +- c1 * coeff(j, j) - s1 * coeff(j, k)); ++ res[2] = atan2(c1 * coeff(j, k) - s1 * coeff(k, k), ++ c1 * coeff(j, j) - s1 * coeff(k, j)); + } else { + // Tait-Bryan angles (all three axes are different; typically used for + // yaw-pitch-roll calculations). The i, j, k indices enable addressing +@@ -236,17 +236,17 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + // c2c3 s2s1c3 - c1s3 s2c1c3 + s1s3 + // c2s3 s2s1s3 + c1c3 s2c1s3 - s1c3 + // -s2 c2s1 c2c1 +- res[0] = atan2(coeff(k, j), coeff(k, k)); +- Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(j, i)); ++ res[0] = atan2(coeff(j, k), coeff(k, k)); ++ Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(i, j)); + // c2 is always positive, so the following atan2 will always return a + // result in the correct canonical middle angle range [-pi/2, pi/2] +- res[1] = atan2(-coeff(k, i), c2); ++ res[1] = atan2(-coeff(i, k), c2); + Scalar s1 = sin(res[0]); + Scalar c1 = cos(res[0]); +- res[2] = atan2(s1 * coeff(i, k) - c1 * coeff(i, j), +- c1 * coeff(j, j) - s1 * coeff(j, k)); ++ res[2] = atan2(s1 * coeff(k, i) - c1 * coeff(j, i), ++ c1 * coeff(j, j) - s1 * coeff(k, j)); + } +- if (odd) { ++ if (!odd) { + res = -res; + } + return res; +@@ -255,7 +255,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) + inline vec3 + Quat2Euler(const quaternion& q) + { +- // 0, 1, 2 correspond to axes leading to XYZ rotation ++ // 0, 1, 2 correspond to axes leading to XYZ rotation + return canonicalEulerAngles(q, 0, 1, 2); + } + +@@ -263,9 +263,9 @@ inline quaternion + Euler2Quat(const vec3& angles) + { + using AngleAxis = Eigen::AngleAxis; +- quaternion q = AngleAxis(angles.z(), vec3::UnitZ()) * ++ quaternion q = AngleAxis(angles.x(), vec3::UnitX()) * + AngleAxis(angles.y(), vec3::UnitY()) * +- AngleAxis(angles.x(), vec3::UnitX()); ++ AngleAxis(angles.z(), vec3::UnitZ()); + return q; + } + +diff --git a/tests/test_rotations.py b/tests/test_rotations.py +index 12c4a2e..dfa4a6a 100644 +--- a/tests/test_rotations.py ++++ b/tests/test_rotations.py +@@ -13,7 +13,7 @@ ENUREF = [[1, 0, 0], + ANGLE = 5 + + +-def rotate_vecs(vecs, angles, seq='xyz', degrees=True): ++def rotate_vecs(vecs, angles, seq="XYZ", degrees=True): + r = R.from_euler(seq, angles, degrees=degrees) + return [r.apply(vec) for vec in vecs] + +@@ -26,7 +26,7 @@ def compare_vecs(vecs, refs, tol=1e-5): + assert abs(vecs[i][j] - refs[i][j]) < 1e-5 + + +-def abseuler2releuler(org, dst, seq='xyz', degrees=True): ++def abseuler2releuler(org, dst, seq="XYZ", degrees=True): + r0 = R.from_euler(seq, org, degrees=degrees).inv() + r1 = R.from_euler(seq, dst, degrees=degrees) + return (r1 * r0).as_euler(seq, degrees=degrees) diff --git a/source/Misc.hpp b/source/Misc.hpp index b12c3034..77d6b336 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -168,11 +168,11 @@ EqualRealNos(const real a1, const real a2) return std::abs(a1 - a2) <= fraction * tol; } - -inline vec3 +inline vec3 canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) { - // From issue #163: https://github.com/FloatingArrayDesign/MoorDyn/issues/163 + // From issue #163: + // https://github.com/FloatingArrayDesign/MoorDyn/issues/163 mat3 coeff = quat.normalized().toRotationMatrix(); vec3 res{}; using Index = int; @@ -190,9 +190,9 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // s2s3 -c2s1s3 + c1c3 -c2c1s3 - s1c3 // -s2c3 c2s1c3 + c1s3 c2c1c3 - s1s3 // Note: s2 is always positive. - Scalar s2 = Eigen::numext::hypot(coeff(i, j), coeff(i, k)); - if (!odd) { - res[0] = atan2(coeff(i, j), coeff(i, k)); + Scalar s2 = Eigen::numext::hypot(coeff(j, i), coeff(k, i)); + if (odd) { + res[0] = atan2(coeff(j, i), coeff(k, i)); // s2 is always positive, so res[1] will be within the canonical [0, // pi] range res[1] = atan2(s2, coeff(i, i)); @@ -211,7 +211,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // arguments to atan2, while the calculation of the third angle does // not need special adjustment since it uses the adjusted res[0] as // the input and produces a correct result. - res[0] = atan2(-coeff(i, j), -coeff(i, k)); + res[0] = atan2(-coeff(j, i), -coeff(k, i)); res[1] = -atan2(s2, coeff(i, i)); } // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first @@ -225,8 +225,8 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // Thus: m11.c1 - m21.s1 = c3 & m12.c1 - m22.s1 = s3 Scalar s1 = sin(res[0]); Scalar c1 = cos(res[0]); - res[2] = atan2(c1 * coeff(k, j) - s1 * coeff(k, k), - c1 * coeff(j, j) - s1 * coeff(j, k)); + res[2] = atan2(c1 * coeff(j, k) - s1 * coeff(k, k), + c1 * coeff(j, j) - s1 * coeff(k, j)); } else { // Tait-Bryan angles (all three axes are different; typically used for // yaw-pitch-roll calculations). The i, j, k indices enable addressing @@ -236,17 +236,17 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) // c2c3 s2s1c3 - c1s3 s2c1c3 + s1s3 // c2s3 s2s1s3 + c1c3 s2c1s3 - s1c3 // -s2 c2s1 c2c1 - res[0] = atan2(coeff(k, j), coeff(k, k)); - Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(j, i)); + res[0] = atan2(coeff(j, k), coeff(k, k)); + Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(i, j)); // c2 is always positive, so the following atan2 will always return a // result in the correct canonical middle angle range [-pi/2, pi/2] - res[1] = atan2(-coeff(k, i), c2); + res[1] = atan2(-coeff(i, k), c2); Scalar s1 = sin(res[0]); Scalar c1 = cos(res[0]); - res[2] = atan2(s1 * coeff(i, k) - c1 * coeff(i, j), - c1 * coeff(j, j) - s1 * coeff(j, k)); + res[2] = atan2(s1 * coeff(k, i) - c1 * coeff(j, i), + c1 * coeff(j, j) - s1 * coeff(k, j)); } - if (odd) { + if (!odd) { res = -res; } return res; @@ -255,7 +255,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) inline vec3 Quat2Euler(const quaternion& q) { - // 0, 1, 2 correspond to axes leading to XYZ rotation + // 0, 1, 2 correspond to axes leading to XYZ rotation return canonicalEulerAngles(q, 0, 1, 2); } @@ -263,9 +263,9 @@ inline quaternion Euler2Quat(const vec3& angles) { using AngleAxis = Eigen::AngleAxis; - quaternion q = AngleAxis(angles.z(), vec3::UnitZ()) * + quaternion q = AngleAxis(angles.x(), vec3::UnitX()) * AngleAxis(angles.y(), vec3::UnitY()) * - AngleAxis(angles.x(), vec3::UnitX()); + AngleAxis(angles.z(), vec3::UnitZ()); return q; } diff --git a/tests/test_rotations.py b/tests/test_rotations.py index 12c4a2ea..92e330b5 100644 --- a/tests/test_rotations.py +++ b/tests/test_rotations.py @@ -13,7 +13,7 @@ ANGLE = 5 -def rotate_vecs(vecs, angles, seq='xyz', degrees=True): +def rotate_vecs(vecs, angles, seq="XYZ", degrees=True): r = R.from_euler(seq, angles, degrees=degrees) return [r.apply(vec) for vec in vecs] @@ -26,7 +26,7 @@ def compare_vecs(vecs, refs, tol=1e-5): assert abs(vecs[i][j] - refs[i][j]) < 1e-5 -def abseuler2releuler(org, dst, seq='xyz', degrees=True): +def abseuler2releuler(org, dst, seq="XYZ", degrees=True): r0 = R.from_euler(seq, org, degrees=degrees).inv() r1 = R.from_euler(seq, dst, degrees=degrees) return (r1 * r0).as_euler(seq, degrees=degrees) @@ -66,19 +66,19 @@ def test_nwu(self): t = 0 # Roll test r, t = rotate_moordyn(system, ANGLE, 0, 0, t) - compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='x')) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='X')) assert(r[1][2] > 0.0) # Portside up, i.e. starboard down r, t = rotate_moordyn(system, -ANGLE, 0, 0, t) compare_vecs(r, ENUREF) # Pitch test r, t = rotate_moordyn(system, 0, ANGLE, 0, t) - compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='y')) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='Y')) assert(r[0][2] < 0.0) # Bow down r, t = rotate_moordyn(system, 0, -ANGLE, 0, t) compare_vecs(r, ENUREF) # Yaw test r, t = rotate_moordyn(system, 0, 0, ANGLE, t) - compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='z')) + compare_vecs(r, rotate_vecs(ENUREF, ANGLE, seq='Z')) assert(r[0][1] > 0.0) # Bow to portside r, t = rotate_moordyn(system, 0, 0, -ANGLE, t) compare_vecs(r, ENUREF) From fc2d9cfd9f36d697f4603221d1ee9e5c9da68209 Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Tue, 9 Jul 2024 07:11:11 +0200 Subject: [PATCH 124/145] docs: Clarify that intrinsic angles are considered, and link to the external resources --- docs/angles.svg | 203 ---------------------------------------------- docs/features.rst | 49 +++-------- 2 files changed, 11 insertions(+), 241 deletions(-) delete mode 100644 docs/angles.svg diff --git a/docs/angles.svg b/docs/angles.svg deleted file mode 100644 index 9a5fcd18..00000000 --- a/docs/angles.svg +++ /dev/null @@ -1,203 +0,0 @@ - - - - - - - - - - - - - xyz - - - - - - - - - - - - - - - - - - - - - diff --git a/docs/features.rst b/docs/features.rst index 2a4b038d..9deb43d4 100644 --- a/docs/features.rst +++ b/docs/features.rst @@ -29,44 +29,17 @@ The main difference between MoorDyn-C and MoorDyn-F is that MoorDyn-C uses quate 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 +MoorDyn-C, MoorDyn-F and `MoorPy `_ share the +same Intrinsic Euler-XYZ (Tait-Bryan) angles criteria to compute orientations. +You can learn more about this on +`Hall M. Generalized Quasi-Static Mooring System Modeling with Analytic Jacobians. Energies. 2024; 17(13):3155. https://doi.org/10.3390/en17133155 `_ + +However, while on MoorDyn-F this is handled by considering orientation +matrices, on MoorDyn-C quaternions are considered to describe the location and +orientation of 6 DOF 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 ---------- From 9992312a12f227d2906606f3e5032e6ebd4584db Mon Sep 17 00:00:00 2001 From: Jose Luis Cercos-Pita Date: Wed, 10 Jul 2024 06:42:57 +0200 Subject: [PATCH 125/145] fix: Drop the patch to move from extrinsic to intrinsic Euler angles --- instrinsic_angles.patch | 119 ---------------------------------------- 1 file changed, 119 deletions(-) delete mode 100644 instrinsic_angles.patch diff --git a/instrinsic_angles.patch b/instrinsic_angles.patch deleted file mode 100644 index c780b2e6..00000000 --- a/instrinsic_angles.patch +++ /dev/null @@ -1,119 +0,0 @@ -diff --git a/source/Misc.hpp b/source/Misc.hpp -index b12c303..77d6b33 100644 ---- a/source/Misc.hpp -+++ b/source/Misc.hpp -@@ -168,11 +168,11 @@ EqualRealNos(const real a1, const real a2) - return std::abs(a1 - a2) <= fraction * tol; - } - -- --inline vec3 -+inline vec3 - canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - { -- // From issue #163: https://github.com/FloatingArrayDesign/MoorDyn/issues/163 -+ // From issue #163: -+ // https://github.com/FloatingArrayDesign/MoorDyn/issues/163 - mat3 coeff = quat.normalized().toRotationMatrix(); - vec3 res{}; - using Index = int; -@@ -190,9 +190,9 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - // s2s3 -c2s1s3 + c1c3 -c2c1s3 - s1c3 - // -s2c3 c2s1c3 + c1s3 c2c1c3 - s1s3 - // Note: s2 is always positive. -- Scalar s2 = Eigen::numext::hypot(coeff(i, j), coeff(i, k)); -- if (!odd) { -- res[0] = atan2(coeff(i, j), coeff(i, k)); -+ Scalar s2 = Eigen::numext::hypot(coeff(j, i), coeff(k, i)); -+ if (odd) { -+ res[0] = atan2(coeff(j, i), coeff(k, i)); - // s2 is always positive, so res[1] will be within the canonical [0, - // pi] range - res[1] = atan2(s2, coeff(i, i)); -@@ -211,7 +211,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - // arguments to atan2, while the calculation of the third angle does - // not need special adjustment since it uses the adjusted res[0] as - // the input and produces a correct result. -- res[0] = atan2(-coeff(i, j), -coeff(i, k)); -+ res[0] = atan2(-coeff(j, i), -coeff(k, i)); - res[1] = -atan2(s2, coeff(i, i)); - } - // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first -@@ -225,8 +225,8 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - // Thus: m11.c1 - m21.s1 = c3 & m12.c1 - m22.s1 = s3 - Scalar s1 = sin(res[0]); - Scalar c1 = cos(res[0]); -- res[2] = atan2(c1 * coeff(k, j) - s1 * coeff(k, k), -- c1 * coeff(j, j) - s1 * coeff(j, k)); -+ res[2] = atan2(c1 * coeff(j, k) - s1 * coeff(k, k), -+ c1 * coeff(j, j) - s1 * coeff(k, j)); - } else { - // Tait-Bryan angles (all three axes are different; typically used for - // yaw-pitch-roll calculations). The i, j, k indices enable addressing -@@ -236,17 +236,17 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - // c2c3 s2s1c3 - c1s3 s2c1c3 + s1s3 - // c2s3 s2s1s3 + c1c3 s2c1s3 - s1c3 - // -s2 c2s1 c2c1 -- res[0] = atan2(coeff(k, j), coeff(k, k)); -- Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(j, i)); -+ res[0] = atan2(coeff(j, k), coeff(k, k)); -+ Scalar c2 = Eigen::numext::hypot(coeff(i, i), coeff(i, j)); - // c2 is always positive, so the following atan2 will always return a - // result in the correct canonical middle angle range [-pi/2, pi/2] -- res[1] = atan2(-coeff(k, i), c2); -+ res[1] = atan2(-coeff(i, k), c2); - Scalar s1 = sin(res[0]); - Scalar c1 = cos(res[0]); -- res[2] = atan2(s1 * coeff(i, k) - c1 * coeff(i, j), -- c1 * coeff(j, j) - s1 * coeff(j, k)); -+ res[2] = atan2(s1 * coeff(k, i) - c1 * coeff(j, i), -+ c1 * coeff(j, j) - s1 * coeff(k, j)); - } -- if (odd) { -+ if (!odd) { - res = -res; - } - return res; -@@ -255,7 +255,7 @@ canonicalEulerAngles(const quaternion& quat, int a0, int a1, int a2) - inline vec3 - Quat2Euler(const quaternion& q) - { -- // 0, 1, 2 correspond to axes leading to XYZ rotation -+ // 0, 1, 2 correspond to axes leading to XYZ rotation - return canonicalEulerAngles(q, 0, 1, 2); - } - -@@ -263,9 +263,9 @@ inline quaternion - Euler2Quat(const vec3& angles) - { - using AngleAxis = Eigen::AngleAxis; -- quaternion q = AngleAxis(angles.z(), vec3::UnitZ()) * -+ quaternion q = AngleAxis(angles.x(), vec3::UnitX()) * - AngleAxis(angles.y(), vec3::UnitY()) * -- AngleAxis(angles.x(), vec3::UnitX()); -+ AngleAxis(angles.z(), vec3::UnitZ()); - return q; - } - -diff --git a/tests/test_rotations.py b/tests/test_rotations.py -index 12c4a2e..dfa4a6a 100644 ---- a/tests/test_rotations.py -+++ b/tests/test_rotations.py -@@ -13,7 +13,7 @@ ENUREF = [[1, 0, 0], - ANGLE = 5 - - --def rotate_vecs(vecs, angles, seq='xyz', degrees=True): -+def rotate_vecs(vecs, angles, seq="XYZ", degrees=True): - r = R.from_euler(seq, angles, degrees=degrees) - return [r.apply(vec) for vec in vecs] - -@@ -26,7 +26,7 @@ def compare_vecs(vecs, refs, tol=1e-5): - assert abs(vecs[i][j] - refs[i][j]) < 1e-5 - - --def abseuler2releuler(org, dst, seq='xyz', degrees=True): -+def abseuler2releuler(org, dst, seq="XYZ", degrees=True): - r0 = R.from_euler(seq, org, degrees=degrees).inv() - r1 = R.from_euler(seq, dst, degrees=degrees) - return (r1 * r0).as_euler(seq, degrees=degrees) From 5eb1d48fc15fd8d539bdfbc416773b7c617fb0f5 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 26 Jul 2024 16:04:22 -0600 Subject: [PATCH 126/145] fix: make rod submergence calcs match what is in MDF (verified code) --- source/Rod.cpp | 35 ++++++++++++----------------------- source/Rod.hpp | 2 +- 2 files changed, 13 insertions(+), 24 deletions(-) diff --git a/source/Rod.cpp b/source/Rod.cpp index 06c0c04f..7942537b 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -917,29 +917,17 @@ Rod::doRHS() // just use the wave elevation computed at the location of the top node for // now - vec r_top, r_bottom; - real zeta_i; - if (r[N][2] > r[0][2]) { - r_top = r[N]; - r_bottom = r[0]; - zeta_i = zeta[N]; - } else { - r_top = r[0]; - r_bottom = r[N]; - zeta_i = zeta[0]; - } - - if ((r_bottom[2] < zeta_i) && (r_top[2] > zeta_i)) { - // the water plane is crossing the rod - // (should also add some limits to avoid near-horizontals at some point) - h0 = (zeta_i - r_bottom[2]) / fabs(q[2]); - } else if (r[0][2] < zeta_i) { - // fully submerged case - h0 = UnstrLen; - } else { - // fully unsubmerged case (ever applicable?) - h0 = 0.0; - } + real zeta_i = zeta[N]; + + // get approximate location of waterline crossing along Rod axis (note: negative h0 indicates end A is above end B, and measures -distance from end A to waterline crossing) + if ((r[0][2] < zeta_i) && (r[N][2] < zeta_i)) // fully submerged case + h0 = UnstrLen; + else if ((r[0][2] < zeta_i) && (r[N][2] > zeta_i)) // check if it's crossing the water plane (should also add some limits to avoid near-horizontals at some point) + h0 = (zeta_i - r[0][2])/q[2]; // distance along rod centerline from end A to the waterplane + else if ((r[N][2] < zeta_i) && (r[0][2] > zeta_i)) // check if it's crossing the water plane but upside down + h0 = -(zeta_i - r[0][2])/q[2]; // negative distance along rod centerline from end A to the waterplane + else + h0 = 0.0; // fully unsubmerged case (ever applicable?) Mext = vec::Zero(); @@ -1165,6 +1153,7 @@ Rod::doRHS() M[i] += VOF[i] * env->rho_w * CaEnd * V_temp * Q; } + // end B if ((i == N) && (z1lo < zeta_i)) { // buoyancy force Ftemp = VOF[i] * Area * env->rho_w * env->g * zA; diff --git a/source/Rod.hpp b/source/Rod.hpp index 0107914c..720c00b6 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -192,7 +192,7 @@ class Rod final : public io::IO, public SuperCFL // wave things /// VOF scalar for each segment (1 = fully submerged, 0 = out of water) - std::vector VOF; + std::vector VOF; // TODO: This doesnt need to be a vector, can be a double reused for each node /// instantaneous axial submerged length [m] real h0; From d40897bf2a8480a20a169329e774186208d51ebd Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 26 Jul 2024 16:04:22 -0600 Subject: [PATCH 127/145] fix: make rod submergence calcs match what is in MDF (verified code) --- source/Rod.cpp | 35 ++++++++++++----------------------- source/Rod.hpp | 2 +- 2 files changed, 13 insertions(+), 24 deletions(-) diff --git a/source/Rod.cpp b/source/Rod.cpp index 06c0c04f..7942537b 100644 --- a/source/Rod.cpp +++ b/source/Rod.cpp @@ -917,29 +917,17 @@ Rod::doRHS() // just use the wave elevation computed at the location of the top node for // now - vec r_top, r_bottom; - real zeta_i; - if (r[N][2] > r[0][2]) { - r_top = r[N]; - r_bottom = r[0]; - zeta_i = zeta[N]; - } else { - r_top = r[0]; - r_bottom = r[N]; - zeta_i = zeta[0]; - } - - if ((r_bottom[2] < zeta_i) && (r_top[2] > zeta_i)) { - // the water plane is crossing the rod - // (should also add some limits to avoid near-horizontals at some point) - h0 = (zeta_i - r_bottom[2]) / fabs(q[2]); - } else if (r[0][2] < zeta_i) { - // fully submerged case - h0 = UnstrLen; - } else { - // fully unsubmerged case (ever applicable?) - h0 = 0.0; - } + real zeta_i = zeta[N]; + + // get approximate location of waterline crossing along Rod axis (note: negative h0 indicates end A is above end B, and measures -distance from end A to waterline crossing) + if ((r[0][2] < zeta_i) && (r[N][2] < zeta_i)) // fully submerged case + h0 = UnstrLen; + else if ((r[0][2] < zeta_i) && (r[N][2] > zeta_i)) // check if it's crossing the water plane (should also add some limits to avoid near-horizontals at some point) + h0 = (zeta_i - r[0][2])/q[2]; // distance along rod centerline from end A to the waterplane + else if ((r[N][2] < zeta_i) && (r[0][2] > zeta_i)) // check if it's crossing the water plane but upside down + h0 = -(zeta_i - r[0][2])/q[2]; // negative distance along rod centerline from end A to the waterplane + else + h0 = 0.0; // fully unsubmerged case (ever applicable?) Mext = vec::Zero(); @@ -1165,6 +1153,7 @@ Rod::doRHS() M[i] += VOF[i] * env->rho_w * CaEnd * V_temp * Q; } + // end B if ((i == N) && (z1lo < zeta_i)) { // buoyancy force Ftemp = VOF[i] * Area * env->rho_w * env->g * zA; diff --git a/source/Rod.hpp b/source/Rod.hpp index 0107914c..720c00b6 100644 --- a/source/Rod.hpp +++ b/source/Rod.hpp @@ -192,7 +192,7 @@ class Rod final : public io::IO, public SuperCFL // wave things /// VOF scalar for each segment (1 = fully submerged, 0 = out of water) - std::vector VOF; + std::vector VOF; // TODO: This doesnt need to be a vector, can be a double reused for each node /// instantaneous axial submerged length [m] real h0; From 2acbfcfd99648b2f364f67f3b84abefc32623ff6 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 2 Oct 2024 17:58:42 -0600 Subject: [PATCH 128/145] Updated consol printing for water kin, fixed lift force --- source/Line.cpp | 9 +++- source/MoorDyn2.cpp | 2 + source/Waves.cpp | 84 ++++++++++++++++---------------- source/Waves/WaveGrid.cpp | 92 +++++++++++++++++------------------ source/Waves/WaveSpectrum.cpp | 12 ++--- 5 files changed, 104 insertions(+), 95 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index db6e9092..7a31b24d 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1238,7 +1238,14 @@ Line::getStateDeriv() // VIVd[i][1] = A_int_dot; // VIVd[i][2] = As_dot; - Lf[i] = 0.5 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp); + // The Lift force + if (i == 0) + Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i]); + else if (i == N) + Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i - 1] * l[i - 1]); + else + Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i] + F[i - 1] * l[i - 1]); + if ((t >= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. yd_old[i] = yd; // for updating rms back indexing (one moordyn timestep back) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 20244eb2..4a1fe877 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -554,6 +554,7 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) if (seafloor) { env->WtrDpth = -seafloor->getAverageDepth(); } + LOGMSG << "Water kinematics for runtime:" << endl; waves->setup(env, seafloor, _t_integrator, _basepath.c_str()); env->WtrDpth = tmp; } @@ -1645,6 +1646,7 @@ moordyn::MoorDyn::ReadInFile() if (seafloor) { env->WtrDpth = -seafloor->getAverageDepth(); } + LOGMSG << "Water kinematics for IC gen:" << endl; waves->setup(env, seafloor, _t_integrator, _basepath.c_str()); env->WtrDpth = tmp; } diff --git a/source/Waves.cpp b/source/Waves.cpp index e7623454..8bc08289 100644 --- a/source/Waves.cpp +++ b/source/Waves.cpp @@ -278,97 +278,97 @@ Waves::setup(EnvCondRef env_in, auto current_mode = env->waterKinOptions.currentMode; if ((wave_mode == moordyn::WAVES_NONE) && (current_mode == moordyn::CURRENTS_NONE)) { - LOGMSG << "No Waves or Currents, or set externally" << endl; + LOGMSG << " No Waves or Currents, or set externally" << endl; return; } if (wave_mode == waves::WAVES_NONE) { if (current_mode == waves::CURRENTS_STEADY_GRID) - LOGDBG << "Current only: option 1 - " - << "read in steady current profile, grid approach " - << "(current_profile.txt)" << endl; + LOGDBG << " Current only: option 1 - " + << " read in steady current profile, grid approach " + << " (current_profile.txt)" << endl; else if (current_mode == waves::CURRENTS_DYNAMIC_GRID) - LOGDBG << "Current only: option 2 - " - << "read in dynamic current profile, grid approach " - << "(current_profile_dynamic.txt)" << endl; + LOGDBG << " Current only: option 2 - " + << " read in dynamic current profile, grid approach " + << " (current_profile_dynamic.txt)" << endl; else if (current_mode == waves::CURRENTS_STEADY_NODE) - LOGDBG << "Current only: option TBD3 - " - << "read in steady current profile, node approach " - << "(current_profile.txt)" << endl; + LOGDBG << " Current only: option TBD3 - " + << " read in steady current profile, node approach " + << " (current_profile.txt)" << endl; else if (current_mode == waves::CURRENTS_DYNAMIC_NODE) - LOGDBG << "Current only: option TBD4 - " - << "read in dynamic current profile, node approach " - << "(current_profile_dynamic.txt)" << endl; + LOGDBG << " Current only: option TBD4 - " + << " read in dynamic current profile, node approach " + << " (current_profile_dynamic.txt)" << endl; else if (current_mode == waves::CURRENTS_4D) - LOGDBG << "Current only: option 4D - read in current profile, grid " - << "approach (current_profile_4d.txt" << endl; + LOGDBG << " Current only: option 4D - read in current profile, grid " + << " approach (current_profile_4d.txt" << endl; else { - LOGDBG << "Invald current input settings (must be 0-4)" << endl; + LOGDBG << " Invalid current input settings (must be 0-4)" << endl; throw moordyn::invalid_value_error("Invalid settings"); } } else if (current_mode == waves::CURRENTS_NONE) { if (wave_mode == waves::WAVES_EXTERNAL) - LOGDBG << "Waves only: option 1 - " - << "set externally for each node in each object" << endl; + LOGDBG << " Waves only: option 1 - " + << " set externally for each node in each object" << endl; else if (wave_mode == waves::WAVES_FFT_GRID) - LOGDBG << "Waves only: option 2 - " - << "set from inputted wave elevation FFT, grid approach " - << "(NOT IMPLEMENTED YET)" << endl; + LOGDBG << " Waves only: option 2 - " + << " set from inputted wave elevation FFT, grid approach " + << " (NOT IMPLEMENTED YET)" << endl; else if (wave_mode == waves::WAVES_GRID) LOGDBG - << "Waves only: option 3 - " - << "set from inputted wave elevation time series, grid approach" + << " Waves only: option 3 - " + << " set from inputted wave elevation time series, grid approach" << endl; else if (wave_mode == waves::WAVES_FFT_GRID) - LOGDBG << "Waves only: option TBD4 - " - << "set from inputted wave elevation FFT, node approach " - << "(NOT IMPLEMENTED YET)" << endl; + LOGDBG << " Waves only: option TBD4 - " + << " set from inputted wave elevation FFT, node approach " + << " (NOT IMPLEMENTED YET)" << endl; else if (wave_mode == waves::WAVES_NODE) LOGDBG - << "Waves only: option TBD5 - " - << "set from inputted wave elevation time series, node approach" + << " Waves only: option TBD5 - " + << " set from inputted wave elevation time series, node approach" << endl; else if (wave_mode == waves::WAVES_KIN) - LOGDBG << "Waves only: option TBD6 - " - << "set from inputted velocity, acceleration, and wave " - "elevation grid data (TBD)" + LOGDBG << " Waves only: option TBD6 - " + << " set from inputted velocity, acceleration, and wave " + " elevation grid data (TBD)" << endl; else if (wave_mode == waves::WAVES_SUM_COMPONENTS_NODE) - LOGDBG << "Waves only: option 7 - " - << "set from inputted wave spectrum, computed at nodes on " - "update " + LOGDBG << " Waves only: option 7 - " + << " set from inputted wave spectrum, computed at nodes on " + " update " << endl; else { - LOGDBG << "Invald wave kinematics input settings (must be 0-7)" + LOGDBG << " Invald wave kinematics input settings (must be 0-7)" << endl; throw moordyn::invalid_value_error("Invalid settings"); } } else if (wave_mode == waves::WAVES_EXTERNAL && current_mode != waves::CURRENTS_NONE) { - LOGDBG << "External waves as well as currents, current options: " + LOGDBG << " External waves as well as currents, current options: " << current_mode << endl; } else if (waves::is_waves_grid(wave_mode) && waves::is_currents_grid(current_mode)) { - LOGDBG << "Waves and currents: options " << wave_mode << " & " + LOGDBG << " Waves and currents: options " << wave_mode << " & " << current_mode << endl; } else if (waves::is_waves_node(wave_mode) && waves::is_currents_node(current_mode)) { - LOGDBG << "Waves and currents: options TBD " << wave_mode << " & " + LOGDBG << " Waves and currents: options TBD " << wave_mode << " & " << current_mode << endl; } // NOTE: nodal settings should use storeWaterKin in objects // now go through each applicable WaveKin option if (wave_mode == waves::WAVES_SUM_COMPONENTS_NODE) { - const string WaveFilename = (string)folder + "/wave_frequencies.txt"; - LOGMSG << "Reading waves spectrum frequencies from '" << WaveFilename + const string WaveFilename = (string)folder + "wave_frequencies.txt"; + LOGMSG << " Reading waves spectrum frequencies from '" << WaveFilename << "'..." << endl; auto waveSpectrum = spectrumFromFile(WaveFilename, _log); - LOGMSG << "'" << WaveFilename << "' parsed" << endl; + LOGMSG << " '" << WaveFilename << "' parsed" << endl; if (waveSpectrum[0].omega != 0.0) { - LOGERR << "The first shall be 0 rad/s" << endl; + LOGERR << " The first shall be 0 rad/s" << endl; throw moordyn::invalid_value_error("Invalid frequencies"); } SpectrumKin spectrumKin{}; diff --git a/source/Waves/WaveGrid.cpp b/source/Waves/WaveGrid.cpp index 19eec0b5..b826d70d 100644 --- a/source/Waves/WaveGrid.cpp +++ b/source/Waves/WaveGrid.cpp @@ -102,7 +102,7 @@ fillWaveGrid(std::unique_ptr waveGrid, // This computes the time distance between samples returned by the ifft // We entirely ignore the env->dtWave value in this case for now waveGrid->dtWave = ((2 * pi) / dw) / nt; - LOGMSG << "in new fillWaveGrid, setting waveGrid->dtWave to be " + LOGMSG << " in new fillWaveGrid, setting waveGrid->dtWave to be " << waveGrid->dtWave << endl; auto h = env->WtrDpth; auto g = env->g; @@ -112,13 +112,13 @@ fillWaveGrid(std::unique_ptr waveGrid, for (unsigned int i = 0; i < nw; i++) w[i] = (real)i * dw; - LOGMSG << "Wave frequencies from " << w[0] << " rad/s to " << w[nw - 1] + LOGMSG << " Wave frequencies from " << w[0] << " rad/s to " << w[nw - 1] << " rad/s in increments of " << dw << " rad/s" << endl; - LOGDBG << "Wave numbers in rad/m are "; + LOGDBG << " Wave numbers in rad/m are "; for (unsigned int I = 0; I < nw; I++) { k[I] = WaveNumber(w[I], env->g, h); - LOGDBG << k[I] << ", "; + LOGDBG << " " << k[I] << ", "; } LOGDBG << endl; @@ -126,7 +126,7 @@ fillWaveGrid(std::unique_ptr waveGrid, // precalculates wave kinematics for a given set of node points for a series // of time steps - LOGDBG << "Making wave Kinematics (iFFT)..." << endl; + LOGDBG << " Making wave Kinematics (iFFT)..." << endl; // start the FFT stuff using kiss_fft unsigned int nFFT = nt; @@ -269,7 +269,7 @@ fillWaveGrid(std::unique_ptr waveGrid, free(cfg); - LOGDBG << "Done!" << endl; + LOGDBG << " Done!" << endl; return waveGrid; } @@ -294,7 +294,7 @@ std::array, 3> rectilinearGridFromFile(std::filesystem::path filepath, moordyn::Log* _log) { - LOGMSG << "Reading waves coordinates grid from '" << filepath << "'..." + LOGMSG << " Reading waves coordinates grid from '" << filepath << "'..." << endl; // --------------------- read grid data from file ------------------------ @@ -304,7 +304,7 @@ rectilinearGridFromFile(std::filesystem::path filepath, moordyn::Log* _log) lines = moordyn::fileIO::fileToLines(filepath); if (lines.size() < 9) { - LOGERR << "The waves grid file '" << filepath << "' has only " + LOGERR << " The waves grid file '" << filepath << "' has only " << lines.size() << "lines, but at least 9 are required" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -317,7 +317,7 @@ rectilinearGridFromFile(std::filesystem::path filepath, moordyn::Log* _log) entries = moordyn::str::split(lines[4]); auto px = gridAxisCoords(coordtype, entries); if (px.empty()) { - LOGERR << "Invalid entry for the grid x values in file '" << filepath + LOGERR << " Invalid entry for the grid x values in file '" << filepath << "'" << endl; throw moordyn::invalid_value_error("Invalid line"); } @@ -327,7 +327,7 @@ rectilinearGridFromFile(std::filesystem::path filepath, moordyn::Log* _log) entries = moordyn::str::split(lines[6]); auto py = gridAxisCoords(coordtype, entries); if (py.empty()) { - LOGERR << "Invalid entry for the grid y values in file '" << filepath + LOGERR << " Invalid entry for the grid y values in file '" << filepath << "'" << endl; throw moordyn::invalid_value_error("Invalid line"); } @@ -337,15 +337,15 @@ rectilinearGridFromFile(std::filesystem::path filepath, moordyn::Log* _log) entries = moordyn::str::split(lines[8]); auto pz = gridAxisCoords(coordtype, entries); if (pz.empty()) { - LOGERR << "Invalid entry for the grid z values in file '" << filepath + LOGERR << " Invalid entry for the grid z values in file '" << filepath << "'" << endl; throw moordyn::invalid_value_error("Invalid line"); } - LOGDBG << "Setup the waves grid with " << px.size() << " x " << py.size() + LOGDBG << " Setup the waves grid with " << px.size() << " x " << py.size() << " x " << pz.size() << " points " << endl; - LOGMSG << "'" << filepath << "' parsed" << endl; + LOGMSG << " '" << filepath << "' parsed" << endl; return { px, py, pz }; } @@ -356,25 +356,25 @@ constructWaveGridSpectrumData(const std::string& folder, moordyn::Log* _log) { - const string WaveFilename = folder + "/wave_frequencies.txt"; - LOGMSG << "Reading waves FFT from '" << WaveFilename << "'..." << endl; - + const string WaveFilename = folder + "wave_frequencies.txt"; + LOGMSG << " Reading waves FFT from '" << WaveFilename << "'..." << endl; + // NOTE: need to decide what inputs/format to expect in file // (1vs2-sided spectrum?) waves::DiscreteWaveSpectrum spectrum = spectrumFromFile(WaveFilename, _log); - LOGMSG << "'" << WaveFilename << "' parsed" << endl; + LOGMSG << " '" << WaveFilename << "' parsed" << endl; if (spectrum[0].omega != 0.0) { - LOGERR << "The first shall be 0 rad/s" << endl; + LOGERR << " The first shall be 0 rad/s" << endl; throw moordyn::invalid_value_error("Invalid frequencies"); } const vector evenFreqComps = spectrum.interpEvenlySpaced(); - // LOGMSG << "Frequency Spectrum: \n"; + // LOGMSG << " Frequency Spectrum: \n"; // for(auto& freqComp : evenFreqComps) { - // LOGMSG << "freq(" << freqComp.omega << ") = " << freqComp.amplitude + // LOGMSG << " freq(" << freqComp.omega << ") = " << freqComp.amplitude // << endl; // } vector zetaC0(evenFreqComps.size()); @@ -391,7 +391,7 @@ constructWaveGridSpectrumData(const std::string& folder, auto nt = static_cast(2 * (evenFreqComps.size() - 1)); auto [px, py, pz] = - rectilinearGridFromFile(folder + "/water_grid.txt", _log); + rectilinearGridFromFile(folder + "water_grid.txt", _log); auto waveGrid = make_unique( _log, px, py, pz, nt, env->waterKinOptions.dtWave); @@ -414,15 +414,15 @@ constructWaveGridElevationData(const std::string& folder, // load wave elevation time series from file (similar to what's done in // GenerateWaveExtnFile.py, and was previously in misc2.cpp) - const string WaveFilename = folder + "/wave_elevation.txt"; - LOGMSG << "Reading waves elevation from '" << WaveFilename << "'..." + const string WaveFilename = folder + "wave_elevation.txt"; + LOGMSG << " Reading waves elevation from '" << WaveFilename << "'..." << endl; vector lines; try { lines = moordyn::fileIO::fileToLines(WaveFilename); } catch (moordyn::input_file_error& err) { - LOGERR << "Cannot read the file '" << WaveFilename << "'" << endl; + LOGERR << " Cannot read the file '" << WaveFilename << "'" << endl; std::stringstream ss; ss << "Waves::setup failed to read wave_elevation.txt file: " << err.what(); @@ -438,14 +438,14 @@ constructWaveGridElevationData(const std::string& folder, for (auto line : lines) { vector entries = moordyn::str::split(line); if (entries.size() < 2) { - LOGERR << "The file '" << WaveFilename << "' should have 2 columns" + LOGERR << " The file '" << WaveFilename << "' should have 2 columns" << endl; throw moordyn::input_file_error("Invalid file format"); } wavetimes.push_back(stod(entries[0])); waveelevs.push_back(stod(entries[1])); } - LOGMSG << "'" << WaveFilename << "' parsed" << endl; + LOGMSG << " '" << WaveFilename << "' parsed" << endl; auto dtWave = env->waterKinOptions.dtWave; // downsample to dtWave @@ -453,7 +453,7 @@ constructWaveGridElevationData(const std::string& folder, // samples the 1 extra is for the point at zero, [0.0, 1.0, 2.0] is 3 // points even though 2.0/1.0 = 2 unsigned int nt = floor(wavetimes.back() / dtWave) + 1; - LOGDBG << "Number of wave time samples = " << nt << "(" << wavetimes.size() + LOGDBG << " Number of wave time samples = " << nt << "(" << wavetimes.size() << " samples provided in the file)" << endl; vector waveTime(nt, 0.0); @@ -475,7 +475,7 @@ constructWaveGridElevationData(const std::string& folder, } // FFT the wave elevation using kiss_fftr - LOGDBG << "Computing FFT..." << endl; + LOGDBG << " Computing FFT..." << endl; unsigned int nFFT = nt; const int is_inverse_fft = 0; // number of FFT frequencies (Nyquist) @@ -510,7 +510,7 @@ constructWaveGridElevationData(const std::string& folder, // perform the real-valued FFT kiss_fftr(cfg, cx_t_in.data(), cx_w_out.data()); - LOGDBG << "Done!" << endl; + LOGDBG << " Done!" << endl; free(cfg); // copy frequencies over from FFT output @@ -529,7 +529,7 @@ constructWaveGridElevationData(const std::string& folder, // make a grid for wave kinematics based on settings in // water_grid.txt auto [px, py, pz] = - rectilinearGridFromFile(folder + "/water_grid.txt", _log); + rectilinearGridFromFile(folder + "water_grid.txt", _log); waveGrid = make_unique(_log, px, py, pz, nt, dtWave); waveGrid->allocateKinematicArrays(); @@ -546,7 +546,7 @@ constructSteadyCurrentGrid(const std::string& folder, { const string CurrentsFilename = folder + "current_profile.txt"; - LOGMSG << "Reading currents profile from '" << CurrentsFilename << "'..." + LOGMSG << " Reading currents profile from '" << CurrentsFilename << "'..." << endl; vector lines; @@ -555,7 +555,7 @@ constructSteadyCurrentGrid(const std::string& folder, try { lines = moordyn::fileIO::fileToLines(CurrentsFilename); } catch (moordyn::input_file_error& err) { - LOGERR << "Cannot read the file '" << CurrentsFilename << "'" << endl; + LOGERR << " Cannot read the file '" << CurrentsFilename << "'" << endl; std::stringstream ss; ss << "constructSteadyCurrentGrid failed to read currents_profile.txt " "file: " @@ -564,7 +564,7 @@ constructSteadyCurrentGrid(const std::string& folder, } if (lines.size() < 4) { - LOGERR << "The file '" << CurrentsFilename + LOGERR << " The file '" << CurrentsFilename << "' should have at least 4 lines" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -577,7 +577,7 @@ constructSteadyCurrentGrid(const std::string& folder, for (unsigned int i = 3; i < lines.size(); i++) { vector entries = moordyn::str::split(lines[i]); if (entries.size() < 2) { - LOGERR << "The file '" << CurrentsFilename + LOGERR << " The file '" << CurrentsFilename << "' should have at least 2 columns" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -594,7 +594,7 @@ constructSteadyCurrentGrid(const std::string& folder, else UProfileUz.push_back(0.0); } - LOGMSG << "'" << CurrentsFilename << "' parsed" << endl; + LOGMSG << " '" << CurrentsFilename << "' parsed" << endl; // NOTE: check data @@ -623,7 +623,7 @@ constructDynamicCurrentGrid(const std::string& folder, { const string CurrentsFilename = folder + "/current_profile_dynamic.txt"; - LOGMSG << "Reading currents dynamic profile from '" << CurrentsFilename + LOGMSG << " Reading currents dynamic profile from '" << CurrentsFilename << "'..." << endl; vector lines; @@ -631,16 +631,16 @@ constructDynamicCurrentGrid(const std::string& folder, try { lines = moordyn::fileIO::fileToLines(CurrentsFilename); } catch (moordyn::input_file_error& err) { - LOGERR << "Cannot read the file '" << CurrentsFilename << "'" << endl; + LOGERR << " Cannot read the file '" << CurrentsFilename << "'" << endl; std::stringstream ss; - ss << "Waves::setup failed to read currents_profile_dynamic.txt " + ss << " Waves::setup failed to read currents_profile_dynamic.txt " "file: " << err.what(); throw input_file_error(ss.str().c_str()); } if (lines.size() < 7) { - LOGERR << "The file '" << CurrentsFilename + LOGERR << " The file '" << CurrentsFilename << "' should have at least 7 lines" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -666,7 +666,7 @@ constructDynamicCurrentGrid(const std::string& folder, entries = moordyn::str::split(lines[i]); const unsigned int it = i - 6; if (entries.size() <= nzin) { - LOGERR << "The file '" << CurrentsFilename + LOGERR << " The file '" << CurrentsFilename << "' should have at least " << nzin + 1 << " columns" << endl; throw moordyn::input_file_error("Invalid file format"); @@ -689,7 +689,7 @@ constructDynamicCurrentGrid(const std::string& folder, for (unsigned int iz = 0; iz < nzin; iz++) UProfileUz[iz][it] = 0.0; } - LOGMSG << "'" << CurrentsFilename << "' parsed" << endl; + LOGMSG << " '" << CurrentsFilename << "' parsed" << endl; // A grid hasn't been set up yet, make it based on the read-in z // values @@ -738,7 +738,7 @@ construct4DCurrentGrid(const std::string& folder, { const string CurrentsFilename = folder + "current_profile_4d.txt"; - LOGMSG << "Reading 4d currents dynamic profile from '" << CurrentsFilename + LOGMSG << " Reading 4d currents dynamic profile from '" << CurrentsFilename << "'..." << endl; vector lines; @@ -746,9 +746,9 @@ construct4DCurrentGrid(const std::string& folder, try { lines = moordyn::fileIO::fileToLines(CurrentsFilename); } catch (moordyn::input_file_error& err) { - LOGERR << "Cannot read the file '" << CurrentsFilename << "'" << endl; + LOGERR << " Cannot read the file '" << CurrentsFilename << "'" << endl; std::stringstream ss; - ss << "Waves::setup failed to read currents_profile_4d.txt " + ss << " Waves::setup failed to read currents_profile_4d.txt " "file: " << err.what(); throw input_file_error(ss.str().c_str()); @@ -757,7 +757,7 @@ construct4DCurrentGrid(const std::string& folder, // A better check here is that the grid is at least as large as the // waves grid, i.e. nxin * nyin * nzin * ntin >= size of waves if (lines.size() < 7) { // TODO: Remove this check? Depends on final format - LOGERR << "The file '" << CurrentsFilename + LOGERR << " The file '" << CurrentsFilename << "' should have at least 7 lines" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -821,7 +821,7 @@ construct4DCurrentGrid(const std::string& folder, // Need to ensure that there is an entry for each gridpoint: if (lines.size() < nCurGridPoints + 5) { - LOGERR << "The file'" << CurrentsFilename + LOGERR << " The file'" << CurrentsFilename << "' should have a line for each gridpoint\n"; throw moordyn::input_file_error("Invalid file format\n"); } diff --git a/source/Waves/WaveSpectrum.cpp b/source/Waves/WaveSpectrum.cpp index 1245284d..172e7575 100644 --- a/source/Waves/WaveSpectrum.cpp +++ b/source/Waves/WaveSpectrum.cpp @@ -72,20 +72,20 @@ DiscreteWaveSpectrum::interpEvenlySpaced() moordyn::waves::DiscreteWaveSpectrum spectrumFromFile(const std::string& path, moordyn::Log* _log) { - LOGMSG << "reading spectrum from file: " << std::filesystem::absolute(path) + LOGMSG << " reading spectrum from file: " << std::filesystem::absolute(path) << endl; vector lines; try { lines = moordyn::fileIO::fileToLines(path); } catch (moordyn::input_file_error& err) { std::stringstream ss; - ss << "Waves::setup failed to read wave_frequencies file: " + ss << " Waves::setup failed to read wave_frequencies file: " << err.what(); throw input_file_error(ss.str().c_str()); } if (lines.size() < 2) { - LOGERR << "At least 2 frequency components shall be provided in '" + LOGERR << " At least 2 frequency components shall be provided in '" << path << "'" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -97,7 +97,7 @@ spectrumFromFile(const std::string& path, moordyn::Log* _log) for (auto line : lines) { vector entries = moordyn::str::split(line); if (entries.size() < 3) { - LOGERR << "The file '" << path << "' should have 3 or 4 columns" + LOGERR << " The file '" << path << "' should have 3 or 4 columns" << endl; throw moordyn::input_file_error("Invalid file format"); } @@ -108,7 +108,7 @@ spectrumFromFile(const std::string& path, moordyn::Log* _log) real i = stod(entries[2]); real beta = entries.size() == 4 ? stod(entries[3]) : 0.0; if (beta > 2 * pi || beta < -2 * pi) { - LOGERR << "Cannot specify a wave frequency with a direction of " + LOGERR << " Cannot specify a wave frequency with a direction of " "great than 2pi or less than -2pi. The value should " "be in radians." << endl; @@ -118,7 +118,7 @@ spectrumFromFile(const std::string& path, moordyn::Log* _log) spectrum.addFreqComp(freq, r, i, beta); // waveelevs.push_back(r + i1 * i); } catch (std::exception& e) { - LOGERR << "Tried to parse the line \"" << line + LOGERR << " Tried to parse the line \"" << line << "\" as 3 floats, but failed:" << e.what() << endl; throw moordyn::input_file_error("Invalid file format"); } From 23a48c26171cfd30e2a318afeb632d3626cd983d Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Thu, 17 Oct 2024 14:29:05 -0600 Subject: [PATCH 129/145] feat: Cleaned up the hack-ish state to generalize it for visco stuff. Made # a comment character in input files. Readded diable VIV during ICgen --- docs/inputs.rst | 2 ++ source/Line.cpp | 51 +++++++++++++++++------------------ source/Line.hpp | 8 +++--- source/Misc.cpp | 7 +++-- source/MoorDyn2.cpp | 9 +++++++ source/State.cpp | 66 ++++++++++++++++++++++----------------------- source/State.hpp | 8 +++--- source/Time.cpp | 4 +-- source/Time.hpp | 18 ++++++------- 9 files changed, 93 insertions(+), 80 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 017b54bf..aa8237c6 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -483,6 +483,8 @@ outputs are wanted. Eight output properties are currently possible: - D – hydrodynamic drag force at each node - t – tension force at each segment - c – internal damping force at each segment + - V - the cross-flow VIV lift force at each node + - K - the curvature at each node - s – strain of each segment - d – rate of strain of each segment diff --git a/source/Line.cpp b/source/Line.cpp index 7a31b24d..fb532e61 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -201,8 +201,8 @@ Line::setup(int number_in, r.assign(N + 1, vec::Zero()); // node positions [i][x/y/z] rd.assign(N + 1, vec::Zero()); // node velocities [i][x/y/z] rdd_old.assign(N + 1, vec::Zero()); // node accelerations previous timestep [i][x/y/z] - VIV.assign(N+1, vec::Zero()); // node viv states [i][phase/amplitude/smoothed amplitude] - VIVd.assign(N+1, vec::Zero()); // node viv state derivatives [i][phase/amplitude/smoothed amplitude] + Misc.assign(N+1, vec::Zero()); // node misc states [i][viv phase/viscoelastic/unused] + Miscd.assign(N+1, vec::Zero()); // node misc state derivatives [i][viv phase/viscoelastic/unused] q.assign(N + 1, vec::Zero()); // unit tangent vectors for each node pvec.assign(N + 1, vec::Zero()); // unit normal vectors for each node qs.assign(N, vec::Zero()); // unit tangent vectors for each segment @@ -566,18 +566,18 @@ Line::initialize() // initial state vector! (velocities leave at 0) std::vector vel(N - 1, vec::Zero()); // inital viv state vector (phase,amplitude,smoothed amplitude) - std::vector viv(N+1, vec::Zero()); + std::vector misc(N+1, vec::Zero()); /// give a random distribution between 0 and 2pi for inital phase of lift force to avoid initial transient if (Cl > 0.0) { std::vector phase_range(N+1); for (unsigned int i = 0; i < N+1; i++) phase_range[i] = (i/moordyn::real(N))*2*pi; shuffle(phase_range.begin(),phase_range.end(),random_device()); - for (unsigned int i = 0; i < N+1; i++) viv[i][0] = phase_range[i]; + for (unsigned int i = 0; i < N+1; i++) misc[i][0] = phase_range[i]; } LOGMSG << "Initialized Line " << number << endl; - return std::make_tuple(vector_slice(r, 1, N - 1), vel, viv); + return std::make_tuple(vector_slice(r, 1, N - 1), vel, misc); }; real @@ -710,20 +710,20 @@ Line::setPin(std::vector p) } void -Line::setState(std::vector pos, std::vector vel, std::vector viv) +Line::setState(std::vector pos, std::vector vel, std::vector misc) { - if ((pos.size() != N - 1) || (vel.size() != N - 1) || (viv.size() != N + 1)) { + if ((pos.size() != N - 1) || (vel.size() != N - 1) || (misc.size() != N + 1)) { LOGERR << "Invalid input size" << endl; throw moordyn::invalid_value_error("Invalid input size"); } - // set interior node positions and velocities and all VIV based on state vector + // set interior node positions and velocities and all misc states based on state vector for (unsigned int i = 0; i < N+1; i++) { if ((i != 0) && (i != N)) { r[i] = pos[i - 1]; rd[i] = vel[i - 1]; } - VIV[i] = viv[i]; // VIV[i][0,1,2] correspond to phase, amplitude, smoothed amplitude. + Misc[i] = misc[i]; // Misc[i][0,1,2] correspond to viv phase, viscoelastic, unused. } } @@ -1192,31 +1192,30 @@ Line::getStateDeriv() // Vortex Induced Vibration (VIV) cross-flow lift force if ((Cl > 0.0) && (!IC_gen)) { // If non-zero lift coefficient and not during IC_gen then VIV to be calculated - // Note: amplitude calculations commented out. Would be needed if a Cl vs A lookup table was implemented + + // Note: amplitude calculations and states commented out. Would be needed if a Cl vs A lookup table was ever implemented - const moordyn::real phi = VIV[i][0] - (2 * pi * floor(VIV[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi - // const moordyn::real A_int = VIV[i][1]; - // const moordyn::real As = VIV[i][2]; + const moordyn::real phi = Misc[i][0] - (2 * pi * floor(Misc[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi + // const moordyn::real A_int = Misc[i][1]; + // const moordyn::real As = Misc[i][2]; // Crossflow velocity const moordyn::real yd = rd[i].dot(q[i].cross(vp.normalized())); - // // Vortex shedding period - // const moordyn::real T_s = d / (Ui_mag * 0.2); // We are assuming strouhal number of 0.2 for sub-critical flow regime based on Reynolds number. - - // phase of y_dot + // Phase of cross-flow velocity // const moordyn::real T_m = 5 * T_s; // take the sampling time to be 5x the sheddding period // const moordyn::real n_m = int(T_m/dtm)+1; const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Jorgen const moordyn::real ydd_old = rdd_old[i].dot(dir_old[i]); const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd_old*ydd_old))/n_m); - moordyn::real phi_yd; + moordyn::real phi_yd; // this is only updated once per dtm time step, while the lift force phase is updated every internal time integration timestep if ((yd_rms==0.0) || (ydd_rms == 0.0)) phi_yd = atan2(-ydd_old, yd_old[i]); // To avoid divide by zero else phi_yd = atan2(-ydd_old/ydd_rms, yd_old[i]/yd_rms); + if (phi_yd < 0) phi_yd = 2*pi + phi_yd; // atan2 to 0-2Pi range // non-dimensional frequency - const moordyn::real f_hat = cF + dF *sin(phi_yd - phi); // phi to be integrated from state + const moordyn::real f_hat = cF + dF *sin(phi_yd - phi); // phi is integrated from state deriv phi_dot // frequency of lift force (rad/s) const moordyn::real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state @@ -1233,11 +1232,6 @@ Line::getStateDeriv() // // Lift coefficient from lookup table // const moordyn::real C_l = cl_lookup(x = As/d); // create function in Line.hpp that uses lookup table - // Prep for returning VIV state derivatives - VIVd[i][0] = phi_dot; - // VIVd[i][1] = A_int_dot; - // VIVd[i][2] = As_dot; - // The Lift force if (i == 0) Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i]); @@ -1246,6 +1240,12 @@ Line::getStateDeriv() else Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i] + F[i - 1] * l[i - 1]); + // Prep for returning VIV state derivatives + Miscd[i][0] = phi_dot; + // Miscd[i][1] = A_int_dot; + // Miscd[i][2] = As_dot; + + if ((t >= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. yd_old[i] = yd; // for updating rms back indexing (one moordyn timestep back) @@ -1253,7 +1253,6 @@ Line::getStateDeriv() ydd_rms_old[i] = ydd_rms; // for updating rms back indexing (one moordyn timestep back) dir_old[i] = q[i].cross(Ui_hat); // direction from previous timestep, to make sure ydd_old and yd_old have same direction } - // FIXME: make sure that in the case of no currents, it runs fine without bugs } // tangential component of fluid acceleration @@ -1373,7 +1372,7 @@ Line::getStateDeriv() rdd_old = a; // saving acceleration for VIV RMS calculation t_old = t; // for updating back indexing if statements } - return make_tuple(u, a, VIVd); + return make_tuple(u, a, Miscd); }; // write output file for line (accepts time parameter since retained time value diff --git a/source/Line.hpp b/source/Line.hpp index 36997cad..ff6fd049 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -270,10 +270,10 @@ class Line final : public io::IO, public NatFreqCFL // VIV stuff // /// VIV amplitude updated every zero crossing of crossflow velcoity // std::vector Amp; - /// VIV state (phase,amplitude,smoothed amplitude) - std::vector VIV; - /// derivative of VIV state (phase,amplitude,smoothed amplitude) - std::vector VIVd; + /// Misc states (viv phase,viscoelastic,unused) + std::vector Misc; + /// derivative of Misc states (viv phase,viscoelastic,unused) + std::vector Miscd; /// Num timesteps for rolling RMS of crossflow velocity phase const unsigned int n_m = 500; diff --git a/source/Misc.cpp b/source/Misc.cpp index aa31cdff..48020acc 100644 --- a/source/Misc.cpp +++ b/source/Misc.cpp @@ -31,6 +31,7 @@ #include "Misc.hpp" #include #include +#include using namespace std; @@ -78,8 +79,10 @@ split(const string& str, const char sep) string token; vector words; while (std::getline(spliter, token, sep)) { - if (token.size()) - words.push_back(token); + if (token.find("#") == string::npos){ + if (token.size()) // # is a comment in input files + words.push_back(token); + } else break; } return words; } diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 4a1fe877..55ab675e 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -528,6 +528,11 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) // ------------------ do IC gen -------------------- if (!skip_ic) { + + for (unsigned int l = 0; l < LineList.size(); l++){ + LineList[l]->IC_gen = true; // turn on IC_gen flag + } + moordyn::error_id err; if (ICgenDynamic) err = icLegacy(); @@ -535,6 +540,10 @@ moordyn::MoorDyn::Init(const double* x, const double* xd, bool skip_ic) err = icStationary(); if (err != MOORDYN_SUCCESS) return err; + + for (unsigned int l = 0; l < LineList.size(); l++){ + LineList[l]->IC_gen = false; // turn off IC_gen flag + } } else { _t_integrator->Init(); } diff --git a/source/State.cpp b/source/State.cpp index ea8755fe..9d6c1c9f 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -603,9 +603,9 @@ MoorDynState::AsString() const s << "Line " << i << ":" << endl; s << lines[i].AsString(); } - for (unsigned int i = 0; i < viv.size(); i++) { - s << "VIV " << i << ":" << endl; - s << viv[i].AsString(); + for (unsigned int i = 0; i < misc.size(); i++) { + s << "Misc " << i << ":" << endl; + s << misc[i].AsString(); } for (unsigned int i = 0; i < points.size(); i++) { s << "Point " << i << ":" << endl; @@ -630,10 +630,10 @@ MoorDynState::operator=(const MoorDynState& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.push_back(l); - viv.clear(); - viv.reserve(rhs.viv.size()); - for (auto l : rhs.viv) - viv.push_back(l); + misc.clear(); + misc.reserve(rhs.misc.size()); + for (auto l : rhs.misc) + misc.push_back(l); points.clear(); points.reserve(rhs.points.size()); for (auto l : rhs.points) @@ -660,11 +660,11 @@ MoorDynState::operator+(const MoorDynState& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] + rhs.lines[i]); - if (viv.size() != rhs.viv.size()) + if (misc.size() != rhs.misc.size()) throw moordyn::invalid_value_error("Invalid input size"); - out.viv.reserve(viv.size()); - for (unsigned int i = 0; i < viv.size(); i++) - out.viv.push_back(viv[i] + rhs.viv[i]); + out.misc.reserve(misc.size()); + for (unsigned int i = 0; i < misc.size(); i++) + out.misc.push_back(misc[i] + rhs.misc[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -694,11 +694,11 @@ MoorDynState::operator-(const MoorDynState& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] - rhs.lines[i]); - if (viv.size() != rhs.viv.size()) + if (misc.size() != rhs.misc.size()) throw moordyn::invalid_value_error("Invalid input size"); - out.viv.reserve(viv.size()); - for (unsigned int i = 0; i < viv.size(); i++) - out.viv.push_back(viv[i] - rhs.viv[i]); + out.misc.reserve(misc.size()); + for (unsigned int i = 0; i < misc.size(); i++) + out.misc.push_back(misc[i] - rhs.misc[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -740,9 +740,9 @@ DMoorDynStateDt::AsString() const s << "Line " << i << ":" << endl; s << lines[i].AsString(); } - for (unsigned int i = 0; i < viv.size(); i++) { - s << "VIV " << i << ":" << endl; - s << viv[i].AsString(); + for (unsigned int i = 0; i < misc.size(); i++) { + s << "Misc " << i << ":" << endl; + s << misc[i].AsString(); } for (unsigned int i = 0; i < points.size(); i++) { s << "Point " << i << ":" << endl; @@ -767,10 +767,10 @@ DMoorDynStateDt::operator=(const DMoorDynStateDt& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.push_back(l); - viv.clear(); - viv.reserve(rhs.viv.size()); - for (auto l : rhs.viv) - viv.push_back(l); + misc.clear(); + misc.reserve(rhs.misc.size()); + for (auto l : rhs.misc) + misc.push_back(l); points.clear(); points.reserve(rhs.points.size()); for (auto l : rhs.points) @@ -795,9 +795,9 @@ DMoorDynStateDt::operator*(const real& dt) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] * dt); - out.viv.reserve(viv.size()); - for (unsigned int i = 0; i < viv.size(); i++) - out.viv.push_back(viv[i] * dt); + out.misc.reserve(misc.size()); + for (unsigned int i = 0; i < misc.size(); i++) + out.misc.push_back(misc[i] * dt); out.points.reserve(points.size()); for (unsigned int i = 0; i < points.size(); i++) out.points.push_back(points[i] * dt); @@ -821,11 +821,11 @@ DMoorDynStateDt::operator+(const DMoorDynStateDt& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] + rhs.lines[i]); - if (viv.size() != rhs.viv.size()) + if (misc.size() != rhs.misc.size()) throw moordyn::invalid_value_error("Invalid input size"); - out.viv.reserve(viv.size()); - for (unsigned int i = 0; i < viv.size(); i++) - out.viv.push_back(viv[i] + rhs.viv[i]); + out.misc.reserve(misc.size()); + for (unsigned int i = 0; i < misc.size(); i++) + out.misc.push_back(misc[i] + rhs.misc[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); @@ -855,11 +855,11 @@ DMoorDynStateDt::operator-(const DMoorDynStateDt& rhs) out.lines.reserve(lines.size()); for (unsigned int i = 0; i < lines.size(); i++) out.lines.push_back(lines[i] - rhs.lines[i]); - if (viv.size() != rhs.viv.size()) + if (misc.size() != rhs.misc.size()) throw moordyn::invalid_value_error("Invalid input size"); - out.viv.reserve(viv.size()); - for (unsigned int i = 0; i < viv.size(); i++) - out.viv.push_back(viv[i] - rhs.viv[i]); + out.misc.reserve(misc.size()); + for (unsigned int i = 0; i < misc.size(); i++) + out.misc.push_back(misc[i] - rhs.misc[i]); if (points.size() != rhs.points.size()) throw moordyn::invalid_value_error("Invalid input size"); out.points.reserve(points.size()); diff --git a/source/State.hpp b/source/State.hpp index d5ed14ef..93836be0 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -267,8 +267,8 @@ class MoorDynState /// The states of the lines std::vector lines; - /// The states of VIV (vel is dummy var) - std::vector viv; + /// The state derivatives of misc states: VIV, viscoelastic, blank (acc is dummy variable) + std::vector misc; /// The states of the points std::vector points; @@ -327,8 +327,8 @@ class DMoorDynStateDt /// The state derivatives of the lines std::vector lines; - /// The state derivatives of VIV (acc is dummy variable) - std::vector viv; + /// The state derivatives of misc states: VIV, viscoelastic, blank (acc is dummy variable) + std::vector misc; /// The state derivatives of the points std::vector points; diff --git a/source/Time.cpp b/source/Time.cpp index c9b88a1e..d19e29e5 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -84,7 +84,7 @@ TimeSchemeBase::Update(real t_local, unsigned int substep) for (unsigned int i = 0; i < lines.size(); i++) { lines[i]->setTime(this->t); - lines[i]->setState(r[substep].lines[i].pos, r[substep].lines[i].vel, r[substep].viv[i].pos); + lines[i]->setState(r[substep].lines[i].pos, r[substep].lines[i].vel, r[substep].misc[i].pos); } } @@ -97,7 +97,7 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) for (unsigned int i = 0; i < lines.size(); i++) { if (!_calc_mask.lines[i]) continue; - std::tie(rd[substep].lines[i].vel, rd[substep].lines[i].acc, rd[substep].viv[i].vel) = + std::tie(rd[substep].lines[i].vel, rd[substep].lines[i].acc, rd[substep].misc[i].vel) = lines[i]->getStateDeriv(); } diff --git a/source/Time.hpp b/source/Time.hpp index 15ff48cb..580a5f0f 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -337,24 +337,24 @@ class TimeSchemeBase : public TimeScheme // Build up the states and states derivatives unsigned int n = obj->getN() - 1; LineState state; - LineState vstate; + LineState mstate; // misc state stuff state.pos.assign(n, vec::Zero()); state.vel.assign(n, vec::Zero()); - vstate.pos.assign(n+2, vec::Zero()); - vstate.vel.assign(n+2, vec::Zero()); + mstate.pos.assign(n+2, vec::Zero()); + mstate.vel.assign(n+2, vec::Zero()); for (unsigned int i = 0; i < r.size(); i++) { r[i].lines.push_back(state); - r[i].viv.push_back(vstate); + r[i].misc.push_back(mstate); } DLineStateDt dstate; - DLineStateDt vdstate; + DLineStateDt mdstate; // misc state stuff dstate.vel.assign(n, vec::Zero()); dstate.acc.assign(n, vec::Zero()); - vdstate.vel.assign(n+2, vec::Zero()); - vdstate.acc.assign(n+2, vec::Zero()); + mdstate.vel.assign(n+2, vec::Zero()); + mdstate.acc.assign(n+2, vec::Zero()); for (unsigned int i = 0; i < rd.size(); i++) { rd[i].lines.push_back(dstate); - rd[i].viv.push_back(vdstate); + rd[i].misc.push_back(mdstate); } // Add the mask value _calc_mask.lines.push_back(true); @@ -565,7 +565,7 @@ class TimeSchemeBase : public TimeScheme } for (unsigned int i = 0; i < lines.size(); i++) { - std::tie(r[0].lines[i].pos, r[0].lines[i].vel, r[0].viv[i].pos) = + std::tie(r[0].lines[i].pos, r[0].lines[i].vel, r[0].misc[i].pos) = lines[i]->initialize(); } } From ba78386da8e3e2770007a33bd4f0d80f1832469f Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Thu, 17 Oct 2024 14:32:08 -0600 Subject: [PATCH 130/145] docs: Added # comment character instructions to docs --- docs/inputs.rst | 3 ++- source/Misc.cpp | 1 - 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index aa8237c6..7260f6ac 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -247,7 +247,8 @@ 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. +the entries in that section's table of inputs. # is the general comment chacater. 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). diff --git a/source/Misc.cpp b/source/Misc.cpp index 48020acc..b4f44f5a 100644 --- a/source/Misc.cpp +++ b/source/Misc.cpp @@ -31,7 +31,6 @@ #include "Misc.hpp" #include #include -#include using namespace std; From 4c2f789922b605522e7b29028f4bd2062a4f11c8 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Thu, 17 Oct 2024 16:32:55 -0600 Subject: [PATCH 131/145] feat: Viscoelastic model with constant and load dependent dynamic stiffness is now live! --- source/Line.cpp | 143 ++++++++++++++++++++++++++++++-------------- source/Line.hpp | 32 ++++++---- source/Misc.hpp | 11 +++- source/MoorDyn2.cpp | 50 +++++++++++++--- 4 files changed, 168 insertions(+), 68 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index fb532e61..e50c5773 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -61,10 +61,10 @@ Line::Line(moordyn::Log* log, size_t lineId) Line::~Line() {} real -Line::getNonlinearE(real l_stretched, real l_unstretched) const +Line::getNonlinearEA(real l_stretched, real l_unstretched) const { if (!nEApoints) - return E; + return EA; real Xi = l_stretched / l_unstretched - 1.0; // strain rate based on inputs if (Xi < 0.0) { @@ -93,10 +93,10 @@ Line::getNonlinearEI(real curv) const } real -Line::getNonlinearC(real ld_stretched, real l_unstretched) const +Line::getNonlinearBA(real ld_stretched, real l_unstretched) const { - if (!nCpoints) - return c; + if (!nBApoints) + return BA; real Xi = ld_stretched / l_unstretched; // stretching/compressing rate real Yi = 0.0; @@ -147,9 +147,14 @@ Line::setup(int number_in, d = props->d; A = pi / 4. * d * d; rho = props->w / A; - E = props->EA / A; + ElasticMod = props->ElasticMod; + EA = props->EA; + EA_D = props->EA_D; + alphaMBL = props->alphaMBL; + vbeta = props->vbeta; EI = props->EI; - BAin = props->c; + BAin = props->BA; + BA_D = props->BA_D; Can = props->Can; Cat = props->Cat; Cdn = props->Cdn; @@ -164,11 +169,11 @@ Line::setup(int number_in, nEApoints = props->nEApoints; for (unsigned int I = 0; I < nEApoints; I++) { stiffXs.push_back(props->stiffXs[I]); - stiffYs.push_back(props->stiffYs[I] / A); + stiffYs.push_back(props->stiffYs[I]); } // Use the last entry on the lookup table. see Line::initialize() - const real EA = nEApoints ? stiffYs.back() / stiffXs.back() * A : props->EA; + const real EA = nEApoints ? stiffYs.back() / stiffXs.back(): props->EA; NatFreqCFL::length(UnstrLen / N); NatFreqCFL::stiffness(EA * N / UnstrLen); NatFreqCFL::mass(props->w * UnstrLen / N); @@ -185,8 +190,8 @@ Line::setup(int number_in, // copy in nonlinear stress-strainrate data if applicable dampXs.clear(); dampYs.clear(); - nCpoints = props->nCpoints; - for (unsigned int I = 0; I < nCpoints; I++) { + nBApoints = props->nBApoints; + for (unsigned int I = 0; I < nBApoints; I++) { dampXs.push_back(props->dampXs[I]); dampYs.push_back(props->dampYs[I]); } @@ -259,22 +264,23 @@ std::tuple, std::vector, std::vector> Line::initialize() { LOGMSG << " - Line" << number << ":" << endl - << " ID: " << number << endl + << " ID : " << number << endl << " UnstrLen: " << UnstrLen << endl - << " N : " << N << endl - << " d : " << d << endl - << " rho : " << rho << endl - << " E : " << E << endl - << " EI : " << EI << endl - << " BAin: " << BAin << endl - << " Can : " << Can << endl - << " Cat : " << Cat << endl - << " Cdn : " << Cdn << endl - << " Cdt : " << Cdt << endl - << " Cl : " << Cl << endl - << " dF : " << dF << endl - << " cF : " << cF << endl - << " ww_l: " << ((rho - env->rho_w) * (pi / 4. * d * d)) * 9.81 + << " N : " << N << endl + << " d : " << d << endl + << " rho : " << rho << endl + << " EAMod : " << ElasticMod << endl + << " EA : " << EA << endl + << " BA : " << BA << endl + << " EI : " << EI << endl + << " Can : " << Can << endl + << " Cat : " << Cat << endl + << " Cdn : " << Cdn << endl + << " Cdt : " << Cdt << endl + << " Cl : " << Cl << endl + << " dF : " << dF << endl + << " cF : " << cF << endl + << " ww_l : " << ((rho - env->rho_w) * (pi / 4. * d * d)) * 9.81 << endl; if (outfile) { @@ -470,21 +476,21 @@ Line::initialize() // For the sake of the following initialization steps, if using a // nonlinear stiffness model, set the stiffness based on the last // entries in the lookup table - E = stiffYs.back() / stiffXs.back(); + EA = stiffYs.back() / stiffXs.back(); } // process internal damping input if (BAin < 0) { // automatic internal damping option (if negative BA provided (stored as // BAin), then -BAin indicates desired damping ratio) - c = -BAin * UnstrLen / N * sqrt(E * rho); // rho = w/A - LOGMSG << "Line " << number << " damping set to " << c - << " Pa-s = " << c * A << " Ns, based on input of " << BAin + BA = -BAin * UnstrLen / N * sqrt(EA * rho); // rho = w/A + LOGMSG << "Line " << number << " damping set to " << BA / A + << " Pa-s = " << BA << " Ns, based on input of " << BAin << endl; } else { // otherwise it's the regular internal damping coefficient, which should // be divided by area to get a material coefficient - c = BAin / A; + BA = BAin; } // initialize line node positions as distributed linearly between the @@ -531,7 +537,7 @@ Line::initialize() int success = Catenary(XF, ZF, UnstrLen, - E * A, + EA, LW, CB, Tol, @@ -950,22 +956,67 @@ Line::getStateDeriv() // loop through the segments for (unsigned int i = 0; i < N; i++) { - // line tension - if (nEApoints > 0) - E = getNonlinearE(lstr[i], l[i]); + if (ElasticMod == 1) { + // line tension + if (nEApoints > 0) + EA = getNonlinearEA(lstr[i], l[i]); - if (lstr[i] / l[i] > 1.0) { - T[i] = E * A * (lstr[i] - l[i]) / l[i] * qs[i]; - } else { - // cable can't "push" ... - // or can it, if bending stiffness is nonzero? <<<<<<<<< - T[i] = vec::Zero(); - } + if (lstr[i] / l[i] > 1.0) { + T[i] = EA * (lstr[i] - l[i]) / l[i] * qs[i]; + } else { + // cable can't "push" ... + // or can it, if bending stiffness is nonzero? <<<<<<<<< + T[i] = vec::Zero(); + } - // line internal damping force - if (nCpoints > 0) - c = getNonlinearC(ldstr[i], l[i]); - Td[i] = c * A * ldstr[i] / l[i] * qs[i]; + // line internal damping force + if (nBApoints > 0) + BA = getNonlinearBA(ldstr[i], l[i]); + Td[i] = BA * ldstr[i] / l[i] * qs[i]; + } + // viscoelastic model from https://asmedigitalcollection.asme.org/OMAE/proceedings/IOWTC2023/87578/V001T01A029/1195018 + else if (ElasticMod > 1){ + + double EA_2; + + // note that Misc[i][1] is the same as Line%dl_1 in MD-F. This is the deltaL of the first static spring k1. + + if (ElasticMod == 3){ + if (Misc[i][1] >= 0.0) + // Mean load dependent dynamic stiffness: from combining eqn. 2 and eqn. 10 from original MD viscoelastic paper, taking mean load = k1 delta_L1 / MBL, and solving for k_D using WolframAlpha with following conditions: k_D > k_s, (MBL,alpha,beta,unstrLen,delta_L1) > 0 + EA_2 = 0.5 * ((alphaMBL) + (vbeta*Misc[i][1]*(EA / l[i])) + EA + sqrt((alphaMBL * alphaMBL) + (2*alphaMBL*(EA / l[i]) * (vbeta*Misc[i][1] - l[i])) + ((EA / l[i])*(EA / l[i]) * (vbeta*Misc[i][1] + l[i])*(vbeta*Misc[i][1] + l[i])))); + else + EA_2 = alphaMBL; // mean load is considered to be 0 in this case. The second term in the above equation is not valid for delta_L1 < 0. + + + } else if (ElasticMod == 2) { + // constant dynamic stiffness + EA_2 = EA_D; + } + + if (EA_2 == 0.0) { // Make sure EA != EA_D or else nans, also make sure EA_D != 0 or else nans. + LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal zero" << endl; + throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal zero"); + } else if (EA_2 == EA) { + LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal static stiffness" << endl; + throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal static stiffness"); + } + + const double EA_1 = EA_2*EA/(EA_2 - EA); // calculated EA_1 which is the stiffness in series with EA_D that will result in the desired static stiffness of EA_S. + + const double dl = lstr[i] - l[i]; // delta l of this segment + + const double ld_1 = (EA_2*dl - (EA_2 + EA_1)*Misc[i][1] + BA_D*ldstr[i]) /( BA_D + BA); // rate of change of static stiffness portion [m/s] + + if (dl >= 0.0) // if both spring 1 (the spring dashpot in parallel) and the whole segment are not in compression + T[i] = (EA_1*Misc[i][1] / l[i]) * qs[i]; // compute tension based on static portion (dynamic portion would give same). See eqn. 14 in paper + else + T[i] = 0.0 * qs[i]; // cable can't "push" + + Td[i] = BA*ld_1 / l[i] * qs[i]; + // update state derivative for static stiffness stretch (last N entries in the state vector) + Miscd[i][1] = ld_1; + } } // Bending loads diff --git a/source/Line.hpp b/source/Line.hpp index ff6fd049..b9f0eb81 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -83,18 +83,18 @@ class Line final : public io::IO, public NatFreqCFL ~Line(); private: - /** @brief Get the non-linear Young's modulus. This is interpolated from a + /** @brief Get the non-linear stiffness. This is interpolated from a * curve provided in the input file. * @param l_stretched The actual length of the segment * @param l_unstretched The unstretched length of the segment */ - real getNonlinearE(real l_stretched, real l_unstretched) const; + real getNonlinearEA(real l_stretched, real l_unstretched) const; /** @brief Get the non-linear Damping coefficient * @param ld_stretched The segment rate of stretch * @param l_unstretched The unstretched length of the segment */ - real getNonlinearC(real ld_stretched, real l_unstretched) const; + real getNonlinearBA(real ld_stretched, real l_unstretched) const; /** @brief Get the non-linear bending stiffness * @param curv The curvature @@ -140,19 +140,29 @@ class Line final : public io::IO, public NatFreqCFL moordyn::real d; /// line density (kg/m^3) moordyn::real rho; - /// line elasticity modulus (Young's modulus) [Pa] - moordyn::real E; + /// Elasticity model flag + unsigned int ElasticMod; + /// line normal/static elasticity modulus (Young's modulus) [Pa] + moordyn::real EA; + /// line dynamic stiffness modulus * area for viscoelastic stuff + moordyn::real EA_D; + /// Alpha * MBL in load dependent dynamic stiffness equation Kd = Alpha * MBL + vbeta * Lm for viscoelastic model + moordyn::real alphaMBL; + /// beta in load dependent dynamic stiffness equation Kd = Alpha * MBL + vbeta * Lm for viscoelastic model + moordyn::real vbeta; /// line bending stiffness [Nm^2] moordyn::real EI; /** line axial internal damping coefficient [Pa-s] * - * The provided value in moordyn::Line::props::c can be either the literal + * The provided value in moordyn::Line::props::BA can be either the literal * damping coefficient, or a negative value in which case it represents the - * fraction of the critical damping, + * fraction of the critical damping * area, * * \f$ C_{crit} = \frac{l}{n} \sqrt{\rho E} \f$ */ - moordyn::real c; + moordyn::real BA; + /// Line axial damping coefficient corresponding to the dynamic spring in the viscoelastic model + moordyn::real BA_D; /// normal added mass coefficient [-] /// with respect to line displacement moordyn::real Can; @@ -192,7 +202,7 @@ class Line final : public io::IO, public NatFreqCFL /// y array for bent stiffness lookup table std::vector bstiffYs; /// number of values in stress-strainrate lookup table (0 for constant c) - unsigned int nCpoints; + unsigned int nBApoints; /// x array for stress-strainrate lookup table std::vector dampXs; /// y array for stress-strainrate lookup table @@ -466,7 +476,7 @@ class Line final : public io::IO, public NatFreqCFL * @return The constant stiffness EA value * @see ::IsConstantEA() */ - inline moordyn::real getConstantEA() const { return E * A; } + inline moordyn::real getConstantEA() const { return EA; } /** @brief Set the constant stiffness of the line * @@ -474,7 +484,7 @@ class Line final : public io::IO, public NatFreqCFL * @param EA The constant stiffness EA value * @see ::IsConstantEA() */ - inline void setConstantEA(moordyn::real EA) { E = EA / A; } + inline void setConstantEA(moordyn::real EA) { EA = EA; } /** @brief Get the position of a node * @param i The line node index diff --git a/source/Misc.hpp b/source/Misc.hpp index e9853146..5b656fa9 100644 --- a/source/Misc.hpp +++ b/source/Misc.hpp @@ -701,7 +701,7 @@ inline vector split(const string& s) { vector sout = split(s, ' '); - if (sout.size() == 1) return split(sout[0], ' '); + if (sout.size() == 1) return split(sout[0], ' '); // if space didnt split it, try again with tab else return sout; } @@ -1087,9 +1087,14 @@ typedef struct _LineProps // (matching Line Dictionary inputs) string type; double d; double w; // linear weight in air + int ElasticMod; double EA; + double EA_D; + double alphaMBL; + double vbeta; double EI; - double c; // internal damping + double BA; // internal damping + double BA_D; double cI; double Can; double Cat; @@ -1103,7 +1108,7 @@ typedef struct _LineProps // (matching Line Dictionary inputs) double stiffXs[nCoef]; // x array for stress-strain lookup table (up to nCoef) double stiffYs[nCoef]; // y array for stress-strain lookup table - int nCpoints; // number of values in stress-strainrate lookup table (0 means + int nBApoints; // number of values in stress-strainrate lookup table (0 means // using constant c) double dampXs[nCoef]; // x array for stress-strainrate lookup table (up to // nCoef) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 55ab675e..a1852a84 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1757,16 +1757,47 @@ moordyn::MoorDyn::readLineProps(string inputText) } else return nullptr; moordyn::error_id err; - err = read_curve(entries[3].c_str(), - &(obj->EA), - &(obj->nEApoints), - obj->stiffXs, - obj->stiffYs); + vector EA_stuff = moordyn::str::split(entries[3],'|'); + const int EA_N = EA_stuff.size(); + if (EA_N == 1) { + obj->ElasticMod = 1; // normal case + } + else if (EA_N==2){ + obj->ElasticMod = 2; // viscoelastic model, constant dynamic stiffness + obj->EA_D = atof(EA_stuff[1].c_str()); + } else if (EA_N==3){ + obj->ElasticMod = 3; // viscoelastic model load dependent dynamic stiffness + obj->alphaMBL = atof(EA_stuff[1].c_str()); + obj->vbeta = atof(EA_stuff[2].c_str()); + } else { + LOGERR << "A line type EA entry can have at most 3 (bar-separated) values." << endl; + return nullptr; + } + err = read_curve(EA_stuff[0].c_str(), + &(obj->EA), + &(obj->nEApoints), + obj->stiffXs, + obj->stiffYs); if (err) return nullptr; - err = read_curve(entries[4].c_str(), - &(obj->c), - &(obj->nCpoints), + + vector BA_stuff = moordyn::str::split(entries[4],'|'); + unsigned int BA_N = BA_stuff.size(); + if (BA_N > EA_N) { + LOGERR << "A line type BA entry cannot have more (bar-separated) values than its EA entry." << endl; + return nullptr; + } else if (BA_N == 2){ + obj->BA_D = atof(BA_stuff[1].c_str()); + } else if (obj->ElasticMod>1){ + LOGWRN << "Warning, viscoelastic model being used with zero damping on the dynamic stiffness." << endl; + obj->BA_D = 0.0; + } else { + LOGERR << "A line type BA entry can have at most 2 (bar-separated) values." << endl; + return nullptr; + } + err = read_curve(BA_stuff[0].c_str(), + &(obj->BA), + &(obj->nBApoints), obj->dampXs, obj->dampYs); if (err) @@ -1779,6 +1810,9 @@ moordyn::MoorDyn::readLineProps(string inputText) if (err) return nullptr; + if (obj->Cl > 0.0) nX = nX+1; + if (obj->ElasticMod > 1) nX = nX+1; + LOGDBG << "\t'" << obj->type << "'" << " - with id " << LinePropList.size() << endl << "\t\td : " << obj->d << endl From 73aef126fb8cc392c0677786d8ff39933252fa4d Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Thu, 17 Oct 2024 17:00:57 -0600 Subject: [PATCH 132/145] docs: Minor change to update viscoelastic docs --- docs/inputs.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index e0a97c72..501cf789 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -316,7 +316,7 @@ tabulated file with 3 header lines and then a strain column and a tension column 0.0 0.0 ... ... -Note: MoorDyn-F has the ability to model the viscoelastic properties of synthetic lines in two ways. The first method, from work linked in the +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 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. Example inputs are below: From 084f23175511b62bfa778a8db6a26e7889c4b919 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 18 Oct 2024 11:32:01 -0600 Subject: [PATCH 133/145] fix: some small fixes for viscoelastic stuff --- source/MoorDyn2.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index bc7561c3..3b8887b0 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -1109,9 +1109,10 @@ moordyn::MoorDyn::ReadInFile() // node (so water depth input is optional) // TODO - this probably doesn't care about 3d seafloor? // Note - this is not in MD-F - if (r0[2] < -env->WtrDpth) + if (r0[2] < -env->WtrDpth) { env->WtrDpth = -r0[2]; - LOGWRN << "\t Water depth set to point " << PointList.size() << " z position because point was specified below the seabed" << endl; + LOGWRN << "\t Water depth set to point " << PointList.size()+1 << " z position because point was specified below the seabed" << endl; + } LOGDBG << "\t'" << number << "'" << " - of type " << Point::TypeName(type) << " with id " @@ -1191,7 +1192,7 @@ moordyn::MoorDyn::ReadInFile() // Make the output file (if queried) if ((outchannels.size() > 0) && - (strcspn(outchannels.c_str(), "pvUDVctsd") < + (strcspn(outchannels.c_str(), "pvUDVKctsd") < strlen(outchannels.c_str()))) { // if 1+ output flag chars are given and they're valid stringstream oname; @@ -1816,9 +1817,9 @@ moordyn::MoorDyn::readLineProps(string inputText) } else if (BA_N == 2){ obj->BA_D = atof(BA_stuff[1].c_str()); } else if (obj->ElasticMod>1){ - LOGWRN << "Warning, viscoelastic model being used with zero damping on the dynamic stiffness." << endl; + LOGMSG << "Message: viscoelastic model being used with zero damping on the dynamic stiffness." << endl; obj->BA_D = 0.0; - } else { + } else if (BA_N > 2) { LOGERR << "A line type BA entry can have at most 2 (bar-separated) values." << endl; return nullptr; } From f3d4a2a8e6b9ed5d4c4b1a9f708aea34fb6ce9af Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 18 Oct 2024 11:34:31 -0600 Subject: [PATCH 134/145] fix: removing files --- .../python-wheels-manylinux-arch.yml | 74 ------------------- 1 file changed, 74 deletions(-) delete mode 100644 .github/workflows/python-wheels-manylinux-arch.yml diff --git a/.github/workflows/python-wheels-manylinux-arch.yml b/.github/workflows/python-wheels-manylinux-arch.yml deleted file mode 100644 index d58a514d..00000000 --- a/.github/workflows/python-wheels-manylinux-arch.yml +++ /dev/null @@ -1,74 +0,0 @@ -name: Python-manylinux-arch - -on: - workflow_call: - inputs: - arch: - description: 'Architecture target' - required: true - type: string - -permissions: write-all - -env: - # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) - BUILD_TYPE: Release - VTK_VERSION_MAJOR: 9 - VTK_VERSION_MINOR: 2 - VTK_VERSION_PATCH: 6 - -jobs: - build_wheels: - name: Build Python wheels - runs-on: ${{ matrix.os }} - strategy: - matrix: - os: [ubuntu-22.04] - - steps: - - uses: actions/checkout@v4 - - # Used to host cibuildwheel - - uses: actions/setup-python@v5 - with: - python-version: '3.x' - - - name: Create setup.py - run: | - mv wrappers/python/wheels.github/* ./ - python set_version.py - python set_eigen_data.py - rm set_version.py set_eigen_data.py - shell: bash - - - name: download pre-built VTK static library - uses: suisei-cn/actions-download-file@v1.6.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-manylinux2014_${{inputs.arch}}.tar.gz - target: ${{github.workspace}}/ - - - name: Set up QEMU - uses: docker/setup-qemu-action@v3 - with: - platforms: all - - - name: Build wheels - uses: pypa/cibuildwheel@v2.19.2 - with: - output-dir: dist - env: - # configure cibuildwheel to build native archs ('auto'), and some - # emulated ones - CIBW_ARCHS_LINUX: ${{inputs.arch}} - # Skip 32-bit wheels builds as well as musllinux - CIBW_SKIP: "*-win32 *musllinux*" - CIBW_BEFORE_ALL_LINUX: > - echo "Considering vtk-manylinux2014_`uname -m`.tar.gz..." && - mkdir -p vtk && - tar -xvzf vtk-manylinux2014_`uname -m`.tar.gz -C vtk/ - - - uses: actions/upload-artifact@v4 - id: build_wheels - with: - name: python-wheels-${{inputs.arch}} - path: ./dist/* From b60399881aeecc86f7c474e6c79f7a4a18ec2e72 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 18 Oct 2024 11:36:00 -0600 Subject: [PATCH 135/145] fix: removing one more file --- docs/features.rst | 124 ---------------------------------------------- 1 file changed, 124 deletions(-) delete mode 100644 docs/features.rst diff --git a/docs/features.rst b/docs/features.rst deleted file mode 100644 index 9deb43d4..00000000 --- a/docs/features.rst +++ /dev/null @@ -1,124 +0,0 @@ -Features and References -======================= -.. _theory: - -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: -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -MoorDyn-C, MoorDyn-F and `MoorPy `_ share the -same Intrinsic Euler-XYZ (Tait-Bryan) angles criteria to compute orientations. -You can learn more about this on -`Hall M. Generalized Quasi-Static Mooring System Modeling with Analytic Jacobians. Energies. 2024; 17(13):3155. https://doi.org/10.3390/en17133155 `_ - -However, while on MoorDyn-F this is handled by considering orientation -matrices, on MoorDyn-C quaternions are considered to describe the location and -orientation of 6 DOF 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.' `_ - -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,” - in Proceedings of the 35th International Conference on Ocean, Offshore and Arctic Engineering, Busan, South Korea, 2016. - `_ - - `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 - International Offshore Wind Technical Conference, San Francisco, California, Nov. 2018. `_ - -Overview of MoorDyn v2 (bodies, rods, and line failures): - - `Hall, Matthew, “MoorDyn V2: New Capabilities in Mooring System Components and Load Cases.” In Proceedings of the ASME 2020 39th International - Conference on Ocean, Offshore and Arctic Engineering. virtual conference, 2020. `_ - -Seabed friction and bathymetry approach used in v2: - - `Housner, Stein, Ericka Lozon, Bruce Martin, Dorian Brefort, and Matthew Hall, “Seabed Bathymetry and Friction Modeling in MoorDyn.” Journal of - Physics: Conference Series 2362, no. 1, Nov 2022: 012018. `_ - -Implementation of bending stiffness modeling for power cables: - - `Hall, Matthew, Senu Sirnivas, and Yi-Hsiang Yu, “Implementation and Verification of Cable Bending Stiffness in MoorDyn.” In ASME 2021 3rd International Offshore Wind - Technical Conference, V001T01A011. Virtual, Online: American Society of Mechanical Engineers, 2021. `_ - -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. `_ - -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. `_ - -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 - - KISSFFT: https://github.com/mborgerding/kissfft From f575aeffe5d84b86f475d631f868f9d0ae2127e8 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 18 Oct 2024 12:00:30 -0600 Subject: [PATCH 136/145] fix: cleaned up some time scheme stuff (added in more spots where Misc states should be accounted for) --- source/Time.hpp | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/source/Time.hpp b/source/Time.hpp index 407d23fa..84f7941e 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -392,10 +392,14 @@ class TimeSchemeBase : public TimeScheme } catch (...) { throw; } - for (unsigned int i = 0; i < r.size(); i++) + for (unsigned int i = 0; i < r.size(); i++) { r[i].lines.erase(r[i].lines.begin() + i); - for (unsigned int i = 0; i < rd.size(); i++) + r[i].misc.erase(r[i].misc.begin() + i); + } + for (unsigned int i = 0; i < rd.size(); i++) { rd[i].lines.erase(rd[i].lines.begin() + i); + rd[i].misc.erase(rd[i].misc.begin() + i); + } _calc_mask.lines.erase(_calc_mask.lines.begin() + i); return i; } @@ -646,6 +650,8 @@ class TimeSchemeBase : public TimeScheme data.insert(data.end(), subdata.begin(), subdata.end()); subdata = io::IO::Serialize(r[i].lines[j].vel); data.insert(data.end(), subdata.begin(), subdata.end()); + subdata = io::IO::Serialize(r[i].misc[j].pos); + data.insert(data.end(), subdata.begin(), subdata.end()); } return data; } @@ -674,6 +680,7 @@ class TimeSchemeBase : public TimeScheme for (unsigned int j = 0; j < lines.size(); j++) { ptr = io::IO::Deserialize(ptr, r[i].lines[j].pos); ptr = io::IO::Deserialize(ptr, r[i].lines[j].vel); + ptr = io::IO::Deserialize(ptr, r[i].misc[j].pos); } return ptr; } @@ -756,6 +763,8 @@ class TimeSchemeBase : public TimeScheme data.insert(data.end(), subdata.begin(), subdata.end()); subdata = io::IO::Serialize(r[substep].lines[i].vel); data.insert(data.end(), subdata.begin(), subdata.end()); + subdata = io::IO::Serialize(r[substep].misc[i].pos); + data.insert(data.end(), subdata.begin(), subdata.end()); } } for (unsigned int substep = 0; substep < NDERIV; substep++) { @@ -782,6 +791,8 @@ class TimeSchemeBase : public TimeScheme data.insert(data.end(), subdata.begin(), subdata.end()); subdata = io::IO::Serialize(rd[substep].lines[i].acc); data.insert(data.end(), subdata.begin(), subdata.end()); + subdata = io::IO::Serialize(rd[substep].misc[i].vel); + data.insert(data.end(), subdata.begin(), subdata.end()); } } @@ -820,6 +831,7 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < lines.size(); i++) { ptr = io::IO::Deserialize(ptr, r[substep].lines[i].pos); ptr = io::IO::Deserialize(ptr, r[substep].lines[i].vel); + ptr = io::IO::Deserialize(ptr, r[substep].misc[i].pos); } } for (unsigned int substep = 0; substep < NDERIV; substep++) { @@ -838,6 +850,7 @@ class TimeSchemeBase : public TimeScheme for (unsigned int i = 0; i < lines.size(); i++) { ptr = io::IO::Deserialize(ptr, rd[substep].lines[i].vel); ptr = io::IO::Deserialize(ptr, rd[substep].lines[i].acc); + ptr = io::IO::Deserialize(ptr, rd[substep].misc[i].vel); } } @@ -941,9 +954,10 @@ class StationaryScheme : public TimeSchemeBase<2, 1> */ inline unsigned int NStates() const { unsigned int n = bodies.size() + rods.size() + points.size(); - for (unsigned int i = 0; i < lines.size(); i++) + for (unsigned int i = 0; i < lines.size(); i++) { n += r[0].lines[i].pos.size(); - return n; + n += r[0].misc[i].pos.size(); + } return n; } private: @@ -1246,6 +1260,7 @@ class ABScheme : public LocalTimeSchemeBase<1, 5> continue; rd[dst].lines[i].vel = rd[org].lines[i].vel; rd[dst].lines[i].acc = rd[org].lines[i].acc; + rd[dst].misc[i].vel = rd[org].misc[i].vel; } for (unsigned int i = 0; i < points.size(); i++) { From 24136667846b70abd36a55710f76cf9b7628b413 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 18 Oct 2024 14:25:50 -0600 Subject: [PATCH 137/145] fix: some more stiffness fixes. Noteably before when reading a non-linear look up table it assumed stress strain. This is not correct and doesnt match theory paper or docs. CHanges to stress tension. --- source/Line.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 821a61bd..64f2ae83 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -173,7 +173,7 @@ Line::setup(int number_in, } // Use the last entry on the lookup table. see Line::initialize() - const real EA = nEApoints ? stiffYs.back() / stiffXs.back() * A : props->EA; + const real EA = nEApoints ? stiffYs.back() / stiffXs.back() : props->EA; NatFreqCFL::length(UnstrLen / N); NatFreqCFL::stiffness(EA * N / UnstrLen); NatFreqCFL::mass(props->w * UnstrLen / N); @@ -271,7 +271,7 @@ Line::initialize() << " rho : " << rho << endl << " EAMod : " << ElasticMod << endl << " EA : " << EA << endl - << " BA : " << BA << endl + << " BA : " << BAin << endl << " EI : " << EI << endl << " Can : " << Can << endl << " Cat : " << Cat << endl @@ -483,7 +483,7 @@ Line::initialize() if (BAin < 0) { // automatic internal damping option (if negative BA provided (stored as // BAin), then -BAin indicates desired damping ratio) - BA = -BAin * UnstrLen / N * sqrt(EA * rho); // rho = w/A + BA = -BAin * UnstrLen / N * sqrt(EA * rho * A); // rho = w/A LOGMSG << "Line " << number << " damping set to " << BA / A << " Pa-s = " << BA << " Ns, based on input of " << BAin << endl; From a7bd34c5b6af31f22ca9604c74ef92cb86480a63 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 21 Oct 2024 09:44:55 -0600 Subject: [PATCH 138/145] docs: clarifying dtout --- docs/inputs.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index 501cf789..0ae058ed 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -645,8 +645,8 @@ The list of possible options is: - 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): Ratio 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) + - dtOut (0.0): Time step size to be written to output files. A value of zero will use the coupling + timestep as a step size (s) - SeafloorFile: A path to the :ref:`bathymetry file ` - ICgenDynamic (0): MoorDyn-C switch for using older dynamic relaxation method (same as MoorDyn-F). If this is enabled initial conditions are calculated with scaled drag according to CdScaleIC. From 5f8006ecdc81a3ca0f24aeb0f11bdb61fe0c14f2 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 21 Oct 2024 13:19:59 -0600 Subject: [PATCH 139/145] fix: dynamic current inflile reading fix --- source/Waves/WaveGrid.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Waves/WaveGrid.cpp b/source/Waves/WaveGrid.cpp index 60a16125..edbfb905 100644 --- a/source/Waves/WaveGrid.cpp +++ b/source/Waves/WaveGrid.cpp @@ -622,7 +622,7 @@ constructDynamicCurrentGrid(const std::string& folder, moordyn::Log* _log) { - const string CurrentsFilename = folder + "/current_profile_dynamic.txt"; + const string CurrentsFilename = folder + "current_profile_dynamic.txt"; LOGMSG << " Reading currents dynamic profile from '" << CurrentsFilename << "'..." << endl; From b39211acb6dfe024e243a46790c34df073e45d77 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Wed, 13 Nov 2024 12:58:17 -0700 Subject: [PATCH 140/145] fix: Some more notes explaining the synchronization model --- source/Line.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 64f2ae83..c7459e25 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1253,10 +1253,8 @@ Line::getStateDeriv() // Crossflow velocity const moordyn::real yd = rd[i].dot(q[i].cross(vp.normalized())); - // Phase of cross-flow velocity - // const moordyn::real T_m = 5 * T_s; // take the sampling time to be 5x the sheddding period - // const moordyn::real n_m = int(T_m/dtm)+1; - const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Jorgen + // Phase of cross-flow velocity: This calcualtes the RMS of the previous timestep, using the vel and accel of t-dtm, and the rms value calculated in the previous timestep, which by definition is rms(t-2dtm) + const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Thorsen const moordyn::real ydd_old = rdd_old[i].dot(dir_old[i]); const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd_old*ydd_old))/n_m); moordyn::real phi_yd; // this is only updated once per dtm time step, while the lift force phase is updated every internal time integration timestep From ed6235ab9298d0151c1d4b97caf94173e3507632 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 15 Nov 2024 11:04:49 -0700 Subject: [PATCH 141/145] Direction Fix --- source/Line.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Line.cpp b/source/Line.cpp index c7459e25..9efd0bab 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -1300,7 +1300,7 @@ Line::getStateDeriv() yd_old[i] = yd; // for updating rms back indexing (one moordyn timestep back) yd_rms_old[i] = yd_rms; // for updating rms back indexing (one moordyn timestep back) ydd_rms_old[i] = ydd_rms; // for updating rms back indexing (one moordyn timestep back) - dir_old[i] = q[i].cross(Ui_hat); // direction from previous timestep, to make sure ydd_old and yd_old have same direction + dir_old[i] = q[i].cross(vp.normalized()); // direction from previous timestep, to make sure ydd_old and yd_old have same direction } } From 4abc5e5a62ce1116da159f7fc97689a6ac32ed10 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Fri, 15 Nov 2024 14:30:27 -0700 Subject: [PATCH 142/145] fix: major clean up to the synchronization model --- source/Line.cpp | 61 ++++++++++++++++++++++++++++--------------------- source/Line.hpp | 4 ---- 2 files changed, 35 insertions(+), 30 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index 9efd0bab..f6cbf689 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -205,7 +205,7 @@ Line::setup(int number_in, r.assign(N + 1, vec::Zero()); // node positions [i][x/y/z] rd.assign(N + 1, vec::Zero()); // node velocities [i][x/y/z] - rdd_old.assign(N + 1, vec::Zero()); // node accelerations previous timestep [i][x/y/z] + rdd_old.assign(N + 1, vec::Zero()); // node accelerations previous iteration [i][x/y/z] Misc.assign(N+1, vec::Zero()); // node misc states [i][viv phase/viscoelastic/unused] Miscd.assign(N+1, vec::Zero()); // node misc state derivatives [i][viv phase/viscoelastic/unused] q.assign(N + 1, vec::Zero()); // unit tangent vectors for each node @@ -240,10 +240,8 @@ Line::setup(int number_in, // Back indexing things for VIV (amplitude disabled, only needed if lift coefficient table is added) // A_int_old.assign(N + 1, 0.0); // running amplitude total, from previous zero crossing of yd // Amp.assign(N + 1, 0.0); // VIV Amplitude updated every zero crossing of crossflow velcoity - yd_old.assign(N + 1, 0.0); // node old CF vel yd_rms_old.assign(N + 1, 0.0); // node old yd_rms ydd_rms_old.assign(N + 1, 0.0);// node old ydd_rms - dir_old.assign(N + 1, vec::Zero()); // node old CF vel direction // ensure end moments start at zero endMomentA = vec::Zero(); @@ -577,7 +575,7 @@ Line::initialize() if (Cl > 0.0) { std::vector phase_range(N+1); for (unsigned int i = 0; i < N+1; i++) phase_range[i] = (i/moordyn::real(N))*2*pi; - shuffle(phase_range.begin(),phase_range.end(),random_device()); + // shuffle(phase_range.begin(),phase_range.end(),random_device()); for (unsigned int i = 0; i < N+1; i++) misc[i][0] = phase_range[i]; } @@ -1243,31 +1241,49 @@ Line::getStateDeriv() // Vortex Induced Vibration (VIV) cross-flow lift force if ((Cl > 0.0) && (!IC_gen)) { // If non-zero lift coefficient and not during IC_gen then VIV to be calculated - - // Note: amplitude calculations and states commented out. Would be needed if a Cl vs A lookup table was ever implemented - const moordyn::real phi = Misc[i][0] - (2 * pi * floor(Misc[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi - // const moordyn::real A_int = Misc[i][1]; - // const moordyn::real As = Misc[i][2]; - + // ----- The Synchronization Model ------ // Crossflow velocity const moordyn::real yd = rd[i].dot(q[i].cross(vp.normalized())); + const moordyn::real ydd = rdd_old[i].dot(q[i].cross(vp.normalized())); - // Phase of cross-flow velocity: This calcualtes the RMS of the previous timestep, using the vel and accel of t-dtm, and the rms value calculated in the previous timestep, which by definition is rms(t-2dtm) - const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd_old[i]*yd_old[i]))/n_m); // RMS approximation from Thorsen - const moordyn::real ydd_old = rdd_old[i].dot(dir_old[i]); - const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd_old*ydd_old))/n_m); - moordyn::real phi_yd; // this is only updated once per dtm time step, while the lift force phase is updated every internal time integration timestep - if ((yd_rms==0.0) || (ydd_rms == 0.0)) phi_yd = atan2(-ydd_old, yd_old[i]); // To avoid divide by zero - else phi_yd = atan2(-ydd_old/ydd_rms, yd_old[i]/yd_rms); + // Rolling RMS calculation + const moordyn::real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd*yd))/n_m); // RMS approximation from Thorsen + const moordyn::real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd*ydd))/n_m); + + if ((t >= t_old + dtm) || (t == 0.0)) { // Update the stormed RMS vaues + // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. + yd_rms_old[i] = yd_rms; // for rms back indexing (one moordyn timestep back) + ydd_rms_old[i] = ydd_rms; // for rms back indexing (one moordyn timestep back) + } + + moordyn::real phi_yd; // The crossflow motion phase + if ((yd_rms==0.0) || (ydd_rms == 0.0)) phi_yd = atan2(-ydd, yd); // To avoid divide by zero + else phi_yd = atan2(-ydd/ydd_rms, yd/yd_rms); if (phi_yd < 0) phi_yd = 2*pi + phi_yd; // atan2 to 0-2Pi range + // if ((i == 50) && (t > 20) && (t < 20.001)){ + // if ((t >= t_old + dtm) || (t == 0.0)) cout << "----- new time " << t << "-----" << endl; + // // cout << "yd: " << yd << endl; + // // cout << "ydd: " << ydd << endl; + // // cout << "ydd via rdd_old: " << rdd_old[i].dot(q[i].cross(vp.normalized())) << endl; + // cout << "phi_yd: " << phi_yd << endl; + // } + + // Note: amplitude calculations and states commented out. Would be needed if a Cl vs A lookup table was ever implemented + + const moordyn::real phi = Misc[i][0] - (2 * pi * floor(Misc[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi + // const moordyn::real A_int = Misc[i][1]; + // const moordyn::real As = Misc[i][2]; + // non-dimensional frequency const moordyn::real f_hat = cF + dF *sin(phi_yd - phi); // phi is integrated from state deriv phi_dot // frequency of lift force (rad/s) const moordyn::real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state + // ----- The rest of the model ----- + // // Oscillation amplitude // const moordyn::real A_int_dot = abs(yd); // // Note: Check if this actually measures zero crossings @@ -1294,14 +1310,6 @@ Line::getStateDeriv() // Miscd[i][1] = A_int_dot; // Miscd[i][2] = As_dot; - - if ((t >= t_old + dtm) || (t == 0.0)) { - // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. - yd_old[i] = yd; // for updating rms back indexing (one moordyn timestep back) - yd_rms_old[i] = yd_rms; // for updating rms back indexing (one moordyn timestep back) - ydd_rms_old[i] = ydd_rms; // for updating rms back indexing (one moordyn timestep back) - dir_old[i] = q[i].cross(vp.normalized()); // direction from previous timestep, to make sure ydd_old and yd_old have same direction - } } // tangential component of fluid acceleration @@ -1418,9 +1426,10 @@ Line::getStateDeriv() } if ((t >= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme) - rdd_old = a; // saving acceleration for VIV RMS calculation t_old = t; // for updating back indexing if statements } + rdd_old = a; // saving the acceleration for VIV RMS calculation + return make_tuple(u, a, Miscd); }; diff --git a/source/Line.hpp b/source/Line.hpp index 8c16767c..5bd95220 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -292,14 +292,10 @@ class Line final : public io::IO, public NatFreqCFL moordyn::real t_old = 0.0; // /// running amplitude total, from previous zero crossing of yd // std::vector A_int_old; - /// node old cf vel - std::vector yd_old; /// node old cf vel rms std::vector yd_rms_old; /// node old cf accel rms std::vector ydd_rms_old; - /// node old CF direction - std::vector dir_old; /// node old accelerations std::vector rdd_old; From 86e150529a3a86c38fcdc27a56a5a397f561a8f4 Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Mon, 13 Jan 2025 13:52:34 -0700 Subject: [PATCH 143/145] fix: cleaning up after merge --- source/Line.cpp | 220 ++++++++++++++++++++--------------------------- source/Line.hpp | 9 +- source/State.hpp | 13 +++ 3 files changed, 112 insertions(+), 130 deletions(-) diff --git a/source/Line.cpp b/source/Line.cpp index d45c926d..5d7362ac 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -480,8 +480,8 @@ Line::initialize() // process internal damping input if (BAin < 0) { // automatic internal damping option (if negative BA provided (stored as - // BAin), then -BAin indicates desired damping ratio) - BA = -BAin * UnstrLen / N * sqrt(EA * rho * A); // rho = w/A + // BAin), then -BAin indicates desired damping ratio [unitless]) + BA = -BAin * UnstrLen / N * sqrt(EA * rho * A); // rho = w/A. Units: no unit * m * sqrt(kg-m/s^2 *kg/m) = Ns LOGMSG << "Line " << number << " damping set to " << BA / A << " Pa-s = " << BA << " Ns, based on input of " << BAin << endl; @@ -714,7 +714,7 @@ Line::setPin(std::vector p) } void -Line::setState(const std::vector& pos, const std::vector& vel, const std::vector misc) +Line::setState(const std::vector& pos, const std::vector& vel, const std::vector& misc) { if ((pos.size() != N - 1) || (vel.size() != N - 1) || (misc.size() != N + 1)) { LOGERR << "Invalid input size" << endl; @@ -839,33 +839,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector l[i]) { - T[i] = E * A * (lstr[i] - l[i]) / l[i] * qs[i]; - } else { - // cable can't "push" ... - // or can it, if bending stiffness is nonzero? <<<<<<<<< - T[i] = vec::Zero(); - } - - // line internal damping force - if (nCpoints) - c = getNonlinearC(ldstr[i], l[i]); - Td[i] = c * A * ldstr[i] / l[i] * qs[i]; - } + // ======= calculate various kinematic quantities and stiffness forces ======= // calculate unit tangent vectors (q) for each internal node. note: I've // reversed these from pointing toward 0 rather than N. Check sign of wave @@ -885,6 +859,77 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector 0) + EA = getNonlinearEA(lstr[i], l[i]); + + if (lstr[i] / l[i] > 1.0) { + T[i] = EA * (lstr[i] - l[i]) / l[i] * qs[i]; + } else { + // cable can't "push" ... + // or can it, if bending stiffness is nonzero? <<<<<<<<< + T[i] = vec::Zero(); + } + + // line internal damping force + if (nBApoints > 0) + BA = getNonlinearBA(ldstr[i], l[i]); + Td[i] = BA * ldstr[i] / l[i] * qs[i]; + + } else if (ElasticMod > 1){ // viscoelastic model from https://asmedigitalcollection.asme.org/OMAE/proceedings/IOWTC2023/87578/V001T01A029/1195018 + // note that Misc[i][1] is the same as Line%dl_1 in MD-F. This is the deltaL of the first static spring k1. + + if (ElasticMod == 2) { + // constant dynamic stiffness + EA_2 = EA_D; + + } else if (ElasticMod == 3){ + if (Misc[i][1] >= 0.0) // spring k1 is in tension + // Mean load dependent dynamic stiffness: from combining eqn. 2 and eqn. 10 from original MD viscoelastic paper, taking mean load = k1 delta_L1 / MBL, and solving for k_D using WolframAlpha with following conditions: k_D > k_s, (MBL,alpha,beta,unstrLen,delta_L1) > 0 + EA_2 = 0.5 * ((alphaMBL) + (vbeta*Misc[i][1]*(EA / l[i])) + EA + sqrt((alphaMBL * alphaMBL) + (2*alphaMBL*(EA / l[i]) * (vbeta*Misc[i][1] - l[i])) + ((EA / l[i])*(EA / l[i]) * (vbeta*Misc[i][1] + l[i])*(vbeta*Misc[i][1] + l[i])))); + + else // spring k1 is in compression + EA_2 = alphaMBL; // mean load is considered to be 0 in this case. The second term in the above equation is not valid for delta_L1 < 0. + } + + if (EA_2 == 0.0) { // Make sure EA_2 != 0 or else nans, also make sure EA != EA_D or else nans. + LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal zero" << endl; + throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal zero"); + } else if (EA_2 == EA) { + LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal static stiffness" << endl; + throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal static stiffness"); + } + + const real EA_1 = EA_2*EA/(EA_2 - EA); // calculated EA_1 which is the stiffness in series with EA_D that will result in the desired static stiffness of EA_S. + + const real dl = lstr[i] - l[i]; // delta l of this segment + + const real ld_1 = (EA_2*dl - (EA_2 + EA_1)*Misc[i][1] + BA_D*ldstr[i]) /( BA_D + BA); // rate of change of static stiffness portion [m/s] + + if (dl >= 0.0) // if both spring 1 (the spring dashpot in parallel) and the whole segment are not in compression + T[i] = (EA_1*Misc[i][1] / l[i]) * qs[i]; // compute tension based on static portion (dynamic portion would give same). See eqn. 14 in paper + else + T[i] = vec::Zero(); // cable can't "push" + + Td[i] = BA*ld_1 / l[i] * qs[i]; + + // update state derivative for static stiffness stretch + Miscd[i][1] = ld_1; + } + } + // calculate the curvatures and normal vectors (just if needed) if (isEI || isPb) { for (unsigned int i = 0; i <= N; i++) { @@ -939,73 +984,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector 0) - EA = getNonlinearEA(lstr[i], l[i]); - - if (lstr[i] / l[i] > 1.0) { - T[i] = EA * (lstr[i] - l[i]) / l[i] * qs[i]; - } else { - // cable can't "push" ... - // or can it, if bending stiffness is nonzero? <<<<<<<<< - T[i] = vec::Zero(); - } - - // line internal damping force - if (nBApoints > 0) - BA = getNonlinearBA(ldstr[i], l[i]); - Td[i] = BA * ldstr[i] / l[i] * qs[i]; - } - // viscoelastic model from https://asmedigitalcollection.asme.org/OMAE/proceedings/IOWTC2023/87578/V001T01A029/1195018 - else if (ElasticMod > 1){ - - double EA_2; - - // note that Misc[i][1] is the same as Line%dl_1 in MD-F. This is the deltaL of the first static spring k1. - - if (ElasticMod == 3){ - if (Misc[i][1] >= 0.0) - // Mean load dependent dynamic stiffness: from combining eqn. 2 and eqn. 10 from original MD viscoelastic paper, taking mean load = k1 delta_L1 / MBL, and solving for k_D using WolframAlpha with following conditions: k_D > k_s, (MBL,alpha,beta,unstrLen,delta_L1) > 0 - EA_2 = 0.5 * ((alphaMBL) + (vbeta*Misc[i][1]*(EA / l[i])) + EA + sqrt((alphaMBL * alphaMBL) + (2*alphaMBL*(EA / l[i]) * (vbeta*Misc[i][1] - l[i])) + ((EA / l[i])*(EA / l[i]) * (vbeta*Misc[i][1] + l[i])*(vbeta*Misc[i][1] + l[i])))); - else - EA_2 = alphaMBL; // mean load is considered to be 0 in this case. The second term in the above equation is not valid for delta_L1 < 0. - - - } else if (ElasticMod == 2) { - // constant dynamic stiffness - EA_2 = EA_D; - } - - if (EA_2 == 0.0) { // Make sure EA != EA_D or else nans, also make sure EA_D != 0 or else nans. - LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal zero" << endl; - throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal zero"); - } else if (EA_2 == EA) { - LOGERR << "Viscoelastic model: Dynamic stiffness cannot equal static stiffness" << endl; - throw moordyn::invalid_value_error("Viscoelastic model: Dynamic stiffness cannot equal static stiffness"); - } - - const double EA_1 = EA_2*EA/(EA_2 - EA); // calculated EA_1 which is the stiffness in series with EA_D that will result in the desired static stiffness of EA_S. - - const double dl = lstr[i] - l[i]; // delta l of this segment - - const double ld_1 = (EA_2*dl - (EA_2 + EA_1)*Misc[i][1] + BA_D*ldstr[i]) /( BA_D + BA); // rate of change of static stiffness portion [m/s] - - if (dl >= 0.0) // if both spring 1 (the spring dashpot in parallel) and the whole segment are not in compression - T[i] = (EA_1*Misc[i][1] / l[i]) * qs[i]; // compute tension based on static portion (dynamic portion would give same). See eqn. 14 in paper - else - T[i] = vec::Zero(); // cable can't "push" - - Td[i] = BA*ld_1 / l[i] * qs[i]; - // update state derivative for static stiffness stretch (last N entries in the state vector) - Miscd[i][1] = ld_1; - } - } + // ============ CALCULATE FORCES ON EACH NODE =============================== // Bending loads // first zero out the forces from last run @@ -1216,19 +1195,18 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector& vel, std::vector& acc, std::vector= t_old + dtm) || (t == 0.0)) { // Update the stormed RMS vaues // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. @@ -1256,53 +1234,39 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector 20) && (t < 20.001)){ - // if ((t >= t_old + dtm) || (t == 0.0)) cout << "----- new time " << t << "-----" << endl; - // // cout << "yd: " << yd << endl; - // // cout << "ydd: " << ydd << endl; - // // cout << "ydd via rdd_old: " << rdd_old[i].dot(q[i].cross(vp.normalized())) << endl; - // cout << "phi_yd: " << phi_yd << endl; - // } - // Note: amplitude calculations and states commented out. Would be needed if a Cl vs A lookup table was ever implemented - const moordyn::real phi = Misc[i][0] - (2 * pi * floor(Misc[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi - // const moordyn::real A_int = Misc[i][1]; - // const moordyn::real As = Misc[i][2]; + const real phi = Misc[i][0] - (2 * pi * floor(Misc[i][0] / (2*pi))); // Map integrated phase to 0-2Pi range. Is this necessary? sin (a-b) is the same if b is 100 pi or 2pi + // const real A_int = Misc[i][1]; + // const real As = Misc[i][2]; // non-dimensional frequency - const moordyn::real f_hat = cF + dF *sin(phi_yd - phi); // phi is integrated from state deriv phi_dot + const real f_hat = cF + dF *sin(phi_yd - phi); // phi is integrated from state deriv phi_dot // frequency of lift force (rad/s) - const moordyn::real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state + const real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state // ----- The rest of the model ----- // // Oscillation amplitude - // const moordyn::real A_int_dot = abs(yd); + // const real A_int_dot = abs(yd); // // Note: Check if this actually measures zero crossings // if ((yd * yd_old[i]) < 0) { // if sign changed, i.e. a zero crossing // Amp[i] = A_int-A_int_old[i]; // amplitude calculation since last zero crossing // A_int_old[i] = A_int; // stores amplitude of previous zero crossing for finding Amp // } // // Careful with integrating smoothed amplitude, as 0.1 was a calibarated value based on a very simple integration method - // const moordyn::real As_dot = (0.1/dtm)*(Amp[i]-As); // As to be variable integrated from the state. stands for amplitude smoothed + // const real As_dot = (0.1/dtm)*(Amp[i]-As); // As to be variable integrated from the state. stands for amplitude smoothed // // Lift coefficient from lookup table - // const moordyn::real C_l = cl_lookup(x = As/d); // create function in Line.hpp that uses lookup table + // const real C_l = cl_lookup(x = As/d); // create function in Line.hpp that uses lookup table // The Lift force - if (i == 0) - Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i]); - else if (i == N) - Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i - 1] * l[i - 1]); - else - Lf[i] = 0.25 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * (F[i] * l[i] + F[i - 1] * l[i - 1]); + Lf[i] = 0.5 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * submerged_length; // Prep for returning VIV state derivatives Miscd[i][0] = phi_dot; @@ -1385,7 +1349,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme) t_old = t; // for updating back indexing if statements } - rdd_old = a; // saving the acceleration for VIV RMS calculation + rdd_old = acc; // saving the acceleration for VIV RMS calculation }; diff --git a/source/Line.hpp b/source/Line.hpp index 0198459a..8be46daf 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -143,13 +143,16 @@ class Line final : public io::IO, public NatFreqCFL /// Elasticity model flag unsigned int ElasticMod; /// line normal/static elasticity modulus (Young's modulus) [Pa] - moordyn::real EA; - /// line dynamic stiffness modulus * area for viscoelastic stuff + moordyn::real EA; // TODO: units + /// constant line dynamic stiffness modulus * area for viscoelastic stuff moordyn::real EA_D; /// Alpha * MBL in load dependent dynamic stiffness equation Kd = Alpha * MBL + vbeta * Lm for viscoelastic model moordyn::real alphaMBL; /// beta in load dependent dynamic stiffness equation Kd = Alpha * MBL + vbeta * Lm for viscoelastic model moordyn::real vbeta; + /// stiffness of spring 2 in viscoelastic model (dynamic stiffness). This is the spring in series with the parallel spring-dashpot. + /// if ElasticMod = 2, EA_2 = EA_D. If ElasticMod = 3, EA_2 is load dependent dynamic stiffness. + moordyn::real EA_2; /// line bending stiffness [Nm^2] moordyn::real EI; /** line axial internal damping coefficient [Pa-s] @@ -184,6 +187,8 @@ class Line final : public io::IO, public NatFreqCFL /// Center VIV synchronization [-] /// in non-dimensional frequency moordyn::real cF; + /// The crossflow motion phase [-] + real phi_yd; /// line axial internal damping coefficient (before proceessing) [Ns] moordyn::real BAin; diff --git a/source/State.hpp b/source/State.hpp index b1f69d52..2d0f6ec7 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -462,6 +462,19 @@ butcher_row(MoorDynState& out_state, } } + for (unsigned int miscIdx = 0; miscIdx < out_state.misc.size(); + miscIdx++) { + auto& misc = out_state.misc[miscIdx]; + for (unsigned int i = 0; i < misc.pos.size(); i++) { + misc.pos[i] = start_state.misc[miscIdx].pos[i]; + misc.vel[i] = start_state.misc[miscIdx].vel[i]; + for (unsigned int j = 0; j < N; j++) { + misc.pos[i] += scales[j] * derivs[j]->misc[miscIdx].vel[i]; + misc.vel[i] += scales[j] * derivs[j]->misc[miscIdx].acc[i]; + } + } + } + for (unsigned int pointIdx = 0; pointIdx < out_state.points.size(); pointIdx++) { auto& point = out_state.points[pointIdx]; From 0cbabea241ae2531ea129ea4d544c6f9d3d890de Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 14 Jan 2025 10:19:20 -0700 Subject: [PATCH 144/145] fix: comment out include random --- source/Line.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Line.cpp b/source/Line.cpp index 5d7362ac..7484e8ba 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -34,7 +34,7 @@ #include "QSlines.hpp" #include "Util/Interp.hpp" #include -#include +// #include #ifdef USE_VTK #include "Util/VTK_Util.hpp" From f9dde93bf0c9d0f5dc171d1f9354d98ae2538e6e Mon Sep 17 00:00:00 2001 From: RyanDavies19 Date: Tue, 25 Feb 2025 14:08:53 -0700 Subject: [PATCH 145/145] fix: update docs with minor clarifications, move VIV model to internal nodes only --- docs/inputs.rst | 18 ++++++++++++------ docs/waterkinematics.rst | 4 ++++ source/Line.cpp | 24 ++++++++++++++++++------ source/Line.hpp | 16 +++++++++------- source/MoorDyn2.cpp | 2 +- 5 files changed, 44 insertions(+), 20 deletions(-) diff --git a/docs/inputs.rst b/docs/inputs.rst index ba40a371..3289ed55 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -297,7 +297,8 @@ The columns in order are as follows: - CaAx – tangential added mass coefficient (with respect to line displacement) - Cl – OPTIONAL - the crossflow VIV lift coefficient. If set to 0, then VIV calculations are disabled for the line. This coefficient has been made backwards compatible. If it is not provided, then it is - assumed to be 0.0. The theory of vortex induced vibrations can be found :ref:`here ` + assumed to be 0.0. The theory of vortex induced vibrations can be found :ref:`here `. Note that VIV is disabled + for end nodes (and thus end half-segments), so if simulating VIV users should ensure to include a higher number of segments. - dF - OPTIONAL - the cF +- range of non-dimensional frequnecies 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 @@ -319,14 +320,16 @@ 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 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. Example inputs are below: +`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 +needs to be input as a value. Example inputs are below: .. code-block:: none - TypeName Diam Mass/m EA - (name) (m) (kg/m) (N) - Polyester ... ... EA_s|EA_d <-- Constant dynamic stiffness method - Polyester ... ... EA_s|EA_Dc|EA_D_Lm <-- Load dependent dynamic stiffness method + TypeName Diam Mass/m EA BA + (name) (m) (kg/m) (N) (N-s) + Polyester ... ... EA_s|EA_d BA_s|BA_d <-- Constant dynamic stiffness method with static and dynamic damping + Polyester ... ... EA_s|EA_Dc|EA_D_Lm BA_s|BA_d <-- Load dependent dynamic stiffness method with static and dynamic damping Rod Types ^^^^^^^^^ @@ -730,6 +733,9 @@ The following options from MoorDyn-F are not supported by MoorDyn-C: 1: yes, 2: yes with ramp to inertialF_rampT] - inertialF_rampT (30.0): Ramp time for inertial forces to reduce coupled object instability (s). This is ignored unless inertialF = 2 + - OutSwitch (1): Switch to disable outputs when running with full OpenFAST simulations, where the + MoorDyn-F output channels are written to the main FAST output file. + 0: no MD main outfile, 1: write MD main outfile Outputs ^^^^^^^ diff --git a/docs/waterkinematics.rst b/docs/waterkinematics.rst index fd6203dd..74d0468d 100644 --- a/docs/waterkinematics.rst +++ b/docs/waterkinematics.rst @@ -346,6 +346,10 @@ and z = -10 are calculated by interpolating between the neighboring values. For example, the current at point ``(10, -6, -5.5)`` would be ``(0.65, 0.0, 0.0)`` +.. note:: + When using steady currents, CdScaleIC for the initialization should be set to a smaller value (1-2) to + avoid initial transients in the simulation. Unlike waves, currents are included in dynamic relaxation. + .. code-block:: --------------------- MoorDyn steady currents File ---------------------------------- diff --git a/source/Line.cpp b/source/Line.cpp index 7484e8ba..924fda67 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -141,7 +141,7 @@ Line::setup(int number_in, // assign number of nodes to line N = NumSegs; // save the moordyn internal timestep - dtm = dtM0; + dtm0 = dtM0; // store passed line properties (and convert to numbers) d = props->d; @@ -1222,13 +1222,13 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector= t_old + dtm) || (t == 0.0)) { // Update the stormed RMS vaues + if ((t >= t_old + dtm0) || (t == 0.0)) { // Update the stormed RMS vaues // update back indexing one moordyn time step (regardless of time integration scheme). T_old is handled at end of getStateDeriv when rdd_old is updated. yd_rms_old[i] = yd_rms; // for rms back indexing (one moordyn timestep back) ydd_rms_old[i] = ydd_rms; // for rms back indexing (one moordyn timestep back) @@ -1266,7 +1266,12 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vectorrho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * submerged_length; + if (i == 0) // Disable for end nodes for now, node acceleration needed for synch model + Lf[i] = vec::Zero(); + else if (i==N) // Disable for end nodes for now, node acceleration needed for synch model + Lf[i] = vec::Zero(); + else + Lf[i] = 0.5 * env->rho_w * d * vp_mag * Cl * cos(phi) * q[i].cross(vp) * submerged_length; // Prep for returning VIV state derivatives Miscd[i][0] = phi_dot; @@ -1344,13 +1349,20 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector 0) rdd_old[i] = acc[i - 1]; // saving the acceleration for VIV RMS calculation. End nodes are left at zero, VIV disabled for end nodes } - if ((t >= t_old + dtm) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme) + if ((t >= t_old + dtm0) || (t == 0.0)) { // update back indexing one moordyn time step (regardless of time integration scheme) t_old = t; // for updating back indexing if statements } - rdd_old = acc; // saving the acceleration for VIV RMS calculation + // if (t <0.5+dtm && t >0.5-dtm && not IC_gen) { + // cout << "rdd_old at t = " << t << endl; + // for (int i = 0; i < 4; i++) cout << "I = " << i << " rdd_old = " << rdd_old[i][0] << ", " << rdd_old[i][1] << ", " << rdd_old[i][2] < Miscd; /// Num timesteps for rolling RMS of crossflow velocity phase const unsigned int n_m = 500; + /// The crossflow motion phase [-] + real phi_yd; // back indexing one dtm for VIV /// old t @@ -565,7 +565,9 @@ class Line final : public io::IO, public NatFreqCFL * * If it is an inner node, the average of the * tension at the surrounding segments is provided. If the node is a - * line-end, the associated ending segment tension is provided + * line-end, the associated ending segment tension is provided. This + * does not account for the direction of pull. In the calculation of + * Fnet for the node, the direction of pull is accounted for. * @param i The line node index * @return The tension * @throws invalid_value_error If the node index \p i is bigger than the @@ -578,11 +580,11 @@ class Line final : public io::IO, public NatFreqCFL << ", which only has " << N + 1 << " nodes" << std::endl; throw moordyn::invalid_value_error("Invalid node index"); } - if (i == 0) + if (i == 0) // bottom node, return ten and damping of bottom section return T[0] + Td[0]; - else if (i == N) + else if (i == N) // top node, return ten and damping of top section return T[N - 1] + Td[N - 1]; - // take average of tension in adjacent segments + // internal node, take average of tension in adjacent segments. return (0.5 * (T[i] + T[i - 1] + Td[i] + Td[i - 1])); }; diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 3f0231be..57c70291 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -2303,7 +2303,7 @@ moordyn::MoorDyn::checkNumberOfEntriesInLine(vector entries, { if ((int)entries.size() < supposedNumberOfEntries) { LOGERR << "Error in " << _filepath << ":" << endl - << supposedNumberOfEntries << " fields are required, but just " + << supposedNumberOfEntries << " fields minimum are required, but just " << entries.size() << " are provided" << endl; return false; }