AP_HAL: Extend UART options to include forwarding MAVLink telemetry

This commit is contained in:
Michael du Breuil 2020-07-03 15:03:23 -07:00 committed by Peter Barker
parent b298477266
commit 1fef30eef1
1 changed files with 11 additions and 10 deletions

View File

@ -53,16 +53,17 @@ public:
virtual uint8_t get_options(void) const { return 0; } virtual uint8_t get_options(void) const { return 0; }
enum { enum {
OPTION_RXINV = (1U<<0), // invert RX line OPTION_RXINV = (1U<<0), // invert RX line
OPTION_TXINV = (1U<<1), // invert TX line OPTION_TXINV = (1U<<1), // invert TX line
OPTION_HDPLEX = (1U<<2), // half-duplex (one-wire) mode OPTION_HDPLEX = (1U<<2), // half-duplex (one-wire) mode
OPTION_SWAP = (1U<<3), // swap RX and TX pins OPTION_SWAP = (1U<<3), // swap RX and TX pins
OPTION_PULLDOWN_RX = (1U<<4), // apply pulldown to RX OPTION_PULLDOWN_RX = (1U<<4), // apply pulldown to RX
OPTION_PULLUP_RX = (1U<<5), // apply pullup to RX OPTION_PULLUP_RX = (1U<<5), // apply pullup to RX
OPTION_PULLDOWN_TX = (1U<<6), // apply pulldown to TX OPTION_PULLDOWN_TX = (1U<<6), // apply pulldown to TX
OPTION_PULLUP_TX = (1U<<7), // apply pullup to TX OPTION_PULLUP_TX = (1U<<7), // apply pullup to TX
OPTION_NODMA_RX = (1U<<8), // don't use DMA for RX OPTION_NODMA_RX = (1U<<8), // don't use DMA for RX
OPTION_NODMA_TX = (1U<<9), // don't use DMA for TX OPTION_NODMA_TX = (1U<<9), // don't use DMA for TX
OPTION_MAVLINK_NO_FORWARD = (1U<<10), // don't forward MAVLink data to or from this device
}; };
enum flow_control { enum flow_control {