Skip to content

Commit

Permalink
prevent body drag coeffs from being negative
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexWKinley committed Apr 15, 2024
1 parent 4f09186 commit 23340a1
Show file tree
Hide file tree
Showing 3 changed files with 124 additions and 24 deletions.
2 changes: 1 addition & 1 deletion source/Body.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -581,7 +581,7 @@ Body::doRHS()
cda(Eigen::seqN(0, 3)) = OrMat.transpose() * bodyCdA.head<3>();
cda(Eigen::seqN(3, 3)) = OrMat.transpose() * bodyCdA.tail<3>();
F6net +=
0.5 * env->rho_w * vi.cwiseProduct(vi.cwiseAbs()).cwiseProduct(cda);
0.5 * env->rho_w * vi.cwiseProduct((vi.cwiseProduct(cda)).cwiseAbs());

// Get contributions from any points attached to the body
for (auto attached : attachedP) {
Expand Down
30 changes: 30 additions & 0 deletions tests/Mooring/body_tests/bodyDrag.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
A simple test to ensure that body drag coefficients don't go negative in certain orientations
------------------------- LINE TYPES --------------------------------------------------
LineType Diam MassDenInAir EA BA/-zeta EI tbd Can Cat Cdn Cdt
(-) (m) (kg/m) (N) (Pa-s/-) (n-m^2) (-) (-) (-) (-) (-)
spring 0.1 10.0 500.0 -0.4 0.0 0.0 0.0 0.0 0.0 0.00
---------------------------- BODIES -----------------------------------------------------
ID Attachment X0 Y0 Z0 r0 p0 y0 Mass CG* I* Volume CdA* Ca
(#) (-) (m) (m) (m) (deg) (deg) (deg) (kg) (m) (kg-m^2) (m^3) (m^2) (-)
1 free 0 0 0 0 -90 0 1e1 0 5 0 0.1 0
----------------------- POINTS ----------------------------------------------
Node Type X Y Z M V CdA CA
(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-)
1 Body1 0.0 0 0 0 0 0 0
2 Fixed 0.0 0 -5 0 0 0 0
-------------------------- LINES -------------------------------------------------
Line LineType NodeA NodeB UnstrLen NumSegs Flags/Outputs
(-) (-) (-) (-) (m) (-) (-)
1 spring 1 2 4.5 1 -
-------------------------- SOLVER OPTIONS---------------------------------------------------
2 writeLog - Write a log file
9.81 g - No gravity
0.002 dtM - time step to use in mooring integration
3.0e6 kb - bottom stiffness
3.0e5 cb - bottom damping
70 WtrDpth - water depth
3.0 ICDfac - factor by which to scale drag coefficients during dynamic relaxation IC gen
0.015 threshIC - threshold for IC convergence
0.0 TmaxIC - threshold for IC convergence
0.01 dtIC - Time lapse between convergence tests (s)
--------------------------- need this line -------------------------------------------------
116 changes: 93 additions & 23 deletions tests/bodies.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -386,7 +386,9 @@ rotatingBody(SeriesWriter* series_writer)
double angle = moordyn::rad2deg * 2 * acos(q.w());
double denom = (sqrt(1 - q.w() * q.w()));
moordyn::vec3 axis{ q.x() / denom, q.y() / denom, q.z() / denom };
if (!(abs(axis.x()) > 0.85 && abs(axis.y()) < 0.2 && abs(axis.z()) < 0.2)) { // if we are just checking axis direction then +/- does not matter
if (!(abs(axis.x()) > 0.85 && abs(axis.y()) < 0.2 &&
abs(axis.z()) < 0.2)) { // if we are just checking axis direction then
// +/- does not matter
cerr << "The final rotation of the body in angle axis form should "
"have an axis in the x direction, but axis is "
<< axis.transpose() << endl;
Expand Down Expand Up @@ -421,19 +423,19 @@ rotatingBody(SeriesWriter* series_writer)
/**
* @brief Compares inertial deflection of a pinned body to analytical solution
*
*
* The coupled pinned body that is massless and volumeless with a rod fixed to it
* is moved with constant acceleration in a vaccum (0 water density).
* The resulting avg inertial deflection should match an analytical solution of
*
* The coupled pinned body that is massless and volumeless with a rod fixed to
* it is moved with constant acceleration in a vaccum (0 water density). The
* resulting avg inertial deflection should match an analytical solution of
* theta = arctan(-accel/gravity)
*
* This solution was derived both with Newtonian and LaGrangian mechanics.
* It is the same as the pendulum on an accelerating cart problem.
*
* This only tests the inertial properties of pinned bodies, other tests deal
*
* This solution was derived both with Newtonian and LaGrangian mechanics.
* It is the same as the pendulum on an accelerating cart problem.
*
* This only tests the inertial properties of pinned bodies, other tests deal
* with hydrodynamics and general body properties
*
*
*
* @param series_writer
* @return true
* @return false
Expand All @@ -456,13 +458,14 @@ pinnedBody(SeriesWriter* series_writer)
cerr << "Failure getting NCoupledDOF: " << err << endl;
return false;
}
if (n_dof != 6) { // rotational DOF are ignored by MDC, same as a coupled pinned rods
if (n_dof !=
6) { // rotational DOF are ignored by MDC, same as a coupled pinned rods
cerr << "Expected 6 DOFs but got " << n_dof << endl;
return false;
}

moordyn::vec6 x{ 0, 0, -5, 0, 0, 0};
moordyn::vec6 xd{ 0, 0, 0 , 0, 0, 0};
moordyn::vec6 x{ 0, 0, -5, 0, 0, 0 };
moordyn::vec6 xd{ 0, 0, 0, 0, 0, 0 };
double f[6];

err = MoorDyn_Init(system, x.data(), xd.data());
Expand All @@ -488,8 +491,8 @@ pinnedBody(SeriesWriter* series_writer)

while (t < 50.0) {

x[1] = 0.5*accel*pow(t, 2);
xd[1] = accel*t;
x[1] = 0.5 * accel * pow(t, 2);
xd[1] = accel * t;
err = MoorDyn_Step(system, x.data(), xd.data(), f, &t, &dt);
if (err != MOORDYN_SUCCESS) {
cerr << "Failure during the mooring initialization: " << err
Expand All @@ -504,20 +507,24 @@ pinnedBody(SeriesWriter* series_writer)
roll.push_back(r[3]);

if (i >= 30) { // after the simulation has run for a few time steps
// When local min or max of oscillation, indicates half of an oscialltion has occured
local_min_max = (((roll[i]-roll[i-1])/dt) * ((roll[i-1]-roll[i-2])/dt)) < 0;
if (local_min_max) j++;
// When local min or max of oscillation, indicates half of an
// oscialltion has occured
local_min_max = (((roll[i] - roll[i - 1]) / dt) *
((roll[i - 1] - roll[i - 2]) / dt)) < 0;
if (local_min_max)
j++;
}
if (j > 3) break; // after 2 full oscillations
if (j > 3)
break; // after 2 full oscillations

t = t + dt;
i++;
}
double theta = atan(-accel/9.80665);
double theta = atan(-accel / 9.80665);
double average = reduce(roll.begin(), roll.end()) / roll.size();
if (abs(average - theta) > 0.001) {
cerr << "Pinned body inertial deflection should be "
<< theta << " but it is " << average << endl;
cerr << "Pinned body inertial deflection should be " << theta
<< " but it is " << average << endl;
return false;
}

Expand All @@ -533,6 +540,65 @@ pinnedBody(SeriesWriter* series_writer)
return true;
}

bool
bodyDrag(SeriesWriter* series_writer)
{
int err;
cout << endl << " => " << __PRETTY_FUNC_NAME__ << "..." << endl;

MoorDyn system = MoorDyn_Create("Mooring/body_tests/bodyDrag.txt");
if (!system) {
cerr << "Failure Creating the Mooring system" << endl;
return false;
}

unsigned int n_dof;
err = MoorDyn_NCoupledDOF(system, &n_dof);
if (err != MOORDYN_SUCCESS) {
cerr << "Failure getting NCoupledDOF: " << err << endl;
return false;
}
if (n_dof != 0) {
cerr << "Expected 0 DOFs but got " << n_dof << endl;
return false;
}

double f[3];

err = MoorDyn_Init(system, nullptr, nullptr);
if (err != MOORDYN_SUCCESS) {
cerr << "Failure during the mooring initialization: " << err << endl;
return false;
}

if (!write_system_vtk(system, 0, series_writer)) {
return false;
}

double t = 0, dt = 0.1;
double max_t = 5;
while (t < max_t) {
// do one outer time step just to make sure everything is settled
err = MoorDyn_Step(system, nullptr, nullptr, f, &t, &dt);
if (err != MOORDYN_SUCCESS) {
cerr << "Failure during the mooring dynamics: " << err << endl;
return false;
}

if (!write_system_vtk(system, t, series_writer)) {
return false;
}
}

err = MoorDyn_Close(system);
if (err != MOORDYN_SUCCESS) {
cerr << "Failure closing Moordyn: " << err << endl;
return false;
}

return true;
}

/** @brief Runs all the test
* @return 0 if the tests have ran just fine. The index of the failing test
* otherwise
Expand Down Expand Up @@ -566,6 +632,10 @@ main(int, char**)
return 3;
}

if (!bodyDrag(NULL)) {
return 2;
}

cout << "bodies.cpp passed successfully" << endl;
return 0;
}

0 comments on commit 23340a1

Please sign in to comment.