mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
APM: send airspeed sensor value, not estimate, when enabled
this solves the problem of people reporting that airspeed is not shown when ARSPD_USE is zero.
This commit is contained in:
parent
a84a08d2a4
commit
3f9bd65d2f
@ -340,7 +340,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
|
||||
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
{
|
||||
float aspeed;
|
||||
if (airspeed.use()) {
|
||||
if (airspeed.enabled()) {
|
||||
aspeed = airspeed.get_airspeed();
|
||||
} else if (!ahrs.airspeed_estimate(&aspeed)) {
|
||||
aspeed = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user