Browse Source

AP_ServoRelayEvents: use millis/micros/panic functions

mission-4.1.18
Caio Marcelo de Oliveira Filho 9 years ago committed by Randy Mackay
parent
commit
7c9a5dc1b9
  1. 4
      libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp

4
libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp

@ -99,11 +99,11 @@ bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, ui @@ -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:

Loading…
Cancel
Save