Baro: example sketch to use healthy() function

This commit is contained in:
Randy Mackay 2014-08-13 22:51:56 +09:00
parent 76634ee8c3
commit 78b1bf8282

View File

@ -77,7 +77,8 @@ void loop()
timer = hal.scheduler->micros(); timer = hal.scheduler->micros();
barometer.read(); barometer.read();
uint32_t read_time = hal.scheduler->micros() - timer; uint32_t read_time = hal.scheduler->micros() - timer;
if (!barometer.healthy) { float alt = barometer.get_altitude();
if (!barometer.healthy()) {
hal.console->println("not healthy"); hal.console->println("not healthy");
return; return;
} }
@ -86,7 +87,7 @@ void loop()
hal.console->print(" Temperature:"); hal.console->print(" Temperature:");
hal.console->print(barometer.get_temperature()); hal.console->print(barometer.get_temperature());
hal.console->print(" Altitude:"); hal.console->print(" Altitude:");
hal.console->print(barometer.get_altitude()); hal.console->print(alt);
hal.console->printf(" climb=%.2f t=%u samples=%u", hal.console->printf(" climb=%.2f t=%u samples=%u",
barometer.get_climb_rate(), barometer.get_climb_rate(),
(unsigned)read_time, (unsigned)read_time,