AP_IOMCU: fixed handling of RC_OPTIONS bit to ignore RC failsafe bit

this worked on FMU but not on IOMCU
This commit is contained in:
Andrew Tridgell 2022-03-16 21:03:09 +11:00
parent 522173328c
commit ce0b7a8957
2 changed files with 7 additions and 3 deletions

View File

@ -301,12 +301,14 @@ void AP_IOMCU_FW::rcin_update()
{
((ChibiOS::RCInput *)hal.rcin)->_timer_tick();
if (hal.rcin->new_input()) {
const auto &rc = AP::RC();
rc_input.count = hal.rcin->num_channels();
rc_input.flags_rc_ok = true;
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();
rc_input.rssi = AP::RC().get_RSSI();
rc_input.rc_protocol = (uint16_t)rc.protocol_detected();
rc_input.rssi = rc.get_RSSI();
rc_input.flags_failsafe = rc.failsafe_active();
} else if (last_ms - rc_last_input_ms > 200U) {
rc_input.flags_rc_ok = false;
}

View File

@ -159,9 +159,11 @@ struct page_mixing {
// enabled needs to be 1 to enable mixing
uint8_t enabled;
uint8_t pad; // pad to even size
uint8_t pad;
};
static_assert(sizeof(struct page_mixing) % 2 == 0, "page_mixing must be even size");
struct __attribute__((packed, aligned(2))) page_GPIO {
uint8_t channel_mask;
uint8_t output_mask;