Browse Source

Baro: example sketch to use healthy() function

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
78b1bf8282
  1. 5
      libraries/AP_Baro/examples/BARO_generic/BARO_generic.pde

5
libraries/AP_Baro/examples/BARO_generic/BARO_generic.pde

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

Loading…
Cancel
Save