AP_SerialManager: implement parameter CopyFieldsFrom and use it

This commit is contained in:
Peter Barker 2022-12-30 13:10:57 +11:00 committed by Andrew Tridgell
parent 7432123e42
commit 798cc2633f
1 changed files with 25 additions and 73 deletions

View File

@ -151,69 +151,57 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
#if SERIALMANAGER_NUM_PORTS > 2 #if SERIALMANAGER_NUM_PORTS > 2
// @Param: 2_PROTOCOL // @Param: 2_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Telemetry 2 protocol selection // @DisplayName: Telemetry 2 protocol selection
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL), AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL),
// @Param: 2_BAUD // @Param: 2_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Telemetry 2 Baud Rate // @DisplayName: Telemetry 2 Baud Rate
// @Description: The baud rate of the Telem2 port. 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. // @Description: The baud rate of the Telem2 port. 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000), AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 3 #if SERIALMANAGER_NUM_PORTS > 3
// @Param: 3_PROTOCOL // @Param: 3_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial 3 (GPS) protocol selection // @DisplayName: Serial 3 (GPS) protocol selection
// @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL), AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL),
// @Param: 3_BAUD // @Param: 3_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 3 (GPS) Baud Rate // @DisplayName: Serial 3 (GPS) Baud Rate
// @Description: The baud rate used for the Serial 3 (GPS). 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. // @Description: The baud rate used for the Serial 3 (GPS). 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000), AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 4 #if SERIALMANAGER_NUM_PORTS > 4
// @Param: 4_PROTOCOL // @Param: 4_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial4 protocol selection // @DisplayName: Serial4 protocol selection
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL), AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL),
// @Param: 4_BAUD // @Param: 4_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 4 Baud Rate // @DisplayName: Serial 4 Baud Rate
// @Description: The baud rate used for Serial4. 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. // @Description: The baud rate used for Serial4. 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000), AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 5 #if SERIALMANAGER_NUM_PORTS > 5
// @Param: 5_PROTOCOL // @Param: 5_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial5 protocol selection // @DisplayName: Serial5 protocol selection
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL), AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
// @Param: 5_BAUD // @Param: 5_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 5 Baud Rate // @DisplayName: Serial 5 Baud Rate
// @Description: The baud rate used for Serial5. 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. // @Description: The baud rate used for Serial5. 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD), AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
#endif #endif
@ -221,18 +209,15 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
#if SERIALMANAGER_NUM_PORTS > 6 #if SERIALMANAGER_NUM_PORTS > 6
// @Param: 6_PROTOCOL // @Param: 6_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial6 protocol selection // @DisplayName: Serial6 protocol selection
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL), AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
// @Param: 6_BAUD // @Param: 6_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 6 Baud Rate // @DisplayName: Serial 6 Baud Rate
// @Description: The baud rate used for Serial6. 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. // @Description: The baud rate used for Serial6. 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD), AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
#endif #endif
@ -248,51 +233,36 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
#if SERIALMANAGER_NUM_PORTS > 2 #if SERIALMANAGER_NUM_PORTS > 2
// @Param: 2_OPTIONS // @Param: 2_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Telem2 options // @DisplayName: Telem2 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0), AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 3 #if SERIALMANAGER_NUM_PORTS > 3
// @Param: 3_OPTIONS // @Param: 3_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial3 options // @DisplayName: Serial3 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0), AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 4 #if SERIALMANAGER_NUM_PORTS > 4
// @Param: 4_OPTIONS // @Param: 4_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial4 options // @DisplayName: Serial4 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0), AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 5 #if SERIALMANAGER_NUM_PORTS > 5
// @Param: 5_OPTIONS // @Param: 5_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial5 options // @DisplayName: Serial5 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0), AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 6 #if SERIALMANAGER_NUM_PORTS > 6
// @Param: 6_OPTIONS // @Param: 6_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial6 options // @DisplayName: Serial6 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0), AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
#endif #endif
@ -320,79 +290,61 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
#if SERIALMANAGER_NUM_PORTS > 7 #if SERIALMANAGER_NUM_PORTS > 7
// @Param: 7_PROTOCOL // @Param: 7_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial7 protocol selection // @DisplayName: Serial7 protocol selection
// @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL), AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL),
// @Param: 7_BAUD // @Param: 7_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 7 Baud Rate // @DisplayName: Serial 7 Baud Rate
// @Description: The baud rate used for Serial7. 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. // @Description: The baud rate used for Serial7. 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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("7_BAUD", 24, AP_SerialManager, state[7].baud, SERIAL7_BAUD), AP_GROUPINFO("7_BAUD", 24, AP_SerialManager, state[7].baud, SERIAL7_BAUD),
// @Param: 7_OPTIONS // @Param: 7_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial7 options // @DisplayName: Serial7 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0), AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 8 #if SERIALMANAGER_NUM_PORTS > 8
// @Param: 8_PROTOCOL // @Param: 8_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial8 protocol selection // @DisplayName: Serial8 protocol selection
// @Description: Control what protocol Serial8 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol Serial8 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("8_PROTOCOL", 26, AP_SerialManager, state[8].protocol, SERIAL8_PROTOCOL), AP_GROUPINFO("8_PROTOCOL", 26, AP_SerialManager, state[8].protocol, SERIAL8_PROTOCOL),
// @Param: 8_BAUD // @Param: 8_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 8 Baud Rate // @DisplayName: Serial 8 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. // @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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, SERIAL8_BAUD), AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, SERIAL8_BAUD),
// @Param: 8_OPTIONS // @Param: 8_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial8 options // @DisplayName: Serial8 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("8_OPTIONS", 28, AP_SerialManager, state[8].options, 0), AP_GROUPINFO("8_OPTIONS", 28, AP_SerialManager, state[8].options, 0),
#endif #endif
#if SERIALMANAGER_NUM_PORTS > 9 #if SERIALMANAGER_NUM_PORTS > 9
// @Param: 9_PROTOCOL // @Param: 9_PROTOCOL
// @CopyFieldsFrom: SERIAL1_PROTOCOL
// @DisplayName: Serial9 protocol selection // @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. // @Description: Control what protocol Serial9 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @CopyValuesFrom: SERIAL1_PROTOCOL
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("9_PROTOCOL", 29, AP_SerialManager, state[9].protocol, SERIAL9_PROTOCOL), AP_GROUPINFO("9_PROTOCOL", 29, AP_SerialManager, state[9].protocol, SERIAL9_PROTOCOL),
// @Param: 9_BAUD // @Param: 9_BAUD
// @CopyFieldsFrom: SERIAL1_BAUD
// @DisplayName: Serial 9 Baud Rate // @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. // @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.
// @CopyValuesFrom: SERIAL1_BAUD
// @User: Standard
AP_GROUPINFO("9_BAUD", 30, AP_SerialManager, state[9].baud, SERIAL9_BAUD), AP_GROUPINFO("9_BAUD", 30, AP_SerialManager, state[9].baud, SERIAL9_BAUD),
// @Param: 9_OPTIONS // @Param: 9_OPTIONS
// @CopyFieldsFrom: SERIAL1_OPTIONS
// @DisplayName: Serial9 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, 12: Ignore Streamrate
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("9_OPTIONS", 31, AP_SerialManager, state[9].options, 0), AP_GROUPINFO("9_OPTIONS", 31, AP_SerialManager, state[9].options, 0),
#endif #endif
AP_GROUPEND AP_GROUPEND
}; };