Plane: use AHRS for air density ratio

This commit is contained in:
Andrew Tridgell 2024-05-04 13:44:16 +10:00 committed by Peter Barker
parent b4ebae5e1b
commit 6e4de623df
1 changed files with 2 additions and 2 deletions

View File

@ -707,7 +707,7 @@ void Tailsitter::speed_scaling(void)
// (mass / A) is disk loading DL so: // (mass / A) is disk loading DL so:
// Ue^2 = (((t / t_h) * DL * 9.81)/(0.5 * rho)) + U0^2 // 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; float hover_rho = rho;
if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) {
// if applying altitude correction use sea level density for hover case // 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) { if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) {
// air density correction // 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[] = { const SRV_Channel::Aux_servo_function_t functions[] = {