From 7d55f6486893982bd0bf8636769a64d5a80367c5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2024 13:44:15 +1000 Subject: [PATCH] AP_Motors: use AHRS for get_air_density_ratio() --- libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp index ff2114864a4556..437cb4b560d725 100644 --- a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp +++ b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp @@ -3,6 +3,7 @@ #include "AP_Motors_Class.h" #include #include +#include #include #define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5 // battery voltage filtered at 0.5hz @@ -193,7 +194,7 @@ float Thrust_Linearization::get_compensation_gain() const #if AP_MOTORS_DENSITY_COMP == 1 // air density ratio is increasing in density / decreasing in altitude - const float air_density_ratio = AP::baro().get_air_density_ratio(); + const float air_density_ratio = AP::ahrs().get_air_density_ratio(); if (air_density_ratio > 0.3 && air_density_ratio < 1.5) { ret *= 1.0 / constrain_float(air_density_ratio, 0.5, 1.25); }