mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
GCS_Common: return airspeed sensor value in vfr_hud_airspeed
This commit is contained in:
parent
18c494b25f
commit
879f250fac
@ -1730,6 +1730,10 @@ void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position)
|
||||
|
||||
float GCS_MAVLINK::vfr_hud_airspeed() const
|
||||
{
|
||||
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||
if (airspeed != nullptr && airspeed->healthy()) {
|
||||
return airspeed->get_airspeed();
|
||||
}
|
||||
// because most vehicles don't have airspeed sensors, we return a
|
||||
// different sort of speed estimate in the relevant field for
|
||||
// comparison's sake.
|
||||
|
Loading…
Reference in New Issue
Block a user