AP_RCProtocol: report tracer frame rate correctly

This commit is contained in:
Andy Piper 2023-07-01 14:45:16 +01:00 committed by Peter Barker
parent de7ef61a29
commit 50e95b6919
1 changed files with 2 additions and 0 deletions

View File

@ -202,6 +202,8 @@ const char* AP_RCProtocol_CRSF::get_protocol_string(ProtocolType protocol) const
uint16_t AP_RCProtocol_CRSF::get_link_rate(ProtocolType protocol) const { uint16_t AP_RCProtocol_CRSF::get_link_rate(ProtocolType protocol) const {
if (protocol == ProtocolType::PROTOCOL_ELRS) { if (protocol == ProtocolType::PROTOCOL_ELRS) {
return RF_MODE_RATES[_link_status.rf_mode + RFMode::ELRS_RF_MODE_4HZ]; return RF_MODE_RATES[_link_status.rf_mode + RFMode::ELRS_RF_MODE_4HZ];
} else if (protocol == ProtocolType::PROTOCOL_TRACER) {
return 250;
} else { } else {
return RF_MODE_RATES[_link_status.rf_mode]; return RF_MODE_RATES[_link_status.rf_mode];
} }