diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index cd21896afe7d7..43f68c4c6a13f 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -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: diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h index 9bbeeaf03a29b..431ceebff7acf 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h @@ -335,6 +335,7 @@ class AP_CRSF_Telem : public AP_RCTelemetry { bool use_rf_mode; AP_RCProtocol_CRSF::ProtocolType protocol; bool pending = true; + uint32_t last_request_info_ms; } _crsf_version; struct {