Skip to content

Commit

Permalink
AP_Motors: use AHRS for get_air_density_ratio()
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed May 7, 2024
1 parent 56a6eda commit 7d55f64
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "AP_Motors_Class.h"
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

#define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5 // battery voltage filtered at 0.5hz
Expand Down Expand Up @@ -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);
}
Expand Down

0 comments on commit 7d55f64

Please sign in to comment.