Skip to content

Commit

Permalink
Added a single wrapping data class and updated README
Browse files Browse the repository at this point in the history
  • Loading branch information
evan-palmer committed Oct 27, 2023
1 parent caf9612 commit 21c45bd
Show file tree
Hide file tree
Showing 5 changed files with 116 additions and 15 deletions.
28 changes: 18 additions & 10 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,21 @@ Checks: >
-clang-diagnostic-error,
-bugprone-exception-escape
CheckOptions:
- { key: readability-identifier-naming.NamespaceCase, value: lower_case }
- { key: readability-identifier-naming.ClassCase, value: CamelCase }
- { key: readability-identifier-naming.GlobalFunctionCase, value: camelBack }
- { key: readability-identifier-naming.StructCase, value: CamelCase }
- { key: readability-identifier-naming.FunctionCase, value: CamelCase }
- { key: readability-identifier-naming.ParameterPrefix, value: _ }
- { key: readability-identifier-naming.VariableCase, value: camelBack }
- { key: readability-identifier-naming.MemberCase, value: camelBack }
- { key: readability-identifier-naming.GlobalConstantPrefix, value: k }
- { key: readability-identifier-naming.GlobalConstantCase, value: CamelCase }
- key: readability-braces-around-statements.ShortStatementLines
value: "2"
- key: readability-identifier-naming.NamespaceCase
value: lower_case
- key: readability-identifier-naming.ClassCase
value: CamelCase
- key: readability-identifier-naming.StructCase
value: CamelCase
- key: readability-identifier-naming.TemplateParameterCase,
value: CamelCase,
- key: readability-identifier-naming.FunctionCase
value: camelBack
- key: readability-identifier-naming.MethodCase
value: camelBack
- key: readability-identifier-naming.VariableCase
value: lower_case
- key: readability-identifier-naming.ClassMemberCase
value: lower_case
5 changes: 3 additions & 2 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
"files.insertFinalNewline": true,
"files.trimTrailingWhitespace": true,
"editor.formatOnSave": true,
"C_Cpp.default.intelliSenseMode": "linux-gcc-x86",
"C_Cpp.default.intelliSenseMode": "linux-gcc-x64",
"C_Cpp.clang_format_fallbackStyle": "Google",
"C_Cpp.codeAnalysis.clangTidy.enabled": true,
"C_Cpp.codeAnalysis.clangTidy.runAutomatically": true,
Expand All @@ -32,7 +32,8 @@
"cschlosser.doxdocgen",
"ms-vscode.cpptools",
"josetr.cmake-language-support-vscode",
"xaver.clang-format"
"xaver.clang-format",
"esbenp.prettier-vscode"
]
}
}
Expand Down
36 changes: 34 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,36 @@
# Hydrodynamics

This project provides a collection of C++ data classes for common hydrodynamic parameters. All
parameters have been defined using Fossen's equations for hydrodynamics.
The hydrodynamics library provides a collection of C++ data classes for hydrodynamic parameters
(i.e., inertia, added mass, coriolis, damping, etc.). The goal of this project is to abstract away
hydrodynamic equations and representations so that you can instead focus on writing underwater
robotics algorithms.

## Installation

The hydrodynamics library has been implemented as a ROS 2 package with support for ROS 2 Humble,
Iron, and Rolling. To install and use this library in your own ROS 2 project, simply clone this
repository to your ROS 2 workspace:

```bash
cd path/to/ws_ros/src
git clone git@github.com:Robotic-Decision-Making-Lab/hydrodynamics.git
```

## Getting Started

All hydrodynamic parameters implemented in this project have been defined using Fossen's equations
for hydrodynamics. The hydrodynamic parameters implemented include:

- Mass: rigid body inertia and added mass
- Coriolis: centripetal, coriolis, and added coriolis
- Damping: linear and quadratic damping
- Restoring forces: buoyancy and gravitational forces
- Current effects: fluid velocity

Each of the aforementioned parameters provide their own distinct data class for independent use
or can be managed altogether within the `HydrodynamicParameters` class. For further
information regarding the interfaces available, please refer to the [library header](https://github.com/Robotic-Decision-Making-Lab/hydrodynamics/blob/main/include/hydrodynamics.hpp).

## License

The hydrodynamics library has been released under the MIT license.
31 changes: 30 additions & 1 deletion include/hydrodynamics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,14 +138,43 @@ class RestoringForces

class CurrentEffects
{
public:
CurrentEffects() = default;

CurrentEffects(Eigen::Vector6d velocity);
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
31 changes: 31 additions & 0 deletions src/hydrodynamics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,4 +204,35 @@ Eigen::Vector6d CurrentEffects::calculateCurrentEffectsVector(const Eigen::Matri
return rotated_current_effects;
}

HydrodynamicParameters::HydrodynamicParameters(Inertia inertia,
Coriolis coriolis,
Damping damping,
RestoringForces restoring_forces,
CurrentEffects current_effects)
: inertia(std::move(inertia)),
coriolis(std::move(coriolis)),
damping(std::move(damping)),
restoring_forces(std::move(restoring_forces)),
current_effects(std::move(current_effects))
{
}

HydrodynamicParameters::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)
{
inertia = Inertia(mass, moments, added_mass);
coriolis = Coriolis(mass, moments, added_mass);
damping = Damping(linear_damping, quadratic_damping);
restoring_forces = RestoringForces(weight, buoyancy, center_of_buoyancy, center_of_gravity);
current_effects = CurrentEffects(current_velocity);
}

} // namespace hydrodynamics

0 comments on commit 21c45bd

Please sign in to comment.