mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_SerialManager: move Alexmos init into Mount library
This commit is contained in:
parent
67afc4418c
commit
a1f1cec40c
@ -484,13 +484,6 @@ void AP_SerialManager::init()
|
||||
AP_SERIALMANAGER_GPS_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_GPS_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_AlexMos:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_ALEXMOS_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_Gimbal:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_GIMBAL_BAUD / 1000); // update baud param in case user looks at it
|
||||
|
@ -104,11 +104,6 @@
|
||||
#define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256
|
||||
#define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
|
||||
|
||||
// AlexMos Gimbal protocol default baud rates and buffer sizes
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BAUD 115200
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128
|
||||
|
||||
#define AP_SERIALMANAGER_GIMBAL_BAUD 115200
|
||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
|
||||
|
Loading…
Reference in New Issue
Block a user