Skip to content

Commit

Permalink
AP_RCTelemetry: throttle CRSF request RX device info messages
Browse files Browse the repository at this point in the history
  • Loading branch information
olliw42 authored and tridge committed Nov 13, 2023
1 parent c4e2c4f commit 61aec54
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 1 deletion.
6 changes: 5 additions & 1 deletion libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RCTelemetry/AP_CRSF_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down

0 comments on commit 61aec54

Please sign in to comment.