AP_SerialManager: move serial port init of SBusOut protocol into SBusOut library

This commit is contained in:
Peter Barker 2023-09-26 07:36:27 +10:00
parent caea42630e
commit 94380eb9be
2 changed files with 0 additions and 16 deletions

View File

@ -494,17 +494,6 @@ void AP_SerialManager::init()
case SerialProtocol_Aerotenna_USD1: case SerialProtocol_Aerotenna_USD1:
state[i].protocol.set_and_save(SerialProtocol_Rangefinder); state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
break; 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: case SerialProtocol_ESCTelemetry:
// ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200 // ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
state[i].baud.set_and_default(115200 / 1000); state[i].baud.set_and_default(115200 / 1000);

View File

@ -116,11 +116,6 @@
#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512 #define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512
#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_TX 16 #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_BAUD 115200
#define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128 #define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128
#define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128 #define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128