AP_Airspeed: added atmospheric tables for high altitude flight

this gets altitude and EAS2TAS much more accurately up to around 150k
feet AMSL. Enabled on boards using EKF double
This commit is contained in:
Andrew Tridgell 2024-04-28 16:53:12 +10:00 committed by Peter Barker
parent bae5859a92
commit 128d9b0e41
2 changed files with 4 additions and 7 deletions

View File

@ -33,11 +33,8 @@ bool AP_Airspeed_SITL::get_temperature(float &temperature)
// this was mostly swiped from SIM_Airspeed_DLVR:
const float sim_alt = sitl->state.altitude;
float sigma, delta, theta;
AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta);
// To Do: Add a sensor board temperature offset parameter
temperature = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0;
temperature = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt);
return true;
}

View File

@ -12,7 +12,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_AHRS/AP_AHRS.h>
#include "AP_Airspeed.h"
@ -131,7 +131,7 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t
// calculate true airspeed, assuming a airspeed ratio of 1.0
float dpress = MAX(get_differential_pressure(i), 0);
float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS();
float true_airspeed = sqrtf(dpress) * AP::ahrs().get_EAS2TAS();
float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
@ -177,7 +177,7 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
vy: vground.y,
vz: vground.z,
diff_pressure: get_differential_pressure(primary),
EAS2TAS: AP::baro().get_EAS2TAS(),
EAS2TAS: AP::ahrs().get_EAS2TAS(),
ratio: param[primary].ratio.get(),
state_x: state[primary].calibration.state.x,
state_y: state[primary].calibration.state.y,