mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: move serial port init of Volz protocol into Volz library
This commit is contained in:
parent
4e0bc79002
commit
05e5d2e6bb
|
@ -501,10 +501,6 @@ void AP_SerialManager::init()
|
|||
case SerialProtocol_Aerotenna_USD1:
|
||||
state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
|
||||
break;
|
||||
case SerialProtocol_Volz:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_VOLZ_BAUD); // update baud param in case user looks at it
|
||||
break;
|
||||
case SerialProtocol_Sbus1:
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_SBUS1_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(state[i].baudrate(),
|
||||
|
|
|
@ -113,8 +113,6 @@
|
|||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
|
||||
|
||||
#define AP_SERIALMANAGER_VOLZ_BAUD 115
|
||||
|
||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
||||
|
||||
|
|
Loading…
Reference in New Issue