AP_RCProtocol: rescan at CRSFv3 baud rates to avoid RX loss on soft reboot

This commit is contained in:
Andy Piper 2023-07-01 14:58:32 +01:00 committed by Randy Mackay
parent d5b01ee404
commit de730eef64
2 changed files with 6 additions and 2 deletions

View File

@ -277,6 +277,8 @@ static const AP_RCProtocol::SerialConfig serial_configs[] {
#endif
// CrossFire:
{ 416666, 0, 1, false },
// CRSFv3 can negotiate higher rates which are sticky on soft reboot
{ 2000000, 0, 1, false },
};
static_assert(ARRAY_SIZE(serial_configs) > 1, "must have at least one serial config");

View File

@ -152,6 +152,8 @@ static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0)
#define CRSF_DIGITAL_CHANNEL_MIN 172
#define CRSF_DIGITAL_CHANNEL_MAX 1811
#define CRSF_BAUDRATE_1MBIT 1000000U
#define CRSF_BAUDRATE_2MBIT 2000000U
const uint16_t AP_RCProtocol_CRSF::RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES] = {
4, 50, 150, 250, // CRSF
@ -561,7 +563,7 @@ void AP_RCProtocol_CRSF::process_link_stats_tx_frame(const void* data)
void AP_RCProtocol_CRSF::process_byte(uint8_t byte, uint32_t baudrate)
{
// reject RC data if we have been configured for standalone mode
if (baudrate != CRSF_BAUDRATE || _uart) {
if ((baudrate != CRSF_BAUDRATE && baudrate != CRSF_BAUDRATE_1MBIT && baudrate != CRSF_BAUDRATE_2MBIT) || _uart) {
return;
}
_process_byte(AP_HAL::micros(), byte);
@ -590,7 +592,7 @@ bool AP_RCProtocol_CRSF::change_baud_rate(uint32_t baudrate)
return false;
}
#endif
if (baudrate > 2000000) {
if (baudrate > CRSF_BAUDRATE_2MBIT) {
return false;
}