From 6e4de623df9faf5db0642f85e31f1e4374b0e613 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2024 13:44:16 +1000 Subject: [PATCH] Plane: use AHRS for air density ratio --- ArduPlane/tailsitter.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 3df68e3bc3..bac8e4d9f7 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -707,7 +707,7 @@ void Tailsitter::speed_scaling(void) // (mass / A) is disk loading DL so: // Ue^2 = (((t / t_h) * DL * 9.81)/(0.5 * rho)) + U0^2 - const float rho = SSL_AIR_DENSITY * plane.barometer.get_air_density_ratio(); + const float rho = SSL_AIR_DENSITY * quadplane.ahrs.get_air_density_ratio(); float hover_rho = rho; if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // if applying altitude correction use sea level density for hover case @@ -752,7 +752,7 @@ void Tailsitter::speed_scaling(void) if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // air density correction - spd_scaler /= plane.barometer.get_air_density_ratio(); + spd_scaler /= quadplane.ahrs.get_air_density_ratio(); } const SRV_Channel::Aux_servo_function_t functions[] = {