mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: remove Volz port config
This commit is contained in:
parent
8eceff2d7a
commit
a551b4f296
|
@ -502,14 +502,9 @@ void AP_SerialManager::init()
|
||||||
state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
|
state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
|
||||||
break;
|
break;
|
||||||
case SerialProtocol_Volz:
|
case SerialProtocol_Volz:
|
||||||
// Note baudrate is hardcoded to 115200
|
// 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
|
state[i].baud.set_and_default(AP_SERIALMANAGER_VOLZ_BAUD); // update baud param in case user looks at it
|
||||||
uart->begin(state[i].baudrate(),
|
break;
|
||||||
AP_SERIALMANAGER_VOLZ_BUFSIZE_RX,
|
|
||||||
AP_SERIALMANAGER_VOLZ_BUFSIZE_TX);
|
|
||||||
uart->set_unbuffered_writes(true);
|
|
||||||
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
|
||||||
break;
|
|
||||||
case SerialProtocol_Sbus1:
|
case SerialProtocol_Sbus1:
|
||||||
state[i].baud.set_and_default(AP_SERIALMANAGER_SBUS1_BAUD / 1000); // update baud param in case user looks at it
|
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(),
|
uart->begin(state[i].baudrate(),
|
||||||
|
|
|
@ -114,8 +114,6 @@
|
||||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
|
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
|
||||||
|
|
||||||
#define AP_SERIALMANAGER_VOLZ_BAUD 115
|
#define AP_SERIALMANAGER_VOLZ_BAUD 115
|
||||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
|
|
||||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
|
|
||||||
|
|
||||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
||||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
||||||
|
|
Loading…
Reference in New Issue