AP_RCTelemetry: throttle CRSF request RX device info messages

This commit is contained in:
olliw42 2023-11-08 18:42:46 +01:00 committed by Andrew Tridgell
parent c4e2c4f7cb
commit 61aec54ea7
2 changed files with 6 additions and 1 deletions

View File

@ -468,7 +468,11 @@ void AP_CRSF_Telem::process_packet(uint8_t idx)
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string());
} else {
calc_device_ping(AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER);
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string());
uint32_t tnow_ms = AP_HAL::millis();
if ((tnow_ms - _crsf_version.last_request_info_ms) > 5000) {
_crsf_version.last_request_info_ms = tnow_ms;
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string());
}
}
break;
case DEVICE_PING:

View File

@ -335,6 +335,7 @@ private:
bool use_rf_mode;
AP_RCProtocol_CRSF::ProtocolType protocol;
bool pending = true;
uint32_t last_request_info_ms;
} _crsf_version;
struct {