Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_RCTelemetry: throttle CRSF request RX device info messages #25494

Merged
merged 1 commit into from
Nov 13, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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