mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: use millis/micros/panic functions
This commit is contained in:
parent
daee8e8e76
commit
5b06924779
|
@ -154,7 +154,7 @@ void AP_OpticalFlow_Linux::update(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// throttle reads to no more than 10hz
|
// throttle reads to no more than 10hz
|
||||||
uint32_t now = hal.scheduler->millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
if (now - last_read_ms < 100) {
|
if (now - last_read_ms < 100) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -75,7 +75,7 @@ void OpticalFlow::update(void)
|
||||||
backend->update();
|
backend->update();
|
||||||
}
|
}
|
||||||
// only healthy if the data is less than 0.5s old
|
// only healthy if the data is less than 0.5s old
|
||||||
_flags.healthy = (hal.scheduler->millis() - _last_update_ms < 500);
|
_flags.healthy = (AP_HAL::millis() - _last_update_ms < 500);
|
||||||
}
|
}
|
||||||
|
|
||||||
void OpticalFlow::setHIL(const struct OpticalFlow::OpticalFlow_state &state)
|
void OpticalFlow::setHIL(const struct OpticalFlow::OpticalFlow_state &state)
|
||||||
|
|
|
@ -22,5 +22,5 @@ extern const AP_HAL::HAL& hal;
|
||||||
void OpticalFlow_backend::_update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
|
void OpticalFlow_backend::_update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
|
||||||
{
|
{
|
||||||
frontend._state = state;
|
frontend._state = state;
|
||||||
frontend._last_update_ms = hal.scheduler->millis();
|
frontend._last_update_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue