mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: check that CRSF and GHST have been detected before sending a version ping or doing rf changes
This commit is contained in:
parent
407b8a6003
commit
567c7a2b1b
|
@ -185,9 +185,14 @@ bool AP_CRSF_Telem::process_rf_mode_changes()
|
||||||
if (crsf != nullptr) {
|
if (crsf != nullptr) {
|
||||||
uart = crsf->get_UART();
|
uart = crsf->get_UART();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (uart == nullptr) {
|
if (uart == nullptr) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!crsf->is_detected()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
// not ready yet
|
// not ready yet
|
||||||
if (!uart->is_initialized()) {
|
if (!uart->is_initialized()) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -402,11 +407,11 @@ bool AP_CRSF_Telem::is_packet_ready(uint8_t idx, bool queue_empty)
|
||||||
case GENERAL_COMMAND:
|
case GENERAL_COMMAND:
|
||||||
return _baud_rate_request.pending;
|
return _baud_rate_request.pending;
|
||||||
case VERSION_PING:
|
case VERSION_PING:
|
||||||
return _crsf_version.pending;
|
return _crsf_version.pending && AP::crsf()->is_detected(); // only send pings if protocol has been detected
|
||||||
case HEARTBEAT:
|
case HEARTBEAT:
|
||||||
return true; // always send heartbeat if enabled
|
return true; // always send heartbeat if enabled
|
||||||
case DEVICE_PING:
|
case DEVICE_PING:
|
||||||
return !_crsf_version.pending; // only send pings if version has been negotiated
|
return !_crsf_version.pending; // only send pings if version has been negotiated
|
||||||
default:
|
default:
|
||||||
return _enable_telemetry;
|
return _enable_telemetry;
|
||||||
}
|
}
|
||||||
|
|
|
@ -111,9 +111,14 @@ bool AP_GHST_Telem::process_rf_mode_changes()
|
||||||
if (ghost != nullptr) {
|
if (ghost != nullptr) {
|
||||||
uart = ghost->get_UART();
|
uart = ghost->get_UART();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (uart == nullptr) {
|
if (uart == nullptr) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!ghost->is_detected()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
// not ready yet
|
// not ready yet
|
||||||
if (!uart->is_initialized()) {
|
if (!uart->is_initialized()) {
|
||||||
return false;
|
return false;
|
||||||
|
|
Loading…
Reference in New Issue