AP_Baro: fix bug in alt error arming check

get_altitude_difference already subtracts MSL altitude
This commit is contained in:
Bob Long 2023-02-07 15:59:29 -05:00 committed by Randy Mackay
parent a4835634e0
commit 3fbeda3e1d
1 changed files with 2 additions and 1 deletions

View File

@ -1088,7 +1088,8 @@ bool AP_Baro::arming_checks(size_t buflen, char *buffer) const
const auto &gps = AP::gps();
if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) {
const float alt_amsl = gps.location().alt*0.01;
const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure());
// note the addition of _field_elevation_active as this is subtracted in get_altitude_difference()
const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()) + _field_elevation_active;
const float error = fabsf(alt_amsl - alt_pressure);
if (error > _alt_error_max) {
hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error);