Skip to content

Commit

Permalink
LTA Dynamics System
Browse files Browse the repository at this point in the history
copy of Hydrodynamics folder, and rename to lta

Renamed to LighterThanAirDynamics

- Added some initial private data
- Requires still alot of cleanup

some initial dynamics added

Building sucessfully with some warnings

Running test to determine succesfull Spawning

successfull ran tests, but still debugging alot

Added additional debug messages

Protection for zero division

- Test running sucessfully with adding forces and torques, but requires
more extensive testing and validation

Improved Documentation,some more work on tests

Improve documentation to include math

Silver bullet model withs its coefficients

small documentation update

Code style updates. wip

Style checks completed

Small correction to dynamics

Added Mass Force and Torques included

- Link class now provides the FluidAddedMassMatrix

Removed Munk from added mass & correct coeff names

Signed-off-by: henrykotze <[email protected]>
  • Loading branch information
henrykotze committed Nov 13, 2023
1 parent e88a46f commit 9e6800d
Show file tree
Hide file tree
Showing 10 changed files with 874 additions and 0 deletions.
9 changes: 9 additions & 0 deletions include/gz/sim/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <vector>

#include <gz/math/Matrix3.hh>
#include <gz/math/Matrix6.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>
Expand Down Expand Up @@ -269,6 +270,14 @@ namespace gz
public: std::optional<math::Matrix3d> WorldInertiaMatrix(
const EntityComponentManager &_ecm) const;

/// \brief Get the fluid added mass matrix in the world frame.
/// \param[in] _ecm Entity-component manager.
/// \return Fluide added matrix in world frame, returns nullopt if link
/// does not have components components::Inertial and
/// components::WorldPose.
public: std::optional<math::Matrix6d> WorldFluidAddedMassMatrix(
const EntityComponentManager &_ecm) const;

/// \brief Get the rotational and translational kinetic energy of the
/// link with respect to the world frame.
/// \param[in] _ecm Entity-component manager.
Expand Down
12 changes: 12 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -337,6 +337,18 @@ std::optional<math::Matrix3d> Link::WorldInertiaMatrix(
math::Inertiald(inertial->Data().MassMatrix(), comWorldPose).Moi());
}

std::optional<math::Matrix6d> Link::WorldFluidAddedMassMatrix(
const EntityComponentManager &_ecm) const
{
auto inertial = _ecm.Component<components::Inertial>(this->dataPtr->id);
auto worldPose = _ecm.Component<components::WorldPose>(this->dataPtr->id);

if (!worldPose || !inertial)
return std::nullopt;

return inertial->Data().FluidAddedMass();
}

//////////////////////////////////////////////////
std::optional<double> Link::WorldKineticEnergy(
const EntityComponentManager &_ecm) const
Expand Down
1 change: 1 addition & 0 deletions src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ add_subdirectory(joint_traj_control)
add_subdirectory(kinetic_energy_monitor)
add_subdirectory(label)
add_subdirectory(lift_drag)
add_subdirectory(lighter_than_air_dynamics)
add_subdirectory(log)
add_subdirectory(log_video_recorder)
add_subdirectory(logical_audio_sensor_plugin)
Expand Down
7 changes: 7 additions & 0 deletions src/systems/lighter_than_air_dynamics/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
gz_add_system(lighter_than_air_dynamics
SOURCES
LighterThanAirDynamics.cc
PUBLIC_LINK_LIBS
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-math${GZ_MATH_VER}::eigen3
)
Loading

0 comments on commit 9e6800d

Please sign in to comment.