Skip to content
Snippets Groups Projects
Commit 3f9bd65d authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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.
parent a84a08d2
No related branches found
No related tags found
No related merge requests found
...@@ -340,7 +340,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan) ...@@ -340,7 +340,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
static void NOINLINE send_vfr_hud(mavlink_channel_t chan) static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
{ {
float aspeed; float aspeed;
if (airspeed.use()) { if (airspeed.enabled()) {
aspeed = airspeed.get_airspeed(); aspeed = airspeed.get_airspeed();
} else if (!ahrs.airspeed_estimate(&aspeed)) { } else if (!ahrs.airspeed_estimate(&aspeed)) {
aspeed = 0; aspeed = 0;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment