diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index f0f910dccd..4fe78f3ab8 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -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(), diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 22c2f871b3..4e8669c69e 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -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