Skip to content

Commit

Permalink
AP_Baro: Returns directly calculated values
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Nov 10, 2023
1 parent 41850ee commit 9b621f8
Showing 1 changed file with 1 addition and 4 deletions.
5 changes: 1 addition & 4 deletions libraries/AP_Baro/AP_Baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,15 +404,12 @@ void AP_Baro::update_calibration()
// given base_pressure in Pascal
float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const
{
float ret;
float temp = C_TO_KELVIN(get_ground_temperature());
float scaling = pressure / base_pressure;

// This is an exact calculation that is within +-2.5m of the standard
// atmosphere tables in the troposphere (up to 11,000 m amsl).
ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active;

return ret;
return 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active;
}

// return sea level pressure where in which the current measured pressure
Expand Down

0 comments on commit 9b621f8

Please sign in to comment.