mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: added get_air_density_ratio()
This commit is contained in:
parent
6e4de623df
commit
5a439bb9b7
|
@ -3570,6 +3570,13 @@ float AP_AHRS::get_EAS2TAS(void) const
|
|||
return 1.0;
|
||||
}
|
||||
|
||||
// get air density / sea level density - decreases as altitude climbs
|
||||
float AP_AHRS::get_air_density_ratio(void) const
|
||||
{
|
||||
const float eas2tas = get_EAS2TAS();
|
||||
return 1.0 / sq(eas2tas);
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
AP_AHRS *AP_AHRS::_singleton;
|
||||
|
||||
|
|
|
@ -143,6 +143,9 @@ public:
|
|||
// get apparent to true airspeed ratio
|
||||
float get_EAS2TAS(void) const;
|
||||
|
||||
// get air density / sea level density - decreases as altitude climbs
|
||||
float get_air_density_ratio(void) const;
|
||||
|
||||
// return an airspeed estimate if available. return true
|
||||
// if we have an estimate
|
||||
bool airspeed_estimate(float &airspeed_ret) const;
|
||||
|
|
|
@ -265,7 +265,7 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
|||
|
||||
// get apparent to true airspeed ratio
|
||||
float AP_AHRS_Backend::get_EAS2TAS(void) {
|
||||
return AP::baro().get_EAS2TAS();
|
||||
return AP::baro()._get_EAS2TAS();
|
||||
}
|
||||
|
||||
// return current vibration vector for primary IMU
|
||||
|
|
Loading…
Reference in New Issue