mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_IOMCU: fixed oneshot support in IO firmware
This commit is contained in:
parent
2c7e27374f
commit
cfb10fbb2f
@ -141,15 +141,18 @@ void AP_IOMCU_FW::init()
|
||||
|
||||
void AP_IOMCU_FW::update()
|
||||
{
|
||||
chEvtWaitAnyTimeout(~0, MS2ST(1));
|
||||
eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(1));
|
||||
|
||||
if (do_reboot && (AP_HAL::millis() > reboot_time)) {
|
||||
hal.scheduler->reboot(true);
|
||||
while(true){}
|
||||
}
|
||||
|
||||
// always do pwm update
|
||||
pwm_out_update();
|
||||
if ((mask & EVENT_MASK(IOEVENT_PWM)) ||
|
||||
(last_safety_off != reg_status.flag_safety_off)) {
|
||||
last_safety_off = reg_status.flag_safety_off;
|
||||
pwm_out_update();
|
||||
}
|
||||
|
||||
// run remaining functions at 1kHz
|
||||
uint32_t now = AP_HAL::millis();
|
||||
|
@ -95,5 +95,6 @@ private:
|
||||
uint32_t last_loop_ms;
|
||||
bool oneshot_enabled;
|
||||
thread_t *thread_ctx;
|
||||
bool last_safety_off;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user