AP_Airspeed: examples use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:07:16 +09:00 committed by Randy Mackay
parent 2b10e0fac0
commit 410bbe4c26
1 changed files with 2 additions and 2 deletions

View File

@ -45,8 +45,8 @@ void setup()
void loop(void)
{
static uint32_t timer;
if((hal.scheduler->millis() - timer) > 100) {
timer = hal.scheduler->millis();
if((AP_HAL::millis() - timer) > 100) {
timer = AP_HAL::millis();
airspeed.read();
hal.console->printf("airspeed %.2f healthy=%u\n", airspeed.get_airspeed(), airspeed.healthy());
}