AP_SerialManager: remove Volz port config

This commit is contained in:
Iampete1 2024-04-04 17:01:37 +01:00 committed by Peter Barker
parent 8eceff2d7a
commit a551b4f296
2 changed files with 3 additions and 10 deletions

View File

@ -502,14 +502,9 @@ void AP_SerialManager::init()
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
uart->begin(state[i].baudrate(),
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;
// 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(),

View File

@ -114,8 +114,6 @@
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
#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_TX 128