From 100f06614c70b9f8e2259fccef4597c4e414e9cf Mon Sep 17 00:00:00 2001 From: Jeremy Feltracco Date: Thu, 11 Apr 2019 10:26:35 -0400 Subject: [PATCH] AP_HAL_Linux: Add support for setting uart parity on Linux boards Pass set_parity down through UART class so that set_parity actually works for Linux boards. --- libraries/AP_HAL_Linux/SerialDevice.h | 3 +++ libraries/AP_HAL_Linux/UARTDevice.cpp | 20 ++++++++++++++++++++ libraries/AP_HAL_Linux/UARTDevice.h | 1 + libraries/AP_HAL_Linux/UARTDriver.cpp | 4 ++++ libraries/AP_HAL_Linux/UARTDriver.h | 2 ++ 5 files changed, 30 insertions(+) diff --git a/libraries/AP_HAL_Linux/SerialDevice.h b/libraries/AP_HAL_Linux/SerialDevice.h index 59b62c00cd..ad10a3774d 100644 --- a/libraries/AP_HAL_Linux/SerialDevice.h +++ b/libraries/AP_HAL_Linux/SerialDevice.h @@ -20,4 +20,7 @@ public: { /* most devices simply ignore this setting */ }; + + /* Depends on lower level to implement, most devices are fine with defaults */ + virtual void set_parity(int v) { } }; diff --git a/libraries/AP_HAL_Linux/UARTDevice.cpp b/libraries/AP_HAL_Linux/UARTDevice.cpp index d4eda6cca5..77b3a38fbf 100644 --- a/libraries/AP_HAL_Linux/UARTDevice.cpp +++ b/libraries/AP_HAL_Linux/UARTDevice.cpp @@ -130,3 +130,23 @@ void UARTDevice::set_flow_control(AP_HAL::UARTDriver::flow_control flow_control_ _flow_control = flow_control_setting; } + +void UARTDevice::set_parity(int v) +{ + struct termios t; + tcgetattr(_fd, &t); + if (v != 0) { + // enable parity + t.c_cflag |= PARENB; + if (v == 1) { + t.c_cflag |= PARODD; + } else { + t.c_cflag &= ~PARODD; + } + } + else { + // disable parity + t.c_cflag &= ~PARENB; + } + tcsetattr(_fd, TCSANOW, &t); +} diff --git a/libraries/AP_HAL_Linux/UARTDevice.h b/libraries/AP_HAL_Linux/UARTDevice.h index abb1d76dfc..b6dcae6ed6 100644 --- a/libraries/AP_HAL_Linux/UARTDevice.h +++ b/libraries/AP_HAL_Linux/UARTDevice.h @@ -19,6 +19,7 @@ public: { return _flow_control; } + virtual void set_parity(int v) override; private: void _disable_crlf(); diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index 8e22326f1c..a7e19ba953 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -457,6 +457,10 @@ void UARTDriver::_timer_tick(void) _in_timer = false; } +void UARTDriver::configure_parity(uint8_t v) { + _device->set_parity(v); +} + /* return timestamp estimate in microseconds for when the start of a nbytes packet arrived on the uart. This should be treated as a diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index 775baadf66..1083844191 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -45,6 +45,8 @@ public: return _device->get_flow_control(); } + virtual void configure_parity(uint8_t v); + virtual void set_flow_control(enum flow_control flow_control_setting) override { _device->set_flow_control(flow_control_setting);