mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: report tracer frame rate correctly
This commit is contained in:
parent
016448ca40
commit
7a6065940d
@ -203,6 +203,8 @@ const char* AP_RCProtocol_CRSF::get_protocol_string(ProtocolType protocol) const
|
||||
uint16_t AP_RCProtocol_CRSF::get_link_rate(ProtocolType protocol) const {
|
||||
if (protocol == ProtocolType::PROTOCOL_ELRS) {
|
||||
return RF_MODE_RATES[_link_status.rf_mode + RFMode::ELRS_RF_MODE_4HZ];
|
||||
} else if (protocol == ProtocolType::PROTOCOL_TRACER) {
|
||||
return 250;
|
||||
} else {
|
||||
return RF_MODE_RATES[_link_status.rf_mode];
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user