Skip to content

Commit

Permalink
Removed current effects and fixed weird const refs in constructor
Browse files Browse the repository at this point in the history
  • Loading branch information
evan-palmer committed Feb 24, 2024
1 parent 21c45bd commit 1dfd812
Show file tree
Hide file tree
Showing 6 changed files with 184 additions and 215 deletions.
5 changes: 2 additions & 3 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,8 @@ BraceWrapping:
AfterNamespace: true
AfterStruct: true
AfterEnum: true
ColumnLimit: 100
BinPackParameters: false
BinPackArguments: false
ColumnLimit: 120
BinPackParameters: true
ConstructorInitializerIndentWidth: 0
ContinuationIndentWidth: 2
DerivePointerAlignment: false
Expand Down
4 changes: 4 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -45,3 +45,7 @@ CheckOptions:
value: lower_case
- key: readability-identifier-naming.ClassMemberCase
value: lower_case
- key: readability-identifier-naming.ProtectedMemberSuffix
value: "_"
- key: readability-identifier-naming.PrivateMemberSuffix
value: "_"
2 changes: 1 addition & 1 deletion .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
"C_Cpp.codeAnalysis.clangTidy.enabled": true,
"C_Cpp.codeAnalysis.clangTidy.runAutomatically": true,
"clang-format.executable": "/usr/bin/clang-format-14",
"editor.rulers": [100],
"editor.rulers": [120],
"editor.tabSize": 2,
"[cpp]": {
"editor.defaultFormatter": "xaver.clang-format"
Expand Down
1 change: 0 additions & 1 deletion include/eigen.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#pragma once

#include <Eigen/Dense>
#include <vector>

namespace Eigen
{
Expand Down
246 changes: 150 additions & 96 deletions include/hydrodynamics.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023, Evan Palmer
// Copyright 2024, Evan Palmer
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
Expand All @@ -21,35 +21,66 @@
#pragma once

#include <Eigen/Dense>
#include <memory>
#include <optional>

#include "eigen.hpp"

namespace hydrodynamics
{

/**
* @brief A wrapper for inertial parameters including added mass and rigid body inertia.
*/
class Inertia
{
public:
Inertia() = default;

Inertia(double mass,
double Ixx,
double Iyy,
double Izz,
double Xdu,
double Ydv,
double Zdw,
double Kdp,
double Mdq,
/**
* @brief Construct a new wrapper for inertial parameters including added mass and rigid body inertia.
*
* @param mass The mass of the vehicle.
* @param Ixx The moment of inertia about the x-axis.
* @param Iyy The moment of inertia about the y-axis.
* @param Izz The moment of inertia about the z-axis.
* @param Xdu The added mass coefficient in the surge direction.
* @param Ydv The added mass coefficient in the sway direction.
* @param Zdw The added mass coefficient in the heave direction.
* @param Kdp The added mass coefficient in the roll direction.
* @param Mdq The added mass coefficient in the pitch direction.
* @param Ndr The added mass coefficient in the yaw direction.
*/
Inertia(double mass, double Ixx, double Iyy, double Izz, double Xdu, double Ydv, double Zdw, double Kdp, double Mdq,
double Ndr);

Inertia(double mass, const Eigen::Vector3d & moments, const Eigen::Vector6d & added_mass);

/**
* @brief Construct a new wrapper for inertial parameters including added mass and rigid body inertia.
*
* @param mass The mass of the vehicle.
* @param moments The moments of inertia about the x, y, and z axes.
* @param added_mass The added mass coefficients in the surge, sway, heave, roll, pitch, and yaw directions.
*/
Inertia(double mass, Eigen::Vector3d moments, Eigen::Vector6d added_mass);

/**
* @brief Get the rigid body inertia matrix.
*
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d getRigidBodyInertiaMatrix() const;

/**
* @brief Get the added mass matrix.
*
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d getAddedMassMatrix() const;

/**
* @brief Get the mass matrix.
*
* @note This is the sum of the rigid body and added mass matrices.
*
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d getMassMatrix() const;

private:
Expand All @@ -58,30 +89,62 @@ class Inertia
Eigen::Matrix6d mass_mat_;
};

/**
* @brief A wrapper for Coriolis and centripetal force parameters.
*/
class Coriolis
{
public:
Coriolis() = default;

Coriolis(double mass,
double Ixx,
double Iyy,
double Izz,
double Xdu,
double Ydv,
double Zdw,
double Kdp,
double Mdq,
/**
* @brief Construct a new wrapper for the Coriolis and centripetal force parameters.
*
* @param mass The mass of the vehicle.
* @param Ixx The moment of inertia about the x-axis.
* @param Iyy The moment of inertia about the y-axis.
* @param Izz The moment of inertia about the z-axis.
* @param Xdu The added mass coefficient in the surge direction.
* @param Ydv The added mass coefficient in the sway direction.
* @param Zdw The added mass coefficient in the heave direction.
* @param Kdp The added mass coefficient in the roll direction.
* @param Mdq The added mass coefficient in the pitch direction.
* @param Ndr The added mass coefficient in the yaw direction.
*/
Coriolis(double mass, double Ixx, double Iyy, double Izz, double Xdu, double Ydv, double Zdw, double Kdp, double Mdq,
double Ndr);

Coriolis(double mass, const Eigen::Vector3d & moments, Eigen::Vector6d added_mass);

[[nodiscard]] Eigen::Matrix6d calculateRigidBodyCoriolisMatrix(
const Eigen::Vector3d & angular_velocity) const;

[[nodiscard]] Eigen::Matrix6d calculateAddedCoriolisMatrix(
const Eigen::Vector6d & velocity) const;

/**
* @brief Construct a new wrapper for the Coriolis and centripetal force parameters.
*
* @param mass The mass of the vehicle.
* @param moments The moments of inertia about the x, y, and z axes.
* @param added_mass The added mass coefficients in the surge, sway, heave, roll, pitch, and yaw directions.
*/
Coriolis(double mass, Eigen::Vector3d moments, Eigen::Vector6d added_mass);

/**
* @brief Calculate the rigid body Coriolis matrix.
*
* @param angular_velocity The angular velocity of the vehicle.
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d calculateRigidBodyCoriolisMatrix(const Eigen::Vector3d & angular_velocity) const;

/**
* @brief Calculate the added mass Coriolis matrix.
*
* @param velocity The velocity of the vehicle.
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d calculateAddedCoriolisMatrix(const Eigen::Vector6d & velocity) const;

/**
* @brief Calculate the Coriolis matrix.
*
* @note This is the sum of the rigid body and added mass Coriolis matrices.
*
* @param velocity The velocity of the vehicle.
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d calculateCoriolisMatrix(const Eigen::Vector6d & velocity) const;

private:
Expand All @@ -90,44 +153,76 @@ class Coriolis
Eigen::Vector6d added_mass_coeff_;
};

/**
* @brief A wrapper for the damping forces acting on the vehicle, including linear and quadratic damping coefficients.
*/
class Damping
{
public:
Damping() = default;

Damping(double Xu,
double Yv,
double Zw,
double Kp,
double Mq,
double Nr,
double Xuu,
double Yvv,
double Zww,
double Kpp,
double Mqq,
double Nrr);

/**
* @brief Construct a new wrapper for the damping coefficients.
*
* @param Xu The linear damping coefficient in the surge direction.
* @param Yv The linear damping coefficient in the sway direction.
* @param Zw The linear damping coefficient in the heave direction.
* @param Kp The linear damping coefficient in the roll direction.
* @param Mq The linear damping coefficient in the pitch direction.
* @param Nr The linear damping coefficient in the yaw direction.
* @param Xuu The quadratic damping coefficient in the surge direction.
* @param Yvv The quadratic damping coefficient in the sway direction.
* @param Zww The quadratic damping coefficient in the heave direction.
* @param Kpp The quadratic damping coefficient in the roll direction.
* @param Mqq The quadratic damping coefficient in the pitch direction.
* @param Nrr The quadratic damping coefficient in the yaw direction.
*/
Damping(double Xu, double Yv, double Zw, double Kp, double Mq, double Nr, double Xuu, double Yvv, double Zww,
double Kpp, double Mqq, double Nrr);

/**
* @brief Construct a new wrapper for the damping coefficients.
*
* @param linear The linear damping coefficients.
* @param quadratic The quadratic damping coefficients.
*/
Damping(Eigen::Vector6d linear, Eigen::Vector6d quadratic);

/**
* @brief Calculate the damping matrix.
*
* @param velocity The current velocity of the vehicle.
* @return Eigen::Matrix6d
*/
[[nodiscard]] Eigen::Matrix6d calculateDampingMatrix(const Eigen::Vector6d & velocity) const;

private:
Eigen::Vector6d linear_coeff_;
Eigen::Vector6d quadratic_coeff_;
};

/**
* @brief A wrapper for the restoring forces acting on the vehicle, including gravity and bouyancy.
*/
class RestoringForces
{
public:
RestoringForces() = default;

RestoringForces(double weight,
double buoyancy,
Eigen::Vector3d center_of_buoyancy,
/**
* @brief Construct a wrapper for restoring force parameters.
*
* @param weight The weight of the vehicle.
* @param buoyancy The buoyancy of the vehicle.
* @param center_of_buoyancy The center of buoyancy of the vehicle.
* @param center_of_gravity The center of gravity of the vehicle.
*/
RestoringForces(double weight, double buoyancy, Eigen::Vector3d center_of_buoyancy,
Eigen::Vector3d center_of_gravity);

[[nodiscard]] Eigen::Vector6d calculateRestoringForcesVector(const Eigen::Matrix3d & rot) const;
/**
* @brief Calculate the restoring forces acting on the vehicle.
*
* @param rotation The current rotation of the vehicle with respect to the inertial frame.
* @return Eigen::Vector6d
*/
[[nodiscard]] Eigen::Vector6d calculateRestoringForcesVector(const Eigen::Matrix3d & rotation) const;

private:
double weight_;
Expand All @@ -136,45 +231,4 @@ class RestoringForces
Eigen::Vector3d center_of_gravity_;
};

class CurrentEffects
{
public:
CurrentEffects() = default;

explicit CurrentEffects(Eigen::Vector6d velocity);

[[nodiscard]] Eigen::Vector6d calculateCurrentEffectsVector(const Eigen::Matrix3d & rot) const;

private:
Eigen::Vector6d current_;
};

struct HydrodynamicParameters
{
Inertia inertia;
Coriolis coriolis;
Damping damping;
RestoringForces restoring_forces;
CurrentEffects current_effects;

HydrodynamicParameters() = default;

HydrodynamicParameters(Inertia inertia,
Coriolis coriolis,
Damping damping,
RestoringForces restoring_forces,
CurrentEffects current_effects);

HydrodynamicParameters(double mass,
double weight,
double buoyancy,
const Eigen::Vector3d & moments,
const Eigen::Vector6d & added_mass,
Eigen::Vector6d linear_damping,
Eigen::Vector6d quadratic_damping,
Eigen::Vector3d center_of_buoyancy,
Eigen::Vector3d center_of_gravity,
Eigen::Vector6d current_velocity);
};

} // namespace hydrodynamics
Loading

0 comments on commit 1dfd812

Please sign in to comment.