mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: implement new UART option bits
This commit is contained in:
parent
bb5c1d07e1
commit
22f8221427
@ -195,7 +195,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 1_OPTIONS
|
||||
// @DisplayName: Telem1 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. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
|
||||
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, 0),
|
||||
@ -205,7 +205,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 2_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
|
||||
@ -215,7 +215,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 3_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
|
||||
@ -225,7 +225,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 4_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
|
||||
@ -235,7 +235,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 5_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
|
||||
@ -245,7 +245,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 6_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
|
||||
@ -292,7 +292,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 7_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, 4:Swap
|
||||
// @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
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0),
|
||||
@ -638,7 +638,7 @@ bool AP_SerialManager::protocol_match(enum SerialProtocol protocol1, enum Serial
|
||||
}
|
||||
|
||||
// setup any special options
|
||||
void AP_SerialManager::set_options(uint8_t i)
|
||||
void AP_SerialManager::set_options(uint16_t i)
|
||||
{
|
||||
struct UARTState &opt = state[i];
|
||||
// pass through to HAL
|
||||
|
@ -212,7 +212,7 @@ private:
|
||||
bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;
|
||||
|
||||
// setup any special options
|
||||
void set_options(uint8_t i);
|
||||
void set_options(uint16_t i);
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
Loading…
Reference in New Issue
Block a user