SITL: Sub: add angular drag based on a laminar, external flow

This commit is contained in:
Willian Galvani 2019-09-23 12:49:00 -03:00 committed by Andrew Tridgell
parent 6bcd2162b9
commit efddff71bf
2 changed files with 23 additions and 6 deletions

View File

@ -153,17 +153,33 @@ void Submarine::calculate_drag_force(const Vector3f &velocity, const Vector3f &d
}
/**
* @brief Calculate angular drag torque
* @brief Calculate angular drag torque using the equivalente sphere area and assuming a laminar external flow.
*
* $F_D = C_D*A*\rho*V^2/2$
* where:
* $F_D$ is the drag force
* $C_D$ is the drag coefficient
* $A$ is the surface area in contact with the fluid
* $/rho$ is the fluid density (1000kg/m³ for water)
* $V$ is the fluid velocity velocity relative to the surface
*
* @param angular_velocity Body frame velocity of fluid
* @param drag_coefficient Rotational drag coefficient of body
*/
void Submarine::calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque)
{
// TODO: Find a good approximation for this.
// While this works, it is not accurate nor has the right dimensions.
torque = angular_velocity;
torque *= drag_coefficient;
/**
* @brief It's necessary to keep the velocity orientation from the body frame.
* To do so, a mathematical artifice is used to do velocity square but without loosing the direction.
* $(|V|/V)*V^2$ = $|V|*V$
*/
Vector3f v_2(
fabsf(angular_velocity.x) * angular_velocity.x,
fabsf(angular_velocity.y) * angular_velocity.y,
fabsf(angular_velocity.z) * angular_velocity.z
);
Vector3f f_d = v_2 *= drag_coefficient * frame_property.equivalent_sphere_area * 1000 / 2;
torque = f_d * frame_property.equivalent_sphere_radius;
}

View File

@ -81,7 +81,8 @@ protected:
// Frame drag coefficient
const Vector3f linear_drag_coefficient = Vector3f(0.2, 0.3, 0.4);
const Vector3f angular_drag_coefficient = Vector3f(5, 5, 5);
// Angular drag coefficient CD for a cube is 1.05. This is subject to change based on experimentation.
const Vector3f angular_drag_coefficient = Vector3f(1.05, 1.05, 1.05);
// Calculate total volume from water buoyancy
// $ V = F_b / (rho * g) $
// V = volume (m^3), rho = water density (kg/m^3), g = gravity (m/s^2), F_b = force (N)