From 1815ed32e9601005b045c4a47cb3ce5e1af9fd0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Nov 2021 14:17:40 +1100 Subject: [PATCH] AP_SerialManager: support up to 9 UARTs --- .../AP_SerialManager/AP_SerialManager.cpp | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 5591420a73..3de19f6f39 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -78,6 +78,14 @@ extern const AP_HAL::HAL& hal; #define SERIAL8_BAUD HAL_SERIAL8_BAUD #endif +#ifndef HAL_SERIAL9_PROTOCOL +#define SERIAL9_PROTOCOL SerialProtocol_None +#define SERIAL9_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 +#else +#define SERIAL9_PROTOCOL HAL_SERIAL9_PROTOCOL +#define SERIAL9_BAUD HAL_SERIAL9_BAUD +#endif + #ifdef HAL_BUILD_AP_PERIPH /* AP_Periph doesn't include the SERIAL parameter tree, instead each @@ -93,6 +101,7 @@ extern const AP_HAL::HAL& hal; #undef SERIAL6_PROTOCOL #undef SERIAL7_PROTOCOL #undef SERIAL8_PROTOCOL +#undef SERIAL9_PROTOCOL #define SERIAL0_PROTOCOL SerialProtocol_None #define SERIAL1_PROTOCOL SerialProtocol_None #define SERIAL2_PROTOCOL SerialProtocol_None @@ -102,6 +111,7 @@ extern const AP_HAL::HAL& hal; #define SERIAL6_PROTOCOL SerialProtocol_None #define SERIAL7_PROTOCOL SerialProtocol_None #define SERIAL8_PROTOCOL SerialProtocol_None +#define SERIAL9_PROTOCOL SerialProtocol_None #endif // HAL_BUILD_AP_PERIPH @@ -358,6 +368,31 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @RebootRequired: True AP_GROUPINFO("8_OPTIONS", 28, AP_SerialManager, state[8].options, 0), #endif + +#if SERIALMANAGER_NUM_PORTS > 9 + // @Param: 9_PROTOCOL + // @DisplayName: Serial9 protocol selection + // @Description: Control what protocol Serial9 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. + // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("9_PROTOCOL", 29, AP_SerialManager, state[9].protocol, SERIAL9_PROTOCOL), + + // @Param: 9_BAUD + // @DisplayName: Serial 9 Baud Rate + // @Description: The baud rate used for Serial8. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults. + // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000 + // @User: Standard + AP_GROUPINFO("9_BAUD", 30, AP_SerialManager, state[9].baud, SERIAL9_BAUD), + + // @Param: 9_OPTIONS + // @DisplayName: Serial9 options + // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. + // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("9_OPTIONS", 31, AP_SerialManager, state[9].options, 0), +#endif AP_GROUPEND };