mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: Do uart's nullptr check first
This commit is contained in:
parent
bb00340171
commit
072420d98e
|
@ -155,12 +155,15 @@ void AP_CRSF_Telem::process_rf_mode_changes()
|
|||
if (crsf != nullptr) {
|
||||
uart = crsf->get_UART();
|
||||
}
|
||||
if (uart == nullptr) {
|
||||
return;
|
||||
}
|
||||
// warn the user if their setup is sub-optimal
|
||||
if (_telem_last_report_ms == 0 && uart != nullptr && !uart->is_dma_enabled()) {
|
||||
if (_telem_last_report_ms == 0 && !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) && uart != nullptr &&
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue