AP_IOMCU: use more efficient read API for rcin
This commit is contained in:
parent
07ee3b4c5e
commit
289a0d8694
@ -301,9 +301,7 @@ void AP_IOMCU_FW::rcin_update()
|
||||
if (hal.rcin->new_input()) {
|
||||
rc_input.count = hal.rcin->num_channels();
|
||||
rc_input.flags_rc_ok = true;
|
||||
for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS; i++) {
|
||||
rc_input.pwm[i] = hal.rcin->read(i);
|
||||
}
|
||||
hal.rcin->read(rc_input.pwm, IOMCU_MAX_CHANNELS);
|
||||
rc_last_input_ms = last_ms;
|
||||
rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected();
|
||||
} else if (last_ms - rc_last_input_ms > 200U) {
|
||||
@ -315,6 +313,7 @@ void AP_IOMCU_FW::rcin_update()
|
||||
}
|
||||
if (update_default_rate) {
|
||||
hal.rcout->set_default_rate(reg_setup.pwm_defaultrate);
|
||||
update_default_rate = false;
|
||||
}
|
||||
|
||||
bool old_override = override_active;
|
||||
|
Loading…
Reference in New Issue
Block a user