mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_ServoRelayEvents: use millis/micros/panic functions
This commit is contained in:
parent
81186e5416
commit
7c9a5dc1b9
@ -99,11 +99,11 @@ bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, ui
|
|||||||
*/
|
*/
|
||||||
void AP_ServoRelayEvents::update_events(void)
|
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;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
start_time_ms = hal.scheduler->millis();
|
start_time_ms = AP_HAL::millis();
|
||||||
|
|
||||||
switch (type) {
|
switch (type) {
|
||||||
case EVENT_TYPE_SERVO:
|
case EVENT_TYPE_SERVO:
|
||||||
|
Loading…
Reference in New Issue
Block a user