mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: conform to new time conversion API
This commit is contained in:
parent
42b4730d88
commit
605e0de03c
|
@ -141,7 +141,7 @@ void AP_IOMCU_FW::init()
|
|||
|
||||
void AP_IOMCU_FW::update()
|
||||
{
|
||||
eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(1));
|
||||
eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(1));
|
||||
|
||||
if (do_reboot && (AP_HAL::millis() > reboot_time)) {
|
||||
hal.scheduler->reboot(true);
|
||||
|
|
Loading…
Reference in New Issue