AP_RCTelemetry: warn if using CRSF on non-DMA channel

don't produce rf_mode messages when not using CRSF for RC control
This commit is contained in:
Andy Piper 2021-05-01 13:01:16 +01:00 committed by Andrew Tridgell
parent f6b9479542
commit 94d4252a2a

View File

@ -148,8 +148,19 @@ 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();
// the presence of a uart indicates that we are using CRSF for RC control
AP_RCProtocol_CRSF* crsf = AP::crsf();
AP_HAL::UARTDriver* uart = nullptr;
if (crsf != nullptr) {
uart = crsf->get_UART();
}
// warn the user if their setup is sub-optimal
if (_telem_last_report_ms == 0 && uart != nullptr && !uart->is_dma_enabled()) {
gcs().send_text(MAV_SEVERITY_WARNING, "CRSF: running on non-DMA serial port");
}
// 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) &&
if ((now - _telem_last_report_ms > 5000) && uart != nullptr &&
(_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);