mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_RCTelemetry: warn if Passthru miss-configured
Co-authored-by: Alessandro Apostoli <30294218+yaapu@users.noreply.github.com>
This commit is contained in:
parent
54d92551d1
commit
89246739c4
@ -94,6 +94,14 @@ void AP_CRSF_Telem::setup_custom_telemetry()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check if passthru already assigned
|
||||||
|
const int8_t frsky_port = AP::serialmanager().find_portnum(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough,0);
|
||||||
|
if (frsky_port != -1) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "CRSF: passthrough telemetry conflict on SERIAL%d",frsky_port);
|
||||||
|
_custom_telem.init_done = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// we need crossfire firmware version
|
// we need crossfire firmware version
|
||||||
if (_crsf_version.pending) {
|
if (_crsf_version.pending) {
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user