Gazebo Sim

API Reference

9.0.0~pre1
LighterThanAirDynamics Class Reference

This class provides the effect of viscousity on the hull of lighter-than-air vehicles such as airships. The equations implemented is based on the work published in [1], which describes a modeling approach for the nonlinear dynamics simulation of airships and [2] providing more insight of the modelling of an airship. More...

#include <LighterThanAirDynamics.hh>

Public Member Functions

 LighterThanAirDynamics ()
 Constructor.
 
 ~LighterThanAirDynamics () override
 Destructor.
 
math::Vector3d AddedMassForce (math::Vector3d lin_vel, math::Vector3d ang_vel, math::Matrix3d m11, math::Matrix3d m12)
 Calculates the potential flow aerodynamic torques that a LTA vehicle experience when moving in a potential fluid. The aerodynamic torques is derived using Kirchoff's equation.
 
math::Vector3d AddedMassTorque (math::Vector3d lin_vel, math::Vector3d ang_vel, math::Matrix3d m11, math::Matrix3d m12, math::Matrix3d m21, math::Matrix3d m22)
 Calculates the potential flow aerodynamic forces that a LTA vehicle experience when moving in a potential fluid. The aerodynamic force is derived using Kirchoff's equation.
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &) override
 Documentation inherited.
 
double DynamicPressure (math::Vector3d vec, double air_density)
 Calculates dynamic pressure.
 
math::Vector3d LocalVelocity (math::Vector3d lin_vel, math::Vector3d ang_vel, math::Vector3d dist)
 Calculates the local velocity at an offset from a origin.
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 Documentation inherited.
 
math::Matrix3d SkewSymmetricMatrix (math::Vector3d mat)
 Skew-symmetric matrices can be used to represent cross products as matrix multiplications.
 
- Public Member Functions inherited from System
 System ()=default
 Constructor.
 
virtual ~System ()=default
 Destructor.
 

Additional Inherited Members

- Public Types inherited from System
using PriorityType = int32_t
 Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases.
 
- Static Public Attributes inherited from System
static constexpr PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases.
 
static constexpr std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed.
 

Detailed Description

This class provides the effect of viscousity on the hull of lighter-than-air vehicles such as airships. The equations implemented is based on the work published in [1], which describes a modeling approach for the nonlinear dynamics simulation of airships and [2] providing more insight of the modelling of an airship.

System Parameters

  • <air_density> sets the density of air that surrounds the buoyant object. [Units: kgm^-3]
  • <force_invisc_coeff is the first coefficient in Eq (11) in [1]: \( (k_2 - k_1) \cdot \int_{\varepsilon_{0}}^{L} \frac{dS}{d\varepsilon} \,d\varepsilon \)
  • <force_visc_coeff> is the second coefficient in Eq (11) in [1]: \( \eta C_{DC} \cdot \int_{\varepsilon_{0}}^{L} 2R \,d\varepsilon \)
  • <moment_invisc_coeff is the first coefficient in Eq (14) in [1]: \( (k_2 - k_1) \cdot \int_{\varepsilon_{0}}^{L} \frac{dS}{d\varepsilon} (\varepsilon_{m} - \varepsilon) \,d\varepsilon \)
  • <moment_visc_coeff> is the second coefficient in Eq (14) in [1]: \( \eta C_{DC} \cdot \int_{\varepsilon_{0}}^{L} 2R (\varepsilon_{m} - \varepsilon) \,d\varepsilon \)
  • <eps_v> is the point on the hull where the flow ceases being potential
  • <axial_drag_coeff> the actual drag coefficient of the hull

Notes

This class only implements the viscous effects on the hull of an airship and currently does not take into the account wind. This class should be used in combination with the boyuancy, added mass and gravity plugins to simulate the behaviour of an airship. Its important to provide a collision property to the hull, since this is from which the buoyancy plugin determines the volume.

Citations

[1] Li, Y., & Nahon, M. (2007). Modeling and simulation of airship dynamics. Journal of Guidance, Control, and Dynamics, 30(6), 1691–1700.

[2] Li, Y., Nahon, M., & Sharf, I. (2011). Airship dynamics modeling: A literature review. Progress in Aerospace Sciences, 47(3), 217–239.

Constructor & Destructor Documentation

◆ LighterThanAirDynamics()

Constructor.

◆ ~LighterThanAirDynamics()

~LighterThanAirDynamics ( )
override

Destructor.

Member Function Documentation

◆ AddedMassForce()

math::Vector3d AddedMassForce ( math::Vector3d  lin_vel,
math::Vector3d  ang_vel,
math::Matrix3d  m11,
math::Matrix3d  m12 
)

Calculates the potential flow aerodynamic torques that a LTA vehicle experience when moving in a potential fluid. The aerodynamic torques is derived using Kirchoff's equation.

Parameters
[in]lin_vel- The body linear velocity
[in]ang_vel- The body angular velocity
[in]m11- The left upper [3x3] matrix of the added mass matrix
[in]m12- The right upper [3x3] matrix of the added mass matrix
Returns
The aerodynamic torque

◆ AddedMassTorque()

math::Vector3d AddedMassTorque ( math::Vector3d  lin_vel,
math::Vector3d  ang_vel,
math::Matrix3d  m11,
math::Matrix3d  m12,
math::Matrix3d  m21,
math::Matrix3d  m22 
)

Calculates the potential flow aerodynamic forces that a LTA vehicle experience when moving in a potential fluid. The aerodynamic force is derived using Kirchoff's equation.

Parameters
[in]lin_vel- The body linear velocity
[in]ang_vel- The body angular velocity
[in]m11- The left upper [3x3] matrix of the added mass matrix
[in]m12- The right upper [3x3] matrix of the added mass matrix
[in]m21- The left lower [3x3] matrix of the added mass matrix
[in]m22- The right lower [3x3] matrix of the added mass matrix
Returns
The aerodynamic force.

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager  
)
overridevirtual

Documentation inherited.

Implements ISystemConfigure.

◆ DynamicPressure()

double DynamicPressure ( math::Vector3d  vec,
double  air_density 
)

Calculates dynamic pressure.

Parameters
[in]vec- The linear velocity
[in]air_density- The air density [kg/m^3]
Returns
The dynamic pressure, q

◆ LocalVelocity()

math::Vector3d LocalVelocity ( math::Vector3d  lin_vel,
math::Vector3d  ang_vel,
math::Vector3d  dist 
)

Calculates the local velocity at an offset from a origin.

Parameters
[in]lin_vel- The linear body velocity
[in]ang_vel- The angular body velocity
[in]dist- The distance vector from the origin
Returns
The local velocity at the distance vector

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPreUpdate.

◆ SkewSymmetricMatrix()

math::Matrix3d SkewSymmetricMatrix ( math::Vector3d  mat)

Skew-symmetric matrices can be used to represent cross products as matrix multiplications.

Parameters
[in]mat- A [3x1] vector
Returns
The skew-symmetric matrix of mat

The documentation for this class was generated from the following file: