diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 6004f70ff1..7b805c767e 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -494,17 +494,6 @@ void AP_SerialManager::init() case SerialProtocol_Aerotenna_USD1: state[i].protocol.set_and_save(SerialProtocol_Rangefinder); 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(), - AP_SERIALMANAGER_SBUS1_BUFSIZE_RX, - AP_SERIALMANAGER_SBUS1_BUFSIZE_TX); - uart->configure_parity(2); // enable even parity - uart->set_stop_bits(2); - uart->set_unbuffered_writes(true); - uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); - break; - case SerialProtocol_ESCTelemetry: // ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200 state[i].baud.set_and_default(115200 / 1000); diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 4938b26164..8b50422058 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -116,11 +116,6 @@ #define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512 #define AP_SERIALMANAGER_EFI_MS_BUFSIZE_TX 16 -// SBUS servo outputs -#define AP_SERIALMANAGER_SBUS1_BAUD 100000 -#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16 -#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32 - #define AP_SERIALMANAGER_SLCAN_BAUD 115200 #define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128 #define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128