From d340f376787febebdff9b046ad7c8fccf55f273f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 10 Apr 2024 19:46:03 +0100 Subject: [PATCH] AP_HAL: UARTDriver: Add new flow control option "FLOW_CONTROL_RTS_DE" for RS485 driver enable. --- libraries/AP_HAL/UARTDriver.cpp | 14 ++++++++++++++ libraries/AP_HAL/UARTDriver.h | 7 +++++++ 2 files changed, 21 insertions(+) diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 20e5741ed8..547cd55ab7 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -165,6 +165,20 @@ uint64_t AP_HAL::UARTDriver::receive_time_constraint_us(uint16_t nbytes) return AP_HAL::micros64(); } +// Helper to check if flow control is enabled given the passed setting +bool AP_HAL::UARTDriver::flow_control_enabled(enum flow_control flow_control_setting) const +{ + switch(flow_control_setting) { + case FLOW_CONTROL_ENABLE: + case FLOW_CONTROL_AUTO: + return true; + case FLOW_CONTROL_DISABLE: + case FLOW_CONTROL_RTS_DE: + break; + } + return false; +} + #if HAL_UART_STATS_ENABLED // Take cumulative bytes and return the change since last call uint32_t AP_HAL::UARTDriver::StatsTracker::ByteTracker::update(uint32_t bytes) diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index 829d7907b3..db395550e0 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -103,10 +103,14 @@ public: FLOW_CONTROL_DISABLE=0, FLOW_CONTROL_ENABLE=1, FLOW_CONTROL_AUTO=2, + FLOW_CONTROL_RTS_DE=3, // RTS pin is used as a driver enable (used in RS-485) }; virtual void set_flow_control(enum flow_control flow_control_setting) {}; virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; } + // Return true if flow control is currently enabled + bool flow_control_enabled() { return flow_control_enabled(get_flow_control()); } + virtual void configure_parity(uint8_t v){}; virtual void set_stop_bits(int n){}; @@ -240,6 +244,9 @@ protected: // discard incoming data on the port virtual bool _discard_input(void) = 0; + // Helper to check if flow control is enabled given the passed setting + bool flow_control_enabled(enum flow_control flow_control_setting) const; + #if HAL_UART_STATS_ENABLED // Getters for cumulative tx and rx counts virtual uint32_t get_total_tx_bytes() const { return 0; }