mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_RCTelemetry: apply a 5s hysteresis to RF mode changes and rate reporting
This commit is contained in:
parent
23158480c7
commit
ecfcd98f8a
@ -148,10 +148,10 @@ void AP_CRSF_Telem::process_rf_mode_changes()
|
||||
{
|
||||
const AP_RCProtocol_CRSF::RFMode current_rf_mode = get_rf_mode();
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if ( _telem_rf_mode != current_rf_mode
|
||||
// report a change of more than 10Hz if we haven't done so in the last 5s
|
||||
|| (now - _telem_last_report_ms > 5000 && abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 10)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "CRSF: rf mode change %d->%d, rate is %dHz", (uint8_t)_telem_rf_mode, (uint8_t)current_rf_mode, _scheduler.avg_packet_rate);
|
||||
// report a change in RF mode or a chnage of more than 10Hz if we haven't done so in the last 5s
|
||||
if ((now - _telem_last_report_ms > 5000) &&
|
||||
(_telem_rf_mode != current_rf_mode || abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 25)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "CRSF: RF mode %d, rate is %dHz", (uint8_t)current_rf_mode, _scheduler.avg_packet_rate);
|
||||
update_custom_telemetry_rates(current_rf_mode);
|
||||
_telem_rf_mode = current_rf_mode;
|
||||
_telem_last_avg_rate = _scheduler.avg_packet_rate;
|
||||
|
Loading…
Reference in New Issue
Block a user