Browse Source

AP_Baro: examples use millis/micros/panic functions

master
Caio Marcelo de Oliveira Filho 9 years ago committed by Randy Mackay
parent
commit
8cce3067f4
  1. 8
      libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp

8
libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp

@ -21,21 +21,21 @@ void setup() @@ -21,21 +21,21 @@ void setup()
barometer.init();
barometer.calibrate();
timer = hal.scheduler->micros();
timer = AP_HAL::micros();
}
void loop()
{
// run accumulate() at 50Hz and update() at 10Hz
if((hal.scheduler->micros() - timer) > 20*1000UL) {
timer = hal.scheduler->micros();
if((AP_HAL::micros() - timer) > 20*1000UL) {
timer = AP_HAL::micros();
barometer.accumulate();
if (counter++ < 5) {
return;
}
counter = 0;
barometer.update();
uint32_t read_time = hal.scheduler->micros() - timer;
uint32_t read_time = AP_HAL::micros() - timer;
float alt = barometer.get_altitude();
if (!barometer.healthy()) {
hal.console->println("not healthy");

Loading…
Cancel
Save