AP_IOMCU: fixed RCIN failsafe

This commit is contained in:
Andrew Tridgell 2018-10-06 11:04:13 +10:00
parent 7b67146bc4
commit 6ec87528db
1 changed files with 4 additions and 1 deletions

View File

@ -202,13 +202,16 @@ void AP_IOMCU_FW::heater_update()
void AP_IOMCU_FW::rcin_update() void AP_IOMCU_FW::rcin_update()
{ {
((ChibiOS::RCInput *)hal.rcin)->_timer_tick(); ((ChibiOS::RCInput *)hal.rcin)->_timer_tick();
uint32_t now = AP_HAL::micros();
if (hal.rcin->new_input()) { if (hal.rcin->new_input()) {
rc_input.count = hal.rcin->num_channels(); rc_input.count = hal.rcin->num_channels();
rc_input.flags_rc_ok = true; rc_input.flags_rc_ok = true;
for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS; i++) { for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS; i++) {
rc_input.pwm[i] = hal.rcin->read(i); rc_input.pwm[i] = hal.rcin->read(i);
} }
rc_input.last_input_us = AP_HAL::micros(); rc_input.last_input_us = now;
} else if (now - rc_input.last_input_us > 200000U) {
rc_input.flags_rc_ok = false;
} }
if (update_rcout_freq) { if (update_rcout_freq) {
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate); hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);