Browse Source

AP_Airspeed: show health status in examples

master
Andrew Tridgell 9 years ago
parent
commit
a3ca732403
  1. 4
      libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp

4
libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp

@ -35,6 +35,8 @@ void setup() @@ -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) @@ -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);
}

Loading…
Cancel
Save