mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: only use the first defined serial port for RCIN
This commit is contained in:
parent
5ce0c23beb
commit
5bb2be206a
|
@ -543,7 +543,11 @@ void AP_SerialManager::init()
|
|||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
case SerialProtocol_RCIN:
|
||||
AP::RC().add_uart(uart);
|
||||
if (AP::RC().has_uart()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Duplicate RCIN configured on SERIAL%u", i);
|
||||
} else {
|
||||
AP::RC().add_uart(uart);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue