AP_ServoRelayEvents: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:14:42 +09:00 committed by Randy Mackay
parent 81186e5416
commit 7c9a5dc1b9
1 changed files with 2 additions and 2 deletions

View File

@ -99,11 +99,11 @@ bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, ui
*/
void AP_ServoRelayEvents::update_events(void)
{
if (repeat == 0 || (hal.scheduler->millis() - start_time_ms) < delay_ms) {
if (repeat == 0 || (AP_HAL::millis() - start_time_ms) < delay_ms) {
return;
}
start_time_ms = hal.scheduler->millis();
start_time_ms = AP_HAL::millis();
switch (type) {
case EVENT_TYPE_SERVO: