mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Baro: expose get_altitude_difference()
this is useful for pressure altitude calculations
This commit is contained in:
parent
b3d84cec81
commit
41dd280739
@ -129,13 +129,33 @@ void AP_Baro::update_calibration()
|
||||
_ground_temperature.set(get_temperature());
|
||||
}
|
||||
|
||||
// return altitude difference in meters between current pressure and a
|
||||
// given base_pressure in Pascal
|
||||
float AP_Baro::get_altitude_difference(float base_pressure, float pressure)
|
||||
{
|
||||
float ret;
|
||||
#if HAL_CPU_CLASS <= HAL_CPU_CLASS_16
|
||||
// on slower CPUs use a less exact, but faster, calculation
|
||||
float scaling = base_pressure / pressure;
|
||||
float temp = _ground_temperature + 273.15f;
|
||||
ret = logf(scaling) * temp * 29.271267f;
|
||||
#else
|
||||
// on faster CPUs use a more exact calculation
|
||||
float scaling = pressure / base_pressure;
|
||||
float temp = _ground_temperature + 273.15f;
|
||||
|
||||
// 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)));
|
||||
#endif
|
||||
return ret;
|
||||
}
|
||||
|
||||
// return current altitude estimate relative to time that calibrate()
|
||||
// was called. Returns altitude in meters
|
||||
// note that this relies on read() being called regularly to get new data
|
||||
float AP_Baro::get_altitude(void)
|
||||
{
|
||||
float scaling, temp;
|
||||
|
||||
if (_ground_pressure == 0) {
|
||||
// called before initialisation
|
||||
return 0;
|
||||
@ -146,21 +166,7 @@ float AP_Baro::get_altitude(void)
|
||||
return _altitude + _alt_offset;
|
||||
}
|
||||
|
||||
|
||||
#if HAL_CPU_CLASS <= HAL_CPU_CLASS_16
|
||||
// on slower CPUs use a less exact, but faster, calculation
|
||||
scaling = (float)_ground_pressure / (float)get_pressure();
|
||||
temp = ((float)_ground_temperature) + 273.15f;
|
||||
_altitude = logf(scaling) * temp * 29.271267f;
|
||||
#else
|
||||
// on faster CPUs use a more exact calculation
|
||||
scaling = (float)get_pressure() / (float)_ground_pressure;
|
||||
temp = ((float)_ground_temperature) + 273.15f;
|
||||
|
||||
// This is an exact calculation that is within +-2.5m of the standard atmosphere tables
|
||||
// in the troposphere (up to 11,000 m amsl).
|
||||
_altitude = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)));
|
||||
#endif
|
||||
_altitude = get_altitude_difference(_ground_pressure, get_pressure());
|
||||
|
||||
_last_altitude_t = _last_update;
|
||||
|
||||
|
@ -41,6 +41,10 @@ public:
|
||||
// of the last calibrate() call
|
||||
float get_altitude(void);
|
||||
|
||||
// get altitude difference in meters relative given a base
|
||||
// pressure in Pascal
|
||||
float get_altitude_difference(float base_pressure, float pressure);
|
||||
|
||||
// get scale factor required to convert equivalent to true airspeed
|
||||
float get_EAS2TAS(void);
|
||||
|
||||
@ -67,7 +71,7 @@ public:
|
||||
}
|
||||
|
||||
// get last time sample was taken (in ms)
|
||||
uint32_t get_last_update() { return _last_update; };
|
||||
uint32_t get_last_update() const { return _last_update; };
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user