From a3ca73240398ea2a848079cc0d6f3561b930f0e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 4 Nov 2015 14:53:59 +1100 Subject: [PATCH] AP_Airspeed: show health status in examples --- libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp index f4dc5fe250..b0595bc109 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp +++ b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp @@ -35,6 +35,8 @@ void setup() hal.console->println("ArduPilot Airspeed library test"); AP_Param::set_object_value(&airspeed, airspeed.var_info, "_PIN", 65); + AP_Param::set_object_value(&airspeed, airspeed.var_info, "_ENABLE", 1); + AP_Param::set_object_value(&airspeed, airspeed.var_info, "_USE", 1); airspeed.init(); airspeed.calibrate(false); @@ -46,7 +48,7 @@ void loop(void) if((hal.scheduler->millis() - timer) > 100) { timer = hal.scheduler->millis(); airspeed.read(); - hal.console->printf("airspeed %.2f\n", airspeed.get_airspeed()); + hal.console->printf("airspeed %.2f healthy=%u\n", airspeed.get_airspeed(), airspeed.healthy()); } hal.scheduler->delay(1); }