From 0bc0115f4c30ba8963d22e255a17c88578faaf43 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 4 Apr 2024 17:01:37 +0100 Subject: [PATCH] AP_SerialManager: remove Volz port config --- libraries/AP_SerialManager/AP_SerialManager.cpp | 11 +++-------- libraries/AP_SerialManager/AP_SerialManager_config.h | 2 -- 2 files changed, 3 insertions(+), 10 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 9818738b3fb90..a42de342ab2e7 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -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(), diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 74ed01243bec2..7ed9e502d692f 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -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