Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refresh the API #202

Merged
merged 6 commits into from
May 6, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
74 changes: 62 additions & 12 deletions source/Body.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,30 +67,28 @@ Body::setup(int number_in,
type = type_in;
outfile = outfile_pointer.get(); // make outfile point to the right place

// We better store the body initial position in all cases so the state is
// correctly initialized, and MoorDyn_GetBodyState() would be successfully
// used before calling MoorDyn_Init()
body_r6.head<3>() = r6_in.head<3>();
body_r6.tail<3>() = deg2rad * r6_in.tail<3>();

if (type == FREE) {
bodyM = M_in;
bodyV = V_in;

body_r6.head<3>() = r6_in.head<3>();
body_r6.tail<3>() = deg2rad * r6_in.tail<3>();
body_rCG = rCG_in;
bodyI = I_in;
bodyCdA = CdA_in;
bodyCa = Ca_in;
} else if (type == FIXED){ // fixed bodies have no need for these variables other than position...
bodyM = 0.0;
bodyV = 0.0;
body_r6.head<3>() = r6_in.head<3>();
body_r6.tail<3>() = deg2rad * r6_in.tail<3>();
bodyI = vec::Zero();
bodyCdA = vec6::Zero();
bodyCa = vec6::Zero();
} else if (type == CPLDPIN){
bodyM = M_in;
bodyV = V_in;

body_r6.head<3>() = vec3::Zero();
body_r6.tail<3>() = deg2rad * r6_in.tail<3>();
body_rCG = rCG_in;
bodyI = I_in;
bodyCdA = CdA_in;
Expand All @@ -99,8 +97,6 @@ Body::setup(int number_in,
{
bodyM = 0.0;
bodyV = 0.0;

body_r6 = vec6::Zero();
body_rCG = vec::Zero();
bodyI = vec::Zero();
bodyCdA = vec6::Zero();
Expand Down Expand Up @@ -511,8 +507,8 @@ Body::getStateDeriv()
return std::make_pair(dPos, a6);
};

vec6
Body::getFnet()
const vec6
Body::getFnet() const
{
vec6 F6_iner = vec6::Zero();
vec6 Fnet_out = vec6::Zero();
Expand Down Expand Up @@ -831,6 +827,60 @@ MoorDyn_GetBodyState(MoorDynBody b, double r[6], double rd[6])
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyPos(MoorDynBody b, double r[3])
{
CHECK_BODY(b);
moordyn::vec pos = ((moordyn::Body*)b)->getPosition();
moordyn::vec2array(pos, r);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyAngle(MoorDynBody b, double r[3])
{
CHECK_BODY(b);
moordyn::vec pos = ((moordyn::Body*)b)->getAngles();
moordyn::vec2array(pos, r);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyVel(MoorDynBody b, double rd[3])
{
CHECK_BODY(b);
moordyn::vec vel = ((moordyn::Body*)b)->getVelocity();
moordyn::vec2array(vel, rd);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyAngVel(MoorDynBody b, double rd[3])
{
CHECK_BODY(b);
moordyn::vec vel = ((moordyn::Body*)b)->getAngularVelocity();
moordyn::vec2array(vel, rd);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyForce(MoorDynBody b, double f[6])
{
CHECK_BODY(b);
moordyn::vec6 force = ((moordyn::Body*)b)->getFnet();
moordyn::vec62array(force, f);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_GetBodyM(MoorDynBody b, double m[6][6])
{
CHECK_BODY(b);
moordyn::mat6 mass = ((moordyn::Body*)b)->getM();
moordyn::mat62array(mass, m);
return MOORDYN_SUCCESS;
}

int DECLDIR
MoorDyn_SaveBodyVTK(MoorDynBody b, const char* filename)
{
Expand Down
48 changes: 48 additions & 0 deletions source/Body.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,54 @@ extern "C"
*/
int DECLDIR MoorDyn_GetBodyState(MoorDynBody b, double r[6], double rd[6]);

/** @brief Get the body position
* @param b The Moordyn body
* @param r The output position (3dof)
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyPos(MoorDynBody b, double r[3]);

/** @brief Get the body angle
* @param b The Moordyn body
* @param r The output angles (3dof)
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyAngle(MoorDynBody b, double r[3]);

/** @brief Get the body velocity
* @param b The Moordyn body
* @param rd The output velocity (3dof)
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyVel(MoorDynBody b, double rd[3]);

/** @brief Get the body angular velocity
* @param b The Moordyn body
* @param rd The output angular velocity (3dof)
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyAngVel(MoorDynBody b, double rd[3]);

/** @brief Get the body angular velocity
* @param b The Moordyn body
* @param rd The output angular velocity (3dof)
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyForce(MoorDynBody b, double f[6]);

/** @brief Get the body mass and intertia matrix
* @param b The Moordyn body
* @param m The output mass matrix
* @return MOORDYN_INVALID_VALUE if a NULL body is provided, MOORDYN_SUCCESS
* otherwise
*/
int DECLDIR MoorDyn_GetBodyM(MoorDynBody b, double m[6][6]);

/** @brief Save the point to a VTK (.vtp) file
* @param b The Moordyn body
* @param filename The output maximum tension module
Expand Down
12 changes: 6 additions & 6 deletions source/Body.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -303,33 +303,33 @@ class Body final : public io::IO
/** @brief Get the body position
* @return The body position
*/
inline vec getPosition() const { return r7.pos; }
inline const vec getPosition() const { return r7.pos; }

/** @brief Get the body Euler XYZ angles
* @return The body Euler XYZ angles
*/
inline vec getAngles() const { return Quat2Euler(r7.quat); }
inline const vec getAngles() const { return Quat2Euler(r7.quat); }
// inline vec getAngles() const { return r6(Eigen::seqN(3, 3)); }

/** @brief Get the body velocity
* @return The body velocity
*/
inline vec getVelocity() const { return v6(Eigen::seqN(0, 3)); }
inline const vec getVelocity() const { return v6(Eigen::seqN(0, 3)); }

/** @brief Get the body angular velocity
* @return The body angular velocity
*/
inline vec getAngularVelocity() const { return v6(Eigen::seqN(3, 3)); }
inline const vec getAngularVelocity() const { return v6(Eigen::seqN(3, 3)); }

/** @brief Get the forces and moments exerted over the body
* @return The net force
*/
vec6 getFnet();
const vec6 getFnet() const;

/** @brief Get the mass and intertia matrix
* @return The mass and inertia matrix
*/
inline mat6 getM() const { return M; };
inline const mat6& getM() const { return M; };

/** @brief Get body output
*
Expand Down
112 changes: 112 additions & 0 deletions source/Line.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1681,6 +1681,34 @@ MoorDyn_GetLineNodePos(MoorDynLine l, unsigned int i, double pos[3])
return err;
}

int DECLDIR
MoorDyn_GetLineNodeVel(MoorDynLine l, unsigned int i, double vel[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec rd = ((moordyn::Line*)l)->getNodeVel(i);
moordyn::vec2array(rd, vel);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeForce(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeForce(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeTen(MoorDynLine l, unsigned int i, double ten[3])
{
Expand All @@ -1695,6 +1723,76 @@ MoorDyn_GetLineNodeTen(MoorDynLine l, unsigned int i, double ten[3])
return err;
}

int DECLDIR
MoorDyn_GetLineNodeBendStiff(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeBendStiff(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeWeight(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeWeight(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeDrag(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeDrag(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeFroudeKrilov(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeFroudeKrilov(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeSeabedForce(MoorDynLine l, unsigned int i, double f[3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::vec force = ((moordyn::Line*)l)->getNodeSeabedForce(i);
moordyn::vec2array(force, f);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineNodeCurv(MoorDynLine l, unsigned int i, double* curv)
{
Expand All @@ -1709,6 +1807,20 @@ MoorDyn_GetLineNodeCurv(MoorDynLine l, unsigned int i, double* curv)
return err;
}

int DECLDIR
MoorDyn_GetLineNodeM(MoorDynLine l, unsigned int i, double m[3][3])
{
CHECK_LINE(l);
moordyn::error_id err = MOORDYN_SUCCESS;
string err_msg;
try {
const moordyn::mat mass = ((moordyn::Line*)l)->getNodeM(i);
moordyn::mat2array(mass, m);
}
MOORDYN_CATCHER(err, err_msg);
return err;
}

int DECLDIR
MoorDyn_GetLineFairTen(MoorDynLine l, double* t)
{
Expand Down
Loading