diff --git a/docs/inputs.rst b/docs/inputs.rst index cc1acfea..3289ed55 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). @@ -273,10 +274,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 - (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 + ---------------------- 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: @@ -294,6 +295,14 @@ 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 – 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 `. 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 + 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 @@ -308,17 +317,19 @@ 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: +`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 ^^^^^^^^^ @@ -488,6 +499,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 @@ -660,8 +673,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. @@ -720,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/structure.rst b/docs/structure.rst index d8071043..c4c71d53 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/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 547919cc..924fda67 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" @@ -60,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) { @@ -92,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; @@ -128,7 +129,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; @@ -138,18 +140,28 @@ Line::setup(int number_in, UnstrLend = 0.0; // assign number of nodes to line N = NumSegs; + // save the moordyn internal timestep + dtm0 = dtM0; // store passed line properties (and convert to numbers) 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; Cdt = props->Cdt; + Cl = props->Cl; + dF = props->dF; + cF = props->cF; // copy in nonlinear stress-strain data if applicable stiffXs.clear(); @@ -157,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); @@ -178,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]); } @@ -192,7 +204,10 @@ Line::setup(int number_in, pin.assign(N + 1, 0.0); // Internal pressure at node points (Pa) 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 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 pvec.assign(N + 1, vec::Zero()); // unit normal vectors for each node qs.assign(N, vec::Zero()); // unit tangent vectors for each segment @@ -215,12 +230,19 @@ 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 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_rms_old.assign(N + 1, 0.0); // node old yd_rms + ydd_rms_old.assign(N + 1, 0.0);// node old ydd_rms + // ensure end moments start at zero endMomentA = vec::Zero(); endMomentB = vec::Zero(); @@ -236,23 +258,27 @@ 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 - << " 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 - << " 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 : " << BAin << 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) { @@ -302,6 +328,13 @@ Line::initialize() << i << "Dz \t "; } } + // 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" + << i << "Vz \t "; + } + } // output segment tensions if (channels.find("t") != string::npos) { for (unsigned int i = 1; i <= N; i++) { @@ -370,6 +403,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++) @@ -436,21 +474,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 - << " Ns = " << c * A << " Pa-s, based on input of " << BAin + // 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; } 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 @@ -463,7 +501,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 // Check if the line touches the seabed, so we are modelling it. Just // the end points are checked const real Tol = 1e-5; @@ -497,7 +535,7 @@ Line::initialize() int success = Catenary(XF, ZF, UnstrLen, - E * A, + EA, LW, CB, Tol, @@ -528,12 +566,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 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++) misc[i][0] = phase_range[i]; + } + + LOGMSG << "Initialized Line " << number << endl; + + return std::make_tuple(vector_slice(r, 1, N - 1), vel, misc); }; real @@ -666,16 +714,17 @@ Line::setPin(std::vector p) } void -Line::setState(const std::vector& pos, const std::vector& vel) +Line::setState(const std::vector& pos, const std::vector& vel, const std::vector& misc) { - if ((pos.size() != N - 1) || (vel.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 based on state vector + // set interior node positions and velocities and all misc states based on state vector std::copy(pos.begin(), pos.end(), r.begin() + 1); std::copy(vel.begin(), vel.end(), rd.begin() + 1); + std::copy(misc.begin(), misc.end(), Misc.begin() + 1); // Misc[i][0,1,2] correspond to viv phase, viscoelastic, unused. } void @@ -768,7 +817,7 @@ Line::getEndSegmentMoment(EndPoints end_point, EndPoints rod_end_point) const } void -Line::getStateDeriv(std::vector& vel, std::vector& acc) +Line::getStateDeriv(std::vector& vel, std::vector& acc, std::vector& misc) { // NOTE: // Jose Luis Cercos-Pita: This is by far the most consuming function of the @@ -790,33 +839,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) // dt is possibly used for stability tricks... - // -------------------- calculate various kinematic quantities - // --------------------------- - for (unsigned int i = 0; i < N; i++) { - // calculate current (Stretched) segment lengths and unit tangent - // vectors (qs) for each segment (this is used for bending calculations) - lstr[i] = unitvector(qs[i], r[i], r[i + 1]); - - 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 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 @@ -836,6 +859,77 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) if ((endTypeB == PINNED) || !isEI) unitvector(q[N], r[N - 1], r[N]); + // loop through the segments for stiffness forces and segment lengths + for (unsigned int i = 0; i < N; i++) { + // calculate current (Stretched) segment lengths and unit tangent + // vectors (qs) for each segment (this is used for bending and stiffness calculations) + lstr[i] = unitvector(qs[i], r[i], r[i + 1]); + + ldstr[i] = qs[i].dot(rd[i + 1] - rd[i]); // strain rate of segment + + // V[i] = A * l[i]; // volume attributed to segment + + // Calculate segment stiffness + if (ElasticMod == 1) { + // line tension + if (nEApoints > 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++) { @@ -890,8 +984,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) } //============================================================================================ - // ============ CALCULATE FORCES ON EACH NODE - // =============================== + // ============ CALCULATE FORCES ON EACH NODE =============================== // Bending loads // first zero out the forces from last run @@ -1094,19 +1187,26 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) // calculate mass matrix M[i] = m_i * I + rho_w * v_i * (Can * (I - Q) + Cat * Q); + // submerged weight (including buoyancy) + // submerged weight (including buoyancy) W[i][0] = W[i][1] = 0.0; W[i][2] = -g * (m_i - v_i * rho_w); + + // magnitude of current + const real Ui_mag = U[i].norm(); + // Unit vector of current flow + const vec Ui_hat = U[i].normalized(); // relative flow velocity over node const vec vi = U[i] - rd[i]; // tangential relative flow component - // <<<<<<< check sign since I've reversed q const real vql = vi.dot(q[i]); const vec vq = vql * q[i]; // transverse relative flow component const vec vp = vi - vq; + // magnitudes of relative flow const real vq_mag = vq.norm(); const real vp_mag = vp.norm(); @@ -1116,6 +1216,70 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) // tangential drag Dq[i] = vq_mag * Cdt * pi * shared_part * vq; + // 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 + + // ----- The Synchronization Model ------ + // Crossflow velocity + const real yd = rd[i].dot(q[i].cross(vp.normalized())); + const real ydd = rdd_old[i].dot(q[i].cross(vp.normalized())); // note: rdd_old initializes as 0's. End nodes don't ever get updated, thus stay at zero + + // Rolling RMS calculation + const real yd_rms = sqrt((((n_m-1)*yd_rms_old[i]*yd_rms_old[i])+(yd*yd))/n_m); // RMS approximation from Thorsen + const real ydd_rms = sqrt((((n_m-1)*ydd_rms_old[i]*ydd_rms_old[i])+(ydd*ydd))/n_m); + + 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) + } + + 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 + + // Note: amplitude calculations and states commented out. Would be needed if a Cl vs A lookup table was ever implemented + + 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 real f_hat = cF + dF *sin(phi_yd - phi); // phi is integrated from state deriv phi_dot + // frequency of lift force (rad/s) + const real phi_dot = 2*pi*f_hat*vp_mag / d;// to be added to state + + // ----- The rest of the model ----- + + // // Oscillation amplitude + // 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 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 real C_l = cl_lookup(x = As/d); // create function in Line.hpp that uses lookup table + + // The Lift force + 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; + // Miscd[i][2] = As_dot; // unused state that could be used for future amplitude calculations + + } + + // tangential component of fluid acceleration // <<<<<<< check sign since I've reversed q const real aql = Ud[i].dot(q[i]); const vec aq = aql * q[i]; @@ -1173,7 +1337,7 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) 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] + Pb[i]; + Bs[i] + Lf[i] + Pb[i]; } // loop through internal nodes and compute the accelerations @@ -1185,7 +1349,20 @@ Line::getStateDeriv(std::vector& vel, std::vector& acc) // https://eigen.tuxfamily.org/dox/group__TutorialLinearAlgebra.html acc[i - 1] = M[i].inverse() * Fnet[i]; vel[i - 1] = rd[i]; + + if (Cl > 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 + 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 } + + // 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] < 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 @@ -243,6 +265,8 @@ class Line final : public io::IO, public NatFreqCFL std::vector Aq; /// node bottom contact force std::vector B; + /// crossflow viv lift force + std::vector Lf; /// total force on node std::vector Fnet; @@ -253,6 +277,32 @@ class Line final : public io::IO, public NatFreqCFL // time /// simulation time moordyn::real t; + /// MoorDyn internal time step + moordyn::real dtm0; + + // VIV stuff + // /// VIV amplitude updated every zero crossing of crossflow velcoity + // std::vector Amp; + /// 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; + /// The crossflow motion phase [-] + real phi_yd; + + // 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 rms + std::vector yd_rms_old; + /// node old cf accel rms + std::vector ydd_rms_old; + /// node old accelerations + std::vector rdd_old; // end conditions /** @brief Types of end points @@ -313,6 +363,9 @@ class Line final : public io::IO, public NatFreqCFL /// 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 @@ -321,6 +374,7 @@ class Line final : public io::IO, public NatFreqCFL * @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, @@ -328,7 +382,8 @@ class Line final : public io::IO, public NatFreqCFL 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 @@ -344,12 +399,12 @@ class Line final : public io::IO, public NatFreqCFL /** @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 * @@ -422,7 +477,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 * @@ -430,7 +485,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 @@ -510,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 @@ -523,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])); }; @@ -812,11 +869,12 @@ class Line final : public io::IO, public NatFreqCFL /** @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(const std::vector& r, const std::vector& u); + void setState(const std::vector& r, const std::vector& u, const std::vector& v); /** @brief Set the position and velocity of an end point * @param r Position @@ -857,10 +915,11 @@ class Line final : public io::IO, public NatFreqCFL /** @brief Calculate forces and get the derivative of the line's states * @param vel Where to store the velocities of the internal nodes - * @param acc Where to store the accelerations of the internal nodes + * @param acc Where to store the accelerations of the internal nodes + * @param misc Where to store the misc states of lines (viv phase, viscoelastic, unused) * @throws nan_error If nan values are detected in any node position */ - void getStateDeriv(std::vector& vel, std::vector& acc); + void getStateDeriv(std::vector& vel, std::vector& acc, std::vector& misc); // void initiateStep(vector &rFairIn, vector &rdFairIn, // double time); diff --git a/source/Misc.cpp b/source/Misc.cpp index 2b1a8c28..78b4dff5 100644 --- a/source/Misc.cpp +++ b/source/Misc.cpp @@ -78,8 +78,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/Misc.hpp b/source/Misc.hpp index c106fb5b..dc32ff64 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,20 +1087,28 @@ 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; 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 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 62d3d636..57c70291 100644 --- a/source/MoorDyn2.cpp +++ b/source/MoorDyn2.cpp @@ -249,7 +249,7 @@ moordyn::MoorDyn::icLegacy() } 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; } } @@ -546,6 +546,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(); @@ -553,6 +558,11 @@ 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(); if (ICfile != "") { @@ -578,6 +588,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; } @@ -1102,7 +1113,7 @@ moordyn::MoorDyn::ReadInFile() // Note - this is not in MD-F if (r0[2] < -env->WtrDpth) { env->WtrDpth = -r0[2]; - LOGWRN << "\t Water depth set to point " << PointList.size() << " 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 << "'" @@ -1183,7 +1194,7 @@ moordyn::MoorDyn::ReadInFile() // Make the output file (if queried) if ((outchannels.size() > 0) && - (strcspn(outchannels.c_str(), "pvUDctsd") < + (strcspn(outchannels.c_str(), "pvUDVKctsd") < strlen(outchannels.c_str()))) { // if 1+ output flag chars are given and they're valid stringstream oname; @@ -1208,7 +1219,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 @@ -1673,6 +1685,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; } @@ -1759,18 +1772,62 @@ 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. + 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(), - &(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){ + LOGMSG << "Message: viscoelastic model being used with zero damping on the dynamic stiffness." << endl; + obj->BA_D = 0.0; + } else if (BA_N > 2) { + 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) @@ -1783,6 +1840,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 @@ -1790,7 +1850,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; } @@ -2242,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; } diff --git a/source/State.cpp b/source/State.cpp index ea42afb4..6fcbd320 100644 --- a/source/State.cpp +++ b/source/State.cpp @@ -603,6 +603,10 @@ MoorDynState::AsString() const s << "Line " << i << ":" << endl; s << lines[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; s << points[i].AsString(); @@ -626,6 +630,10 @@ MoorDynState::operator=(const MoorDynState& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.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) @@ -652,6 +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 (misc.size() != rhs.misc.size()) + throw moordyn::invalid_value_error("Invalid input size"); + 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()); @@ -681,6 +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 (misc.size() != rhs.misc.size()) + throw moordyn::invalid_value_error("Invalid input size"); + 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()); @@ -721,6 +739,10 @@ DMoorDynStateDt::AsString() const s << "Line " << i << ":" << endl; s << lines[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; s << points[i].AsString(); @@ -744,6 +766,10 @@ DMoorDynStateDt::operator=(const DMoorDynStateDt& rhs) lines.reserve(rhs.lines.size()); for (auto l : rhs.lines) lines.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) @@ -768,6 +794,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.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); @@ -791,6 +820,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 (misc.size() != rhs.misc.size()) + throw moordyn::invalid_value_error("Invalid input size"); + 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()); @@ -820,6 +854,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 (misc.size() != rhs.misc.size()) + throw moordyn::invalid_value_error("Invalid input size"); + 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 acc735a9..2d0f6ec7 100644 --- a/source/State.hpp +++ b/source/State.hpp @@ -252,6 +252,9 @@ class MoorDynState /// The states of the lines std::vector lines; + /// The state derivatives of misc states: VIV, viscoelastic, blank (acc is dummy variable) + std::vector misc; + /// The states of the points std::vector points; @@ -306,6 +309,9 @@ class DMoorDynStateDt /// The state derivatives of the lines std::vector lines; + /// 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; @@ -456,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]; diff --git a/source/Time.cpp b/source/Time.cpp index ae2c1b8a..e6f45170 100644 --- a/source/Time.cpp +++ b/source/Time.cpp @@ -85,7 +85,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].misc[i].pos); } } @@ -99,7 +99,8 @@ TimeSchemeBase::CalcStateDeriv(unsigned int substep) if (!_calc_mask.lines[i]) continue; lines[i]->getStateDeriv(rd[substep].lines[i].vel, - rd[substep].lines[i].acc); + rd[substep].lines[i].acc, + rd[substep].misc[i].vel); } for (unsigned int i = 0; i < points.size(); i++) { diff --git a/source/Time.hpp b/source/Time.hpp index 7ca359d4..84f7941e 100644 --- a/source/Time.hpp +++ b/source/Time.hpp @@ -355,16 +355,24 @@ class TimeSchemeBase : public TimeScheme // Build up the states and states derivatives unsigned int n = obj->getN() - 1; LineState state; + LineState mstate; // misc state stuff state.pos.assign(n, vec::Zero()); state.vel.assign(n, 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].misc.push_back(mstate); } DLineStateDt dstate; + DLineStateDt mdstate; // misc state stuff dstate.vel.assign(n, vec::Zero()); dstate.acc.assign(n, 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].misc.push_back(mdstate); } // Add the mask value _calc_mask.lines.push_back(true); @@ -384,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; } @@ -575,7 +587,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].misc[i].pos) = lines[i]->initialize(); } } @@ -638,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; } @@ -666,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; } @@ -748,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++) { @@ -774,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()); } } @@ -812,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++) { @@ -830,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); } } @@ -933,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: @@ -1238,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++) { diff --git a/source/Waves.cpp b/source/Waves.cpp index ee63edbb..a73444c2 100644 --- a/source/Waves.cpp +++ b/source/Waves.cpp @@ -278,83 +278,83 @@ 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; } @@ -365,10 +365,10 @@ Waves::setup(EnvCondRef env_in, 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 f3054288..ba60e347 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 }; } @@ -363,18 +363,18 @@ constructWaveGridSpectrumData(const std::string& folder, // (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()); @@ -422,7 +422,7 @@ constructWaveGridElevationData(const std::string& folder, 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 @@ -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 @@ -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 c28bd9a3..25876173 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"); }