mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_AHRS: remove unused base-class airspeed_estimate method
This commit is contained in:
parent
676c36bad4
commit
ad435dcdbb
@ -179,26 +179,6 @@ Vector3f AP_AHRS::get_gyro_latest(void) const
|
|||||||
return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
|
return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
|
||||||
}
|
}
|
||||||
|
|
||||||
// return airspeed estimate if available
|
|
||||||
bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
|
|
||||||
{
|
|
||||||
if (airspeed_sensor_enabled()) {
|
|
||||||
airspeed_ret = _airspeed->get_airspeed();
|
|
||||||
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
|
||||||
// constrain the airspeed by the ground speed
|
|
||||||
// and AHRS_WIND_MAX
|
|
||||||
const float gnd_speed = AP::gps().ground_speed();
|
|
||||||
float true_airspeed = airspeed_ret * get_EAS2TAS();
|
|
||||||
true_airspeed = constrain_float(true_airspeed,
|
|
||||||
gnd_speed - _wind_max,
|
|
||||||
gnd_speed + _wind_max);
|
|
||||||
airspeed_ret = true_airspeed / get_EAS2TAS();
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set_trim
|
// set_trim
|
||||||
void AP_AHRS::set_trim(const Vector3f &new_trim)
|
void AP_AHRS::set_trim(const Vector3f &new_trim)
|
||||||
{
|
{
|
||||||
|
@ -260,7 +260,7 @@ public:
|
|||||||
|
|
||||||
// return an airspeed estimate if available. return true
|
// return an airspeed estimate if available. return true
|
||||||
// if we have an estimate
|
// if we have an estimate
|
||||||
virtual bool airspeed_estimate(float &airspeed_ret) const WARN_IF_UNUSED;
|
virtual bool airspeed_estimate(float &airspeed_ret) const WARN_IF_UNUSED = 0;
|
||||||
|
|
||||||
// return a true airspeed estimate (navigation airspeed) if
|
// return a true airspeed estimate (navigation airspeed) if
|
||||||
// available. return true if we have an estimate
|
// available. return true if we have an estimate
|
||||||
|
Loading…
Reference in New Issue
Block a user