diff --git a/libraries/AP_IOMCU/iofirmware/rc.cpp b/libraries/AP_IOMCU/iofirmware/rc.cpp index 20d08e19ce..ad6f562b1b 100644 --- a/libraries/AP_IOMCU/iofirmware/rc.cpp +++ b/libraries/AP_IOMCU/iofirmware/rc.cpp @@ -28,7 +28,7 @@ extern const AP_HAL::HAL& hal; // usart3 is for SBUS input and output -static const SerialConfig uart3_cfg = { +static const SerialConfig sbus_cfg = { 100000, // speed USART_CR1_PCE | USART_CR1_M, // cr1, enable even parity USART_CR2_STOP_1, // cr2, two stop bits @@ -40,15 +40,19 @@ static const SerialConfig uart3_cfg = { // listen for parity errors on sd3 input static event_listener_t sd3_listener; +static uint8_t sd3_config; + void sbus_out_write(uint16_t *channels, uint8_t nchannels) { - uint8_t buffer[25]; - AP_SBusOut::sbus_format_frame(channels, nchannels, buffer); - chnWrite(&SD3, buffer, sizeof(buffer)); + if (sd3_config == 0) { + uint8_t buffer[25]; + AP_SBusOut::sbus_format_frame(channels, nchannels, buffer); + chnWrite(&SD3, buffer, sizeof(buffer)); + } } // usart1 is for DSM input and (optionally) debug to FMU -static const SerialConfig uart1_cfg = { +static const SerialConfig dsm_cfg = { 115200, // speed 0, // cr1 0, // cr2 @@ -62,16 +66,17 @@ static const SerialConfig uart1_cfg = { */ void AP_IOMCU_FW::rcin_serial_init(void) { - sdStart(&SD1, &uart1_cfg); - sdStart(&SD3, &uart3_cfg); + sdStart(&SD1, &dsm_cfg); + sdStart(&SD3, &sbus_cfg); chEvtRegisterMaskWithFlags(chnGetEventSource(&SD3), &sd3_listener, EVENT_MASK(1), SD_PARITY_ERROR); // disable input for SBUS with pulses, we will use the UART for - // SBUS. + // SBUS and FPORT AP::RC().disable_for_pulses(AP_RCProtocol::SBUS); AP::RC().disable_for_pulses(AP_RCProtocol::SBUS_NI); + AP::RC().disable_for_pulses(AP_RCProtocol::FPORT); } static struct { @@ -79,6 +84,7 @@ static struct { uint32_t num_sbus_bytes; uint32_t num_sbus_errors; eventflags_t sbus_error; + uint32_t last_good_ms; } rc_stats; /* @@ -88,13 +94,19 @@ void AP_IOMCU_FW::rcin_serial_update(void) { uint8_t b[16]; uint32_t n; + uint32_t now = AP_HAL::millis(); // read from DSM port if ((n = chnReadTimeout(&SD1, b, sizeof(b), TIME_IMMEDIATE)) > 0) { n = MIN(n, sizeof(b)); - rc_stats.num_dsm_bytes += n; - for (uint8_t i=0; i 0) { eventflags_t flags; - if ((flags = chEvtGetAndClearFlags(&sd3_listener)) & SD_PARITY_ERROR) { + if (sd3_config == 0 && ((flags = chEvtGetAndClearFlags(&sd3_listener)) & SD_PARITY_ERROR)) { rc_stats.sbus_error = flags; rc_stats.num_sbus_errors++; } else { n = MIN(n, sizeof(b)); rc_stats.num_sbus_bytes += n; for (uint8_t i=0; i 2000) { + rc_stats.last_good_ms = now; + sd3_config ^= 1; + sdStop(&SD3); + sdStart(&SD3, sd3_config==0?&sbus_cfg:&dsm_cfg); + } + } /*