diff --git a/bench/CMakeLists.txt b/bench/CMakeLists.txt index 077c252f..40183ca5 100644 --- a/bench/CMakeLists.txt +++ b/bench/CMakeLists.txt @@ -22,6 +22,7 @@ endfunction() add_bench(WaveBenchmark WaveBench.cpp) add_bench(MoordynBenchmark MDBench.cpp) +add_bench(LinesBenchmark LinesBench.cpp) add_custom_target(run_benchmarks COMMAND $ diff --git a/bench/LinesBench.cpp b/bench/LinesBench.cpp new file mode 100644 index 00000000..4e99f5e5 --- /dev/null +++ b/bench/LinesBench.cpp @@ -0,0 +1,67 @@ +#include "LinesBench.hpp" +#include "Time.hpp" +#include +#include + +/** + * @brief Benchmarks stepping the model 0.1s + * Loads the given model file and measures the duration + * to complete an 0.1 second outer time step. + * @param state Benchmark state + * @param tScheme name of integrator to use + */ +static void +MoorDynStepWithIntegrator(benchmark::State& state, const std::string& tScheme) +{ + int num_lines = state.range(0); + int num_segments = state.range(1); + std::string input_file = "Mooring/cases/" + std::to_string(num_lines) + + "_lines_" + std::to_string(num_segments) + + "_segs/lines.txt"; + moordyn::MoorDyn system(input_file.c_str(), MOORDYN_NO_OUTPUT); + system.SetDisableOutput(true); + + // Don't have to free this pointer because it's done by the MoorDyn system. + moordyn::TimeScheme* timeScheme = moordyn::create_time_scheme( + tScheme, system.GetLogger(), system.GetWaves()); + system.SetTimeScheme(timeScheme); + + // int err; + unsigned int n_dof; + n_dof = system.NCoupledDOF(); + double *x = NULL, *dx = NULL; + if (n_dof) { + x = new double[n_dof]; + std::fill(x, x + n_dof, 0.0); + dx = new double[n_dof]; + std::fill(dx, dx + n_dof, 0.0); + } + system.Init(x, dx, true); + + double t = 0.0, dt = 0.01; + double f[3]; + + for (auto _ : state) { + system.Step(x, dx, f, t, dt); + } + state.counters["OuterTimeStep"] = dt; +} +static void +MoordynStepCaseRK4(benchmark::State& state) +{ + MoorDynStepWithIntegrator(state, "RK4"); +} +BENCHMARK(MoordynStepCaseRK4) + ->ArgsProduct({ { 1, 2, 4, 8, 16, 32, 64 }, { 1, 2, 4, 8, 16, 32, 64 } }) + ->Unit(benchmark::kMicrosecond); + +static void +MoordynStepCaseRK2(benchmark::State& state) +{ + MoorDynStepWithIntegrator(state, "RK2"); +} +BENCHMARK(MoordynStepCaseRK2) + ->ArgsProduct({ { 1, 2, 4, 8, 16, 32, 64 }, { 1, 2, 4, 8, 16, 32, 64 } }) + ->Unit(benchmark::kMicrosecond); + +BENCHMARK_MAIN(); diff --git a/bench/LinesBench.hpp b/bench/LinesBench.hpp new file mode 100644 index 00000000..4bd7d6fd --- /dev/null +++ b/bench/LinesBench.hpp @@ -0,0 +1,11 @@ + +#pragma once + +#define _USE_MATH_DEFINES +#include "MoorDyn.h" +#include "MoorDyn2.hpp" +#include "Waves.hpp" +#include "Waves/SpectrumKin.hpp" + +#include +#include diff --git a/bench/MDBench.cpp b/bench/MDBench.cpp index dcb1f54a..e9094f05 100644 --- a/bench/MDBench.cpp +++ b/bench/MDBench.cpp @@ -21,8 +21,10 @@ LineGetStateDeriv(benchmark::State& state, std::string input_file) auto line = system.GetLines().front(); + std::vector vel{}; + std::vector acc{}; for (auto _ : state) { - line->getStateDeriv(); + line->getStateDeriv(vel, acc); } } BENCHMARK_CAPTURE(LineGetStateDeriv, diff --git a/bench/Mooring/cases/.gitignore b/bench/Mooring/cases/.gitignore new file mode 100644 index 00000000..7fcf08e2 --- /dev/null +++ b/bench/Mooring/cases/.gitignore @@ -0,0 +1 @@ +lines.txt \ No newline at end of file diff --git a/bench/Mooring/cases/generate_cases.py b/bench/Mooring/cases/generate_cases.py new file mode 100644 index 00000000..5f4466ce --- /dev/null +++ b/bench/Mooring/cases/generate_cases.py @@ -0,0 +1,92 @@ +from itertools import product +import os +from dataclasses import dataclass + +"""Simple script for generating a bunch of model files for benchmarking purposes. + +Just needs basic python (tested for version >=3.8). +""" + + +@dataclass +class BenchmarkParams: + num_lines: int + num_segments: int + + +def generate_benchmark(base_output_folder, params: BenchmarkParams): + """Generate a single benchmark model file. + + The model has a user defined number of lines that each share a fixed top + point, and have their own bottom point. + They start off at a 10 degree angle from vertical. + """ + points = "\n".join( + f"{i + 2} free 34.20201433256687 0.0 -93.96926207859084 0 0 0 0 -" + for i in range(params.num_lines) + ) + line_length = 100.0 + lines = "\n".join( + f"{i+1} chain 1 {i + 2} {line_length} {params.num_segments} p,t" + for i in range(params.num_lines) + ) + + file_str = f"""--------------------- MoorDyn Input File ------------------------------------------------------- +Output from generate_cases.py +----------------------- 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 16000000.0 -0.3 0.0 1.37 0.64 1.0 0.0 +----------------------- POINTS ------------------------------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 free 0.0 0.0 0.0 0 0 0 0 - +{points} +-------------------------- LINES ----------------------------------------------------------------- +Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs +(-) (-) (-) (-) (m) (-) (-) +{lines} +-------------------------- SOLVER OPTIONS--------------------------- +0 writeLog - Write a log file +0.001 dtM - time step to use in mooring integration +rk4 tScheme +3000000.0 kb - bottom stiffness +300000.0 cb - bottom damping +200.0 WtrDpth - water depth +4.0 ICDfac - factor to scale drag coeff during IC +1.5e-06 threshIC - threshold for IC convergence +0.0 TmaxIC - threshold for IC convergence +1e-05 dtIC - Time lapse between convergence tests (s) +9.81 g - gravitational force constant +1025 rho - water density +0 WaveKin - waves mode +0 Currents - current mode +------------------------- need this line -------------------------------------- +""" + + folder_name = f"{params.num_lines}_lines_{params.num_segments}_segs" + + output_folder = os.path.join(base_output_folder, folder_name) + try: + os.mkdir(output_folder) + except FileExistsError: + pass + + out_path = os.path.join(output_folder, "lines.txt") + + with open(out_path, "w") as f: + f.write(file_str) + + +def main(): + + number_of_lines = [2**n for n in range(7)] + number_of_segments = [2**n for n in range(7)] + + for vals in product(number_of_lines, number_of_segments): + params = BenchmarkParams(*vals) + generate_benchmark("./", params) + + +if __name__ == "__main__": + main() diff --git a/docs/inputs.rst b/docs/inputs.rst index d977a1f4..10863914 100644 --- a/docs/inputs.rst +++ b/docs/inputs.rst @@ -595,6 +595,8 @@ The list of possible options is: 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. + - disableOutput (0): Disables some console and file outputs to improve runtime. + - disableOutTime (0): Disables the printing of the current timestep to the console, useful for the MATLAB wrapper 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 @@ -629,6 +631,8 @@ The following MoorDyn-C options are not supported by MoorDyn-F: - 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 + - disableOutput: MoorDyn-F output verbosity is controlled by OpenFAST + - disableOutTime: MoorDyn-F output verbosity is controlled by OpenFAST The following options from MoorDyn-F are not supported by MoorDyn-C: diff --git a/source/Line.cpp b/source/Line.cpp index 75b9f3a9..547919cc 100644 --- a/source/Line.cpp +++ b/source/Line.cpp @@ -666,7 +666,7 @@ Line::setPin(std::vector p) } void -Line::setState(std::vector pos, std::vector vel) +Line::setState(const std::vector& pos, const std::vector& vel) { if ((pos.size() != N - 1) || (vel.size() != N - 1)) { LOGERR << "Invalid input size" << endl; @@ -674,10 +674,8 @@ Line::setState(std::vector pos, std::vector vel) } // 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]; - } + std::copy(pos.begin(), pos.end(), r.begin() + 1); + std::copy(vel.begin(), vel.end(), rd.begin() + 1); } void @@ -769,8 +767,8 @@ Line::getEndSegmentMoment(EndPoints end_point, EndPoints rod_end_point) const return qEnd * EIEnd / dlEnd; } -std::pair, std::vector> -Line::getStateDeriv() +void +Line::getStateDeriv(std::vector& vel, std::vector& acc) { // NOTE: // Jose Luis Cercos-Pita: This is by far the most consuming function of the @@ -802,6 +800,22 @@ Line::getStateDeriv() ldstr[i] = qs[i].dot(rd[i + 1] - rd[i]); // strain rate of segment // V[i] = A * l[i]; // volume attributed to segment + + if (nEApoints) + E = getNonlinearE(lstr[i], l[i]); + + if (lstr[i] > 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 unit tangent vectors (q) for each internal node. note: I've @@ -876,51 +890,9 @@ Line::getStateDeriv() } //============================================================================================ - // calculate mass matrix - for (unsigned int i = 0; i <= N; i++) { - real m_i; // node mass - real v_i; // node submerged volume - - if (i == 0) { - m_i = pi / 8. * d * d * l[0] * rho; - v_i = 0.5 * F[0] * V[0]; - } else if (i == N) { - m_i = pi / 8. * d * d * l[N - 1] * rho; - v_i = 0.5 * F[i - 1] * V[i - 1]; - } else { - m_i = pi / 8. * (d * d * rho * (l[i] + l[i - 1])); - v_i = 0.5 * (F[i - 1] * V[i - 1] + F[i] * V[i]); - } - - // Make node mass matrix - const mat I = mat::Identity(); - const mat Q = q[i] * q[i].transpose(); - M[i] = m_i * I + env->rho_w * v_i * (Can * (I - Q) + Cat * Q); - } - // ============ CALCULATE FORCES ON EACH NODE // =============================== - // loop through the segments - for (unsigned int i = 0; i < N; i++) { - // line tension - if (nEApoints > 0) - E = getNonlinearE(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(); - } - - // line internal damping force - if (nCpoints > 0) - c = getNonlinearC(ldstr[i], l[i]); - Td[i] = c * A * ldstr[i] / l[i] * qs[i]; - } - // Bending loads // first zero out the forces from last run for (unsigned int i = 0; i <= N; i++) { @@ -1092,95 +1064,76 @@ Line::getStateDeriv() } } + // This mostly just simplifies the code, but also sometimes helps the + // compiler avoid repeated pointer lookup. + const real rho_w = env->rho_w; + const real g = env->g; + // loop through the nodes for (unsigned int i = 0; i <= N; i++) { - W[i][0] = W[i][1] = 0.0; + // Nodes are considered to have a line length of half the length of the + // line on either side. + const real length_left = i == 0 ? 0.0 : l[i - 1]; + const real length_right = i == N ? 0.0 : l[i]; + const real length = 0.5 * (length_left + length_right); + const real submergence_left = i == 0 ? 0.0 : F[i - 1]; + const real submergence_right = i == N ? 0.0 : F[i]; + // Submerged length is half the submerged length of the neighboring + // segments + const real submerged_length = 0.5 * (length_left * submergence_left + + length_right * submergence_right); + + const real submerged_volume = submerged_length * A; + + const real m_i = A * length * rho; // node mass + const real v_i = submerged_volume; // node submerged volume + + // Make node mass matrix + const mat I = mat::Identity(); + const mat Q = q[i] * q[i].transpose(); + // calculate mass matrix + M[i] = m_i * I + rho_w * v_i * (Can * (I - Q) + Cat * Q); + // submerged weight (including buoyancy) - if (i == 0) - W[i][2] = 0.5 * A * (l[i] * (rho - F[i] * env->rho_w)) * (-env->g); - else if (i == N) - W[i][2] = 0.5 * A * (l[i - 1] * (rho - F[i - 1] * env->rho_w)) * - (-env->g); // missing the "W[i][2] =" previously! - else - W[i][2] = 0.5 * A * - (l[i] * (rho - F[i] * env->rho_w) + - l[i - 1] * (rho - F[i - 1] * env->rho_w)) * - (-env->g); + W[i][0] = W[i][1] = 0.0; + W[i][2] = -g * (m_i - v_i * rho_w); // 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 real vql = vi.dot(q[i]); const vec vq = vql * q[i]; // transverse relative flow component const vec vp = vi - vq; - const moordyn::real vq_mag = vq.norm(); - const moordyn::real vp_mag = vp.norm(); + const real vq_mag = vq.norm(); + const real vp_mag = vp.norm(); + const real shared_part = 0.5 * rho_w * d * submerged_length; // transverse drag - if (i == 0) - Dp[i] = 0.25 * vp_mag * env->rho_w * Cdn * d * (F[i] * l[i]) * vp; - else if (i == N) - Dp[i] = 0.25 * vp_mag * env->rho_w * Cdn * d * - (F[i - 1] * l[i - 1]) * vp; - else - Dp[i] = 0.25 * vp_mag * env->rho_w * Cdn * d * - (F[i] * l[i] + F[i - 1] * l[i - 1]) * vp; - + Dp[i] = vp_mag * Cdn * shared_part * vp; // tangential drag - if (i == 0) - Dq[i] = - 0.25 * vq_mag * env->rho_w * Cdt * pi * d * (F[i] * l[i]) * vq; - else if (i == N) - Dq[i] = 0.25 * vq_mag * env->rho_w * Cdt * pi * d * - (F[i - 1] * l[i - 1]) * vq; - else - Dq[i] = 0.25 * vq_mag * env->rho_w * Cdt * pi * d * - (F[i] * l[i] + F[i - 1] * l[i - 1]) * vq; + Dq[i] = vq_mag * Cdt * pi * shared_part * vq; - // tangential component of fluid acceleration // <<<<<<< check sign since I've reversed q - const moordyn::real aql = Ud[i].dot(q[i]); + const real aql = Ud[i].dot(q[i]); const vec aq = aql * q[i]; // normal component of fluid acceleration const vec ap = Ud[i] - aq; // transverse Froude-Krylov force - if (i == 0) - Ap[i] = env->rho_w * (1. + Can) * 0.5 * (F[i] * V[i]) * ap; - else if (i == N) - Ap[i] = env->rho_w * (1. + Can) * 0.5 * (F[i - 1] * V[i - 1]) * ap; - else - Ap[i] = env->rho_w * (1. + Can) * 0.5 * - (F[i] * V[i] + F[i - 1] * V[i - 1]) * ap; + Ap[i] = rho_w * (1. + Can) * submerged_volume * ap; // tangential Froude-Krylov force - if (i == 0) - Aq[i] = env->rho_w * (1. + Cat) * 0.5 * (F[i] * V[i]) * aq; - else if (i == N) - Aq[i] = env->rho_w * (1. + Cat) * 0.5 * (F[i - 1] * V[i - 1]) * aq; - else - Aq[i] = env->rho_w * (1. + Cat) * 0.5 * - (F[i] * V[i] + F[i - 1] * V[i - 1]) * aq; + Aq[i] = rho_w * (1. + Cat) * submerged_volume * aq; // bottom contact (stiffness and damping, vertical-only for now) - // updated for general case of potentially anchor or fairlead end in // contact const real waterDepth = getWaterDepth(r[i][0], r[i][1]); if (r[i][2] < waterDepth) { - if (i == 0) - B[i][2] = - ((waterDepth - r[i][2]) * env->kb - rd[i][2] * env->cb) * - 0.5 * d * (l[i]); - else if (i == N) - B[i][2] = - ((waterDepth - r[i][2]) * env->kb - rd[i][2] * env->cb) * - 0.5 * d * (l[i - 1]); - else - B[i][2] = - ((waterDepth - r[i][2]) * env->kb - rd[i][2] * env->cb) * - 0.5 * d * (l[i - 1] + l[i]); + B[i][2] = ((waterDepth - r[i][2]) * env->kb - rd[i][2] * env->cb) * + d * (length); // new rough-draft addition of seabed friction real FrictionMax = @@ -1223,44 +1176,16 @@ Line::getStateDeriv() Bs[i] + Pb[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); - a.reserve(N - 1); + vel.reserve(N - 1); + acc.reserve(N - 1); for (unsigned int i = 1; i < N; i++) { - // double M_out[9]; - // double F_out[3]; - // for (int I=0; I<3; I++) - // { F_out[I] = Fnet[i][I]; - // for (int J=0; J<3; J++) M_out[3*I + J] = M[i][I][J]; - // } - - // solve for accelerations in [M]{a}={f} using LU decomposition - // double LU[9]; // serialized matrix that will - // hold LU matrices combined Crout(3, M_out, LU); // - // perform LU decomposition on mass matrix double acc[3]; // - // acceleration vector to solve for solveCrout(3, LU, F_out, acc); - // // solve for acceleration vector - - // LUsolve3(M[i], acc, Fnet[i]); - - // Solve3(M[i], acc, (const double*)Fnet[i]); - // For small systems it is usually faster to compute the inverse // of the matrix. See // https://eigen.tuxfamily.org/dox/group__TutorialLinearAlgebra.html - a.push_back(M[i].inverse() * Fnet[i]); - u.push_back(rd[i]); + acc[i - 1] = M[i].inverse() * Fnet[i]; + vel[i - 1] = rd[i]; } - - return make_pair(u, a); }; // write output file for line (accepts time parameter since retained time value diff --git a/source/Line.hpp b/source/Line.hpp index 608a6934..fdfdf13a 100644 --- a/source/Line.hpp +++ b/source/Line.hpp @@ -816,7 +816,7 @@ class Line final : public io::IO, public NatFreqCFL * @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(const std::vector& r, const std::vector& u); /** @brief Set the position and velocity of an end point * @param r Position @@ -856,11 +856,11 @@ class Line final : public io::IO, public NatFreqCFL vec getEndSegmentMoment(EndPoints end_point, EndPoints rod_end_point) const; /** @brief Calculate forces and get the derivative of the line's states - * @return The velocities of the internal nodes (first) and the accelerations - * of the internal nodes (second) + * @param vel Where to store the velocities of the internal nodes + * @param acc Where to store the accelerations of the internal nodes * @throws nan_error If nan values are detected in any node position */ - std::pair, std::vector> getStateDeriv(); + void getStateDeriv(std::vector& vel, std::vector& acc); // void initiateStep(vector &rFairIn, vector &rdFairIn, // double time); diff --git a/source/MoorDyn2.cpp b/source/MoorDyn2.cpp index 6e6fc62c..c7acceee 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -635,12 +635,14 @@ moordyn::MoorDyn::Step(const double* x, double& dt) { // should check if wave kinematics have been set up if expected! - const auto default_precision{std::cout.precision()}; - std::cout << std::fixed << setprecision(1); - LOGDBG << "t = " << t << "s \r"; - std::cout << std::defaultfloat << setprecision(default_precision); + if (!disableOutput) { + const auto default_precision{ std::cout.precision() }; + std::cout << std::fixed << setprecision(1); + LOGDBG << "t = " << t << "s \r"; + std::cout << std::defaultfloat << setprecision(default_precision); - cout << "\rt = " << t << " " << flush; + if (!disableOutTime) cout << "\rt = " << t << " " << flush; + } if (dt <= 0) { // Nothing to do, just recover the forces if there are coupled DOFs @@ -2126,23 +2128,23 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) LOGDBG << "\t" << entries[1] << " = " << entries[0] << endl; const string value = entries[0]; - const string name = entries[1]; + const string name = str::lower(entries[1]); // 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") { + if ((name == "dtm") || (name == "dt")) + dtM0 = atof(value.c_str()); + else if (name == "cfl") + cfl = atof(value.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 // Unrecognized option writeLog - // env->writeLog = atoi(entries[0].c_str()); - } else if (name == "tScheme") { + // env->writeLog = atoi(value.c_str()); + } else if (name == "tscheme") { moordyn::error_id err = MOORDYN_SUCCESS; string err_msg; try { - _t_integrator = create_time_scheme(entries[0], _log, waves); + _t_integrator = create_time_scheme(value, _log, waves); } MOORDYN_CATCHER(err, err_msg); if (err != MOORDYN_SUCCESS) { @@ -2150,67 +2152,84 @@ moordyn::MoorDyn::readOptionsLine(vector& in_txt, int i) LOGERR << err_msg << endl; } } else if ((name == "g") || (name == "gravity")) - env->g = atof(entries[0].c_str()); - else if ((name == "Rho") || (name == "rho") || (name == "WtrDnsty")) - env->rho_w = atof(entries[0].c_str()); - else if (name == "WtrDpth") - env->WtrDpth = atof(entries[0].c_str()); - else if ((name == "kBot") || (name == "kbot") || (name == "kb")) - env->kb = atof(entries[0].c_str()); - 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()); - else if ((name == "TmaxIC") || (name == "ICTmax")) - ICTmax = atof(entries[0].c_str()); - else if ((name == "CdScaleIC") || (name == "ICDfac")) - ICDfac = atof(entries[0].c_str()); - else if ((name == "threshIC") || (name == "ICthresh")) - ICthresh = atof(entries[0].c_str()); - else if ((name == "genDynamicIC") || (name == "ICgenDynamic")) - ICgenDynamic = bool(atof(entries[0].c_str())); - else if ((name == "fileIC") || (name == "ICfile")) - ICfile = entries[0]; - else if (name == "WaveKin") { - WaveKinTemp = (waves::waves_settings)stoi(entries[0]); + env->g = atof(value.c_str()); + else if ((name == "rho") || (name == "wtrdnsty")) + env->rho_w = atof(value.c_str()); + else if (name == "wtrdpth") + env->WtrDpth = atof(value.c_str()); + else if ((name == "kbot") || (name == "kb")) + env->kb = atof(value.c_str()); + else if ((name == "cbot") || (name == "cb")) + env->cb = atof(value.c_str()); + else if ((name == "dtic") || (name == "icdt")) + ICdt = atof(value.c_str()); + else if ((name == "tmaxic") || (name == "ictmax")) + ICTmax = atof(value.c_str()); + else if ((name == "cdscaleic") || (name == "icdfac")) + ICDfac = atof(value.c_str()); + else if ((name == "threshic") || (name == "icthresh")) + ICthresh = atof(value.c_str()); + else if ((name == "gendynamicic") || (name == "icgendynamic")) + ICgenDynamic = bool(atof(value.c_str())); + else if ((name == "fileic") || (name == "icfile")) + ICfile = value; + else if (name == "wavekin") { + WaveKinTemp = (waves::waves_settings)stoi(value); if ((WaveKinTemp < waves::WAVES_NONE) || (WaveKinTemp > waves::WAVES_SUM_COMPONENTS_NODE)) LOGWRN << "Unknown WaveKin option value " << WaveKinTemp << endl; - } else if (name == "dtWave") - env->waterKinOptions.dtWave = stof(entries[0]); - else if (name == "Currents") { - auto current_mode = (waves::currents_settings)stoi(entries[0]); + } else if (name == "dtwave") + env->waterKinOptions.dtWave = stof(value); + else if (name == "currents") { + auto current_mode = (waves::currents_settings)stoi(value); env->waterKinOptions.currentMode = current_mode; if ((current_mode < waves::CURRENTS_NONE) || (current_mode > waves::CURRENTS_4D)) LOGWRN << "Unknown Currents option value " << current_mode << endl; - } else if (name == "UnifyCurrentGrid") { - if (entries[0] == "1") { + } else if (name == "unifycurrentgrid") { + if (value == "1") { env->waterKinOptions.unifyCurrentGrid = true; - } else if (entries[0] == "0") { + } else if (value == "0") { env->waterKinOptions.unifyCurrentGrid = false; } else { LOGWRN << "Unrecognized UnifyCurrentGrid value " - << std::quoted(entries[1]) << ". Should be 0 or 1" << endl; + << std::quoted(value) << ". Should be 0 or 1" << endl; } - } else if (name == "WriteUnits") - env->WriteUnits = atoi(entries[0].c_str()); - else if (name == "FrictionCoefficient") - env->FrictionCoefficient = atof(entries[0].c_str()); - else if (name == "FricDamp") - env->FricDamp = atof(entries[0].c_str()); - else if (name == "StatDynFricScale") - env->StatDynFricScale = atof(entries[0].c_str()); + } else if (name == "writeunits") + env->WriteUnits = atoi(value.c_str()); + else if (name == "frictioncoefficient") + env->FrictionCoefficient = atof(value.c_str()); + else if (name == "fricdamp") + env->FricDamp = atof(value.c_str()); + else if (name == "statdynfricscale") + env->StatDynFricScale = atof(value.c_str()); // output writing period (0 for at every call) - else if (name == "dtOut") - dtOut = atof(entries[0].c_str()); - else if (name == "SeafloorFile") { + else if (name == "dtout") + dtOut = atof(value.c_str()); + else if (name == "seafloorfile") { env->SeafloorMode = seafloor_settings::SEAFLOOR_3D; this->seafloor = make_shared(_log); - std::string filepath = entries[0]; + std::string filepath = value; this->seafloor->setup(env, filepath); - } - else + } else if (name == "disableoutput"){ + if (value == "1") { + disableOutput = true; + } else if (value == "0") { + disableOutput = false; + } else { + LOGWRN << "Unrecognized disableOutput value " + << std::quoted(value) << ". Should be 0 or 1" << endl; + } + } else if (name == "disableouttime"){ + if (value == "1") { + disableOutTime = true; + } else if (value == "0") { + disableOutTime = false; + } else { + LOGWRN << "Unrecognized disableOutTime value " + << std::quoted(value) << ". Should be 0 or 1" << endl; + } + } else LOGWRN << "Warning: Unrecognized option '" << name << "'" << endl; } @@ -2305,6 +2324,8 @@ moordyn::MoorDyn::detachLines(FailProps* failure) moordyn::error_id moordyn::MoorDyn::AllOutput(double t, double dt) { + if (disableOutput) + return MOORDYN_SUCCESS; // if (env->writeLog == 0) // return MOORDYN_SUCCESS; diff --git a/source/MoorDyn2.hpp b/source/MoorDyn2.hpp index eb647582..5ca1aeda 100644 --- a/source/MoorDyn2.hpp +++ b/source/MoorDyn2.hpp @@ -126,6 +126,13 @@ class MoorDyn final : public io::IO */ inline vector GetLines() const { return LineList; } + /** + * @brief Set whether console and file output is disabled. + * + * @param disable + */ + inline void SetDisableOutput(bool disable) { disableOutput = disable; } + /** @brief Return the number of coupled Degrees Of Freedom (DOF) * * This should match with the number of components of the positions and @@ -630,6 +637,12 @@ class MoorDyn final : public io::IO /// (if using env.WaveKin=1) unsigned int npW; + /// Disabled writing to output files or console when running + bool disableOutput = false; + + /// Disabledtime updates to console when running (for MATLAB wrapper) + bool disableOutTime = false; + /// main output file ofstream outfileMain; diff --git a/source/State.hpp b/source/State.hpp index 2799613a..acc735a9 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -50,12 +50,6 @@ template class StateVar { public: - /// @brief Costructor - StateVar() {} - - /// @brief Destructor - ~StateVar() {} - /// The position T pos; /// The velocity @@ -108,12 +102,6 @@ template class StateVarDeriv { public: - /// @brief Constructor - StateVarDeriv() {} - - /// @brief Destructor - ~StateVarDeriv() {} - /// The velocity T vel; /// The acceleration @@ -168,7 +156,7 @@ class StateVarDeriv * @return The module of the linear acceleration, or their sum in case * of lists of accelerations */ - real MakeStationary(const real &dt); + real MakeStationary(const real& dt); /** @brief Carry out a Newmark step * @@ -261,12 +249,6 @@ typedef StateVarDeriv DBodyStateDt; class MoorDynState { public: - /// @brief Constructor - MoorDynState() {} - - /// @brief Destructor - ~MoorDynState() {} - /// The states of the lines std::vector lines; @@ -321,12 +303,6 @@ class MoorDynState class DMoorDynStateDt { public: - /// @brief Constructor - DMoorDynStateDt() {} - - /// @brief Destructor - ~DMoorDynStateDt() {} - /// The state derivatives of the lines std::vector lines; @@ -382,7 +358,7 @@ class DMoorDynStateDt * @param dt Time step. * @return The sum of the linear acceleration norms */ - real MakeStationary(const real &dt); + real MakeStationary(const real& dt); /** @brief Carry out a Newmark step * @@ -442,4 +418,74 @@ class DMoorDynStateDt void Mix(const DMoorDynStateDt& visitor, const real& f); }; +/** + * @brief Do the computation for a row of a Butcher Tableau for an explicit + * integrator + * + * This function unwraps the computation so that is avoids any allocation. + * This function essentially computes: + * out_state = start_state + sum(scales[i] * derivs[i] for i = 1:N) + * + * out_state and start_state can be the same state. + * + * @tparam N Number of columns in the row + * @param out_state Where to save the new state + * @param start_state Starting state + * @param scales Derivative weights, one for each derivative state + * @param derivs State derivative values + */ +template +constexpr void +butcher_row(MoorDynState& out_state, + const MoorDynState& start_state, + const std::array& scales, + const std::array& derivs) +{ + static_assert(N > 0, "butcher_row must have at least one state deriv"); + + for (unsigned int lineIdx = 0; lineIdx < out_state.lines.size(); + lineIdx++) { + auto& line = out_state.lines[lineIdx]; + for (unsigned int i = 0; i < line.pos.size(); i++) { + line.pos[i] = start_state.lines[lineIdx].pos[i]; + line.vel[i] = start_state.lines[lineIdx].vel[i]; + for (unsigned int j = 0; j < N; j++) { + line.pos[i] += scales[j] * derivs[j]->lines[lineIdx].vel[i]; + line.vel[i] += scales[j] * derivs[j]->lines[lineIdx].acc[i]; + } + } + } + + for (unsigned int pointIdx = 0; pointIdx < out_state.points.size(); + pointIdx++) { + auto& point = out_state.points[pointIdx]; + point.pos = start_state.points[pointIdx].pos; + point.vel = start_state.points[pointIdx].vel; + for (unsigned int j = 0; j < N; j++) { + point.pos += scales[j] * derivs[j]->points[pointIdx].vel; + point.vel += scales[j] * derivs[j]->points[pointIdx].acc; + } + } + + for (unsigned int rodIdx = 0; rodIdx < out_state.rods.size(); rodIdx++) { + auto& rod = out_state.rods[rodIdx]; + rod.pos = start_state.rods[rodIdx].pos; + rod.vel = start_state.rods[rodIdx].vel; + for (unsigned int j = 0; j < N; j++) { + rod.pos = rod.pos + derivs[j]->rods[rodIdx].vel * scales[j]; + rod.vel = rod.vel + scales[j] * derivs[j]->rods[rodIdx].acc; + } + } + for (unsigned int bodyIdx = 0; bodyIdx < out_state.bodies.size(); + bodyIdx++) { + auto& body = out_state.bodies[bodyIdx]; + body.pos = start_state.bodies[bodyIdx].pos; + body.vel = start_state.bodies[bodyIdx].vel; + for (unsigned int j = 0; j < N; j++) { + body.pos = body.pos + derivs[j]->bodies[bodyIdx].vel * scales[j]; + body.vel = body.vel + scales[j] * derivs[j]->bodies[bodyIdx].acc; + } + } +} + } // ::moordyn diff --git a/source/Time.cpp b/source/Time.cpp index bf0ef085..ae2c1b8a 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -29,6 +29,7 @@ */ #include "Time.hpp" +#include "State.hpp" #include "Waves.hpp" #include @@ -97,8 +98,8 @@ 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) = - lines[i]->getStateDeriv(); + lines[i]->getStateDeriv(rd[substep].lines[i].vel, + rd[substep].lines[i].acc); } for (unsigned int i = 0; i < points.size(); i++) { @@ -382,11 +383,13 @@ RK2Scheme::Step(real& dt) // Compute the intermediate state CalcStateDeriv(0); t += 0.5 * dt; - r[1] = r[0] + rd[0] * (0.5 * dt); + // r[1] = r[0] + rd[0] * (0.5 * dt); + butcher_row<1>(r[1], r[0], { 0.5 * dt }, { &rd[0] }); Update(0.5 * dt, 1); // And so we can compute the new derivative and apply it CalcStateDeriv(1); - r[0] = r[0] + rd[1] * dt; + // r[0] = r[0] + rd[1] * dt; + butcher_row<1>(r[0], r[0], { dt }, { &rd[1] }); t += 0.5 * dt; Update(dt, 0); TimeSchemeBase::Step(dt); @@ -408,23 +411,35 @@ RK4Scheme::Step(real& dt) // k2 t += 0.5 * dt; - r[1] = r[0] + rd[0] * (0.5 * dt); + // r[1] = r[0] + rd[0] * (0.5 * dt); + butcher_row<1>(r[1], r[0], { 0.5 * dt }, { &rd[0] }); + Update(0.5 * dt, 1); CalcStateDeriv(1); // k3 - r[1] = r[0] + rd[1] * (0.5 * dt); + + // r[1] = r[0] + rd[1] * (0.5 * dt); + butcher_row<1>(r[1], r[0], { 0.5 * dt }, { &rd[1] }); Update(0.5 * dt, 1); CalcStateDeriv(2); // k4 t += 0.5 * dt; - r[2] = r[0] + rd[2] * dt; + + // r[2] = r[0] + rd[2] * dt; + butcher_row<1>(r[2], r[0], { dt }, { &rd[2] }); + Update(dt, 2); CalcStateDeriv(3); // Apply - r[0] = r[0] + (rd[0] + rd[3]) * (dt / 6.0) + (rd[1] + rd[2]) * (dt / 3.0); + // r[0] = r[0] + (rd[0] + rd[3]) * (dt / 6.0) + (rd[1] + rd[2]) * (dt + // / 3.0); + butcher_row<4>(r[0], + r[0], + { dt / 6.0, dt / 3.0, dt / 3.0, dt / 6.0 }, + { &rd[0], &rd[1], &rd[2], &rd[3] }); Update(dt, 0); TimeSchemeBase::Step(dt);