SerialManager: do not init uart for FrSky S-Port

This commit is contained in:
Randy Mackay 2015-01-27 20:52:37 +09:00 committed by Andrew Tridgell
parent cc71db1e2f
commit 0fe4436c72
1 changed files with 1 additions and 1 deletions

View File

@ -147,7 +147,7 @@ void AP_SerialManager::init()
state[i].rx_size = AP_SERIALMANAGER_FRSKY_BUFSIZE_RX;
state[i].tx_size = AP_SERIALMANAGER_FRSKY_BUFSIZE_TX;
state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it
state[i].uart->begin(AP_SERIALMANAGER_FRSKY_SPORT_BAUD, state[i].rx_size, state[i].tx_size);
// begin is handled by AP_Frsky_telem library
break;
case SerialProtocol_GPS:
case SerialProtocol_GPS2: