|
|
|
@ -300,6 +300,8 @@ void AP_IOMCU_FW::rcin_update()
@@ -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()
@@ -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() |
|
|
|
|