mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: report tracer frame rate correctly
This commit is contained in:
parent
de730eef64
commit
352bc482af
|
@ -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 {
|
||||
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