Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Prevent conflicts between CRSF and GHST leading to radio failsafes #26118

Merged
merged 1 commit into from
Feb 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,10 @@ class AP_RCProtocol_Backend {
return frontend.rc_protocols_mask;
}

bool protocol_enabled(enum AP_RCProtocol::rcprotocol_t protocol) const {
return frontend.protocol_enabled(protocol);
}

// get RSSI
int16_t get_RSSI(void) const {
return rssi;
Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,10 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte)
return;
}

if (_frame.device_address != DeviceAddress::CRSF_ADDRESS_FLIGHT_CONTROLLER) {
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
return;
}

// parse the length
if (_frame_ofs == CSRF_HEADER_TYPE_LEN) {
_frame_crc = crc8_dvb_s2(0, _frame.type);
Expand Down Expand Up @@ -617,7 +621,7 @@ void AP_RCProtocol_CRSF::process_handshake(uint32_t baudrate)
|| baudrate != CRSF_BAUDRATE
|| baudrate == get_bootstrap_baud_rate()
|| uart->get_baud_rate() == get_bootstrap_baud_rate()
|| (get_rc_protocols_mask() & ((1U<<(uint8_t(AP_RCProtocol::CRSF)+1))+1)) == 0) {
|| !protocol_enabled(AP_RCProtocol::CRSF)) {
return;
}

Expand Down
11 changes: 8 additions & 3 deletions libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,10 @@ void AP_RCProtocol_GHST::_process_byte(uint32_t timestamp_us, uint8_t byte)
return;
}

if (_frame.device_address != DeviceAddress::GHST_ADDRESS_FLIGHT_CONTROLLER) {
return;
}

// parse the length
if (_frame_ofs == GHST_HEADER_TYPE_LEN) {
_frame_crc = crc8_dvb_s2(0, _frame.type);
Expand Down Expand Up @@ -421,17 +425,18 @@ void AP_RCProtocol_GHST::process_byte(uint8_t byte, uint32_t baudrate)
_process_byte(AP_HAL::micros(), byte);
}

// change the bootstrap baud rate to ELRS standard if configured
// change the bootstrap baud rate to Ghost standard if configured
void AP_RCProtocol_GHST::process_handshake(uint32_t baudrate)
{
AP_HAL::UARTDriver *uart = get_current_UART();

// only change the baudrate if we are bootstrapping CRSF
// only change the baudrate if we are specifically bootstrapping Ghost
if (uart == nullptr
|| baudrate != CRSF_BAUDRATE
|| baudrate == GHST_BAUDRATE
|| uart->get_baud_rate() == GHST_BAUDRATE
|| (get_rc_protocols_mask() & ((1U<<(uint8_t(AP_RCProtocol::GHST)+1))+1)) == 0) {
|| !protocol_enabled(AP_RCProtocol::GHST)
|| protocol_enabled(AP_RCProtocol::CRSF)) {
return;
}

Expand Down
Loading