Browse Source

AP_HAL: Add UART option to not override streamrates

gps-1.3.1
Stephen Dade 3 years ago committed by Peter Barker
parent
commit
68ca18329c
  1. 9
      libraries/AP_HAL/UARTDriver.h

9
libraries/AP_HAL/UARTDriver.h

@ -9,6 +9,10 @@ class ExpandingString; @@ -9,6 +9,10 @@ class ExpandingString;
/* Pure virtual UARTDriver class */
class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
private:
// option bits for port
uint16_t _last_options;
public:
UARTDriver() {}
/* Do not allow copies */
@ -61,8 +65,8 @@ public: @@ -61,8 +65,8 @@ public:
virtual int16_t read_locked(uint32_t key) { return -1; }
// control optional features
virtual bool set_options(uint16_t options) { return options==0; }
virtual uint8_t get_options(void) const { return 0; }
virtual bool set_options(uint16_t options) { _last_options = options; return options==0; }
virtual uint16_t get_options(void) const { return _last_options; }
enum {
OPTION_RXINV = (1U<<0), // invert RX line
@ -77,6 +81,7 @@ public: @@ -77,6 +81,7 @@ public:
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
OPTION_NOFIFO = (1U<<11), // disable hardware FIFO
OPTION_NOSTREAMOVERRIDE = (1U<<12), // don't allow GCS to override streamrates
};
enum flow_control {

Loading…
Cancel
Save