mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: define more UART option bits
This commit is contained in:
parent
ab0f1a8887
commit
4eccea2607
|
@ -49,14 +49,20 @@ public:
|
|||
virtual int16_t read_locked(uint32_t key) { return -1; }
|
||||
|
||||
// control optional features
|
||||
virtual bool set_options(uint8_t options) { return options==0; }
|
||||
virtual bool set_options(uint16_t options) { return options==0; }
|
||||
virtual uint8_t get_options(void) const { return 0; }
|
||||
|
||||
enum {
|
||||
OPTION_RXINV=(1U<<0), // invert RX line
|
||||
OPTION_TXINV=(1U<<1), // invert TX line
|
||||
OPTION_HDPLEX=(1U<<2), // half-duplex (one-wire) mode
|
||||
OPTION_SWAP=(1U<<3), // swap RX and TX pins
|
||||
OPTION_RXINV = (1U<<0), // invert RX line
|
||||
OPTION_TXINV = (1U<<1), // invert TX line
|
||||
OPTION_HDPLEX = (1U<<2), // half-duplex (one-wire) mode
|
||||
OPTION_SWAP = (1U<<3), // swap RX and TX pins
|
||||
OPTION_PULLDOWN_RX = (1U<<4), // apply pulldown to RX
|
||||
OPTION_PULLUP_RX = (1U<<5), // apply pullup to RX
|
||||
OPTION_PULLDOWN_TX = (1U<<6), // apply pulldown to TX
|
||||
OPTION_PULLUP_TX = (1U<<7), // apply pullup to TX
|
||||
OPTION_NODMA_RX = (1U<<8), // don't use DMA for RX
|
||||
OPTION_NODMA_TX = (1U<<9), // don't use DMA for TX
|
||||
};
|
||||
|
||||
enum flow_control {
|
||||
|
|
Loading…
Reference in New Issue