mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_IOMCU: respond to override change more quickly
This commit is contained in:
parent
8d8853d4b7
commit
8e7695e5f0
@ -300,6 +300,8 @@ void AP_IOMCU_FW::rcin_update()
|
||||
hal.rcout->set_default_rate(reg_setup.pwm_defaultrate);
|
||||
}
|
||||
|
||||
bool old_override = override_active;
|
||||
|
||||
// check for active override channel
|
||||
if (mixing.enabled &&
|
||||
mixing.rc_chan_override > 0 &&
|
||||
@ -309,6 +311,12 @@ void AP_IOMCU_FW::rcin_update()
|
||||
} else {
|
||||
override_active = false;
|
||||
}
|
||||
if (old_override != override_active) {
|
||||
if (override_active) {
|
||||
fill_failsafe_pwm();
|
||||
}
|
||||
chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM));
|
||||
}
|
||||
}
|
||||
|
||||
void AP_IOMCU_FW::process_io_packet()
|
||||
|
Loading…
Reference in New Issue
Block a user