Make use of C++ standard library

This commit is contained in:
BlackMark 2022-05-29 16:15:11 +02:00
parent a5f8e8e3d7
commit 419b86999d
6 changed files with 99 additions and 112 deletions

View File

@ -1,6 +1,6 @@
#pragma once
#include <stdint.h>
#include <cstdint>
namespace uart {
@ -27,17 +27,17 @@ namespace detail {
template <DataBits dataBits>
struct choose_data_type {
using type = uint8_t;
using type = std::uint8_t;
};
template <>
struct choose_data_type<DataBits::NINE> {
using type = uint16_t;
using type = std::uint16_t;
};
} // namespace detail
template <uint32_t baudRate = 9600, DataBits dataBits = DataBits::EIGHT, Parity parity = Parity::NONE,
template <std::uint32_t baudRate = 9600, DataBits dataBits = DataBits::EIGHT, Parity parity = Parity::NONE,
StopBits stopBits = StopBits::ONE>
struct Config {
static constexpr auto BAUD_RATE = baudRate;

View File

@ -2,12 +2,8 @@
#include "../clock.hpp"
#include "../util/type.hpp"
#include <math.h>
#include <stdint.h>
#define FORCE_INLINE __attribute__((always_inline))
#include <cmath>
#include <cstdint>
namespace uart {
@ -25,18 +21,18 @@ enum class Driven {
namespace detail {
using reg_ptr_t = volatile uint8_t *;
using reg_ptr_t = volatile std::uint8_t *;
template <uintptr_t Address>
template <std::uintptr_t Address>
static inline reg_ptr_t getRegPtr()
{
return reinterpret_cast<reg_ptr_t>(Address);
}
template <typename data_t, uint8_t Size>
template <typename data_t, std::uint8_t Size>
struct RingBuffer {
uint8_t head;
uint8_t tail;
std::uint8_t head;
std::uint8_t tail;
data_t buf[Size];
};
@ -44,17 +40,17 @@ template <class Registers, typename CtrlFlagsA, typename CtrlFlagsB, typename Ct
Mode mode>
class Hardware {
public:
static void init() FORCE_INLINE
[[gnu::always_inline]] static void init()
{
constexpr auto AbsDoubleError = fabs(calcBaudError<true>());
constexpr auto AbsNormalError = fabs(calcBaudError<false>());
constexpr auto AbsDoubleError = std::fabs(calcBaudError<true>());
constexpr auto AbsNormalError = std::fabs(calcBaudError<false>());
static_assert(AbsDoubleError <= 3.0 || AbsNormalError <= 3.0, "Baud rate error over 3%, probably unusable");
constexpr auto UseDoubleSpeed = (AbsDoubleError < AbsNormalError);
constexpr auto BaudVal = calcBaudVal<UseDoubleSpeed>();
*getRegPtr<Registers::BAUD_REG_H_ADDR>() = static_cast<uint8_t>(BaudVal >> 8);
*getRegPtr<Registers::BAUD_REG_L_ADDR>() = static_cast<uint8_t>(BaudVal);
*getRegPtr<Registers::BAUD_REG_H_ADDR>() = static_cast<std::uint8_t>(BaudVal >> 8);
*getRegPtr<Registers::BAUD_REG_L_ADDR>() = static_cast<std::uint8_t>(BaudVal);
constexpr auto DataBitsValues = calcDataBits();
constexpr auto ParityVal = calcParity();
@ -64,8 +60,8 @@ class Hardware {
constexpr auto EnableTx = calcTxState<true>();
constexpr auto InterruptVal = calcInterrupt();
constexpr uint8_t ControlRegB = DataBitsValues.regBVal | EnableRx | EnableTx | InterruptVal;
constexpr uint8_t ControlRegC = DataBitsValues.regCVal | ParityVal | StopBitsVal | ModeVal;
constexpr std::uint8_t ControlRegB = DataBitsValues.regBVal | EnableRx | EnableTx | InterruptVal;
constexpr std::uint8_t ControlRegC = DataBitsValues.regCVal | ParityVal | StopBitsVal | ModeVal;
auto ctrlStatRegA = getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>();
@ -78,7 +74,7 @@ class Hardware {
*getRegPtr<Registers::CTRL_STAT_REG_C_ADDR>() = ControlRegC;
}
static bool rxByteBlocking(typename cfg::data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static bool rxByteBlocking(typename cfg::data_t &byte)
{
if (*getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>() & (1 << CtrlFlagsA::RECEIVE_COMPLETE)) {
byte = *getRegPtr<Registers::IO_REG_ADDR>();
@ -88,27 +84,27 @@ class Hardware {
return false;
}
static typename cfg::data_t rxByteInterrupt() FORCE_INLINE
[[gnu::always_inline]] static typename cfg::data_t rxByteInterrupt()
{
return *getRegPtr<Registers::IO_REG_ADDR>();
}
static bool txEmpty() FORCE_INLINE
[[gnu::always_inline]] static bool txEmpty()
{
return *getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>() & (1 << CtrlFlagsA::DATA_REG_EMPTY);
}
static bool txComplete() FORCE_INLINE
[[gnu::always_inline]] static bool txComplete()
{
return *getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>() & (1 << CtrlFlagsA::TRANSMIT_COMPLETE);
}
static void clearTxComplete() FORCE_INLINE
[[gnu::always_inline]] static void clearTxComplete()
{
*getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>() |= (1 << CtrlFlagsA::TRANSMIT_COMPLETE);
}
static void txByteBlocking(const typename cfg::data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static void txByteBlocking(const typename cfg::data_t &byte)
{
while (!txEmpty())
;
@ -116,12 +112,12 @@ class Hardware {
*getRegPtr<Registers::IO_REG_ADDR>() = byte;
}
static void txByteInterrupt(volatile const typename cfg::data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static void txByteInterrupt(volatile const typename cfg::data_t &byte)
{
*getRegPtr<Registers::IO_REG_ADDR>() = byte;
}
static bool peekBlocking() FORCE_INLINE
[[gnu::always_inline]] static bool peekBlocking()
{
if (*getRegPtr<Registers::CTRL_STAT_REG_A_ADDR>() & (1 << CtrlFlagsA::RECEIVE_COMPLETE)) {
return true;
@ -130,13 +126,13 @@ class Hardware {
return false;
}
static void enableDataRegEmptyInt() FORCE_INLINE
[[gnu::always_inline]] static void enableDataRegEmptyInt()
{
auto ctrlStatRegB = getRegPtr<Registers::CTRL_STAT_REG_B_ADDR>();
*ctrlStatRegB = *ctrlStatRegB | (1 << CtrlFlagsB::DATA_REG_EMPTY_INT_ENABLE);
}
static void disableDataRegEmptyInt() FORCE_INLINE
[[gnu::always_inline]] static void disableDataRegEmptyInt()
{
auto ctrlStatRegB = getRegPtr<Registers::CTRL_STAT_REG_B_ADDR>();
*ctrlStatRegB = *ctrlStatRegB & ~(1 << CtrlFlagsB::DATA_REG_EMPTY_INT_ENABLE);
@ -144,31 +140,31 @@ class Hardware {
private:
struct DataBitsVal {
uint8_t regCVal = 0;
uint8_t regBVal = 0;
std::uint8_t regCVal = 0;
std::uint8_t regBVal = 0;
};
template <bool DoubleSpeed = true>
static constexpr auto calcBaudVal()
{
if constexpr (DoubleSpeed) {
constexpr auto BaudVal = static_cast<uint16_t>(round(F_CPU / (8.0 * cfg::BAUD_RATE) - 1));
constexpr auto BaudVal = static_cast<std::uint16_t>(round(F_CPU / (8.0 * cfg::BAUD_RATE) - 1));
return BaudVal;
}
constexpr auto BaudVal = static_cast<uint16_t>(round(F_CPU / (16.0 * cfg::BAUD_RATE) - 1));
constexpr auto BaudVal = static_cast<std::uint16_t>(round(F_CPU / (16.0 * cfg::BAUD_RATE) - 1));
return BaudVal;
}
template <uint16_t BaudVal, bool DoubleSpeed = true>
template <std::uint16_t BaudVal, bool DoubleSpeed = true>
static constexpr auto calcBaudRate()
{
if constexpr (DoubleSpeed) {
constexpr auto BaudRate = static_cast<uint32_t>(round(F_CPU / (8.0 * (BaudVal + 1))));
constexpr auto BaudRate = static_cast<std::uint32_t>(round(F_CPU / (8.0 * (BaudVal + 1))));
return BaudRate;
}
constexpr auto BaudRate = static_cast<uint32_t>(round(F_CPU / (16.0 * (BaudVal + 1))));
constexpr auto BaudRate = static_cast<std::uint32_t>(round(F_CPU / (16.0 * (BaudVal + 1))));
return BaudRate;
}
@ -209,7 +205,7 @@ class Hardware {
static constexpr auto calcParity()
{
uint8_t parityVal = 0;
std::uint8_t parityVal = 0;
if (cfg::PARITY == Parity::EVEN)
parityVal = (1 << CtrlFlagsC::PARITY_MODE_1);
@ -221,7 +217,7 @@ class Hardware {
static constexpr auto calcStopBits()
{
uint8_t stopBitsVal = 0;
std::uint8_t stopBitsVal = 0;
if (cfg::STOP_BITS == StopBits::TWO)
stopBitsVal = (1 << CtrlFlagsC::STOP_BIT_SEL);
@ -233,7 +229,7 @@ class Hardware {
{
static_assert(mode != Mode::SPI, "SPI mode can not be used with uart");
uint8_t modeVal = 0;
std::uint8_t modeVal = 0;
if (mode == Mode::SYNCHRONOUS_MASTER || mode == Mode::SYNCHRONOUS_SLAVE) {
modeVal = (1 << CtrlFlagsC::MODE_SEL_0);
@ -245,7 +241,7 @@ class Hardware {
template <bool Enable>
static constexpr auto calcRxState()
{
uint8_t enableVal = 0;
std::uint8_t enableVal = 0;
if (Enable)
enableVal = (1 << CtrlFlagsB::RX_ENABLE);
@ -256,7 +252,7 @@ class Hardware {
template <bool Enable>
static constexpr auto calcTxState()
{
uint8_t enableVal = 0;
std::uint8_t enableVal = 0;
if (Enable)
enableVal = (1 << CtrlFlagsB::TX_ENABLE);
@ -266,7 +262,7 @@ class Hardware {
static constexpr auto calcInterrupt()
{
uint8_t interruptVal = 0;
std::uint8_t interruptVal = 0;
if (driven == Driven::INTERRUPT)
interruptVal = (1 << CtrlFlagsB::RX_INT_ENABLE);
@ -281,33 +277,33 @@ class BlockingHardware {
using data_t = typename cfg::data_t;
static constexpr auto DATA_BITS = cfg::DATA_BITS;
static void init() FORCE_INLINE
[[gnu::always_inline]] static void init()
{
HardwareImpl::init();
}
static void txByte(const data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static void txByte(const data_t &byte)
{
HardwareImpl::txByteBlocking(byte);
}
static bool rxByte(data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static bool rxByte(data_t &byte)
{
return HardwareImpl::rxByteBlocking(byte);
}
static bool peek(data_t &) FORCE_INLINE
[[gnu::always_inline]] static bool peek(data_t &)
{
static_assert(util::always_false_v<data_t>, "Peek with data is not supported in blocking mode");
return false;
}
static bool peek() FORCE_INLINE
[[gnu::always_inline]] static bool peek()
{
return HardwareImpl::peekBlocking();
}
static void flushTx() FORCE_INLINE
[[gnu::always_inline]] static void flushTx()
{
while (!HardwareImpl::txEmpty())
;
@ -326,9 +322,9 @@ class InterruptHardware {
using data_t = typename cfg::data_t;
static constexpr auto DATA_BITS = cfg::DATA_BITS;
static void txByte(const data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static void txByte(const data_t &byte)
{
uint8_t tmpHead = (sm_txBuf.head + 1) % TX_BUFFER_SIZE;
std::uint8_t tmpHead = (sm_txBuf.head + 1) % TX_BUFFER_SIZE;
while (tmpHead == sm_txBuf.tail)
;
@ -338,35 +334,35 @@ class InterruptHardware {
HardwareImpl::enableDataRegEmptyInt();
}
static bool rxByte(data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static bool rxByte(data_t &byte)
{
if (sm_rxBuf.head == sm_rxBuf.tail)
return false;
uint8_t tmpTail = (sm_rxBuf.tail + 1) % RX_BUFFER_SIZE;
std::uint8_t tmpTail = (sm_rxBuf.tail + 1) % RX_BUFFER_SIZE;
byte = sm_rxBuf.buf[tmpTail];
sm_rxBuf.tail = tmpTail;
return true;
}
static bool peek(data_t &byte) FORCE_INLINE
[[gnu::always_inline]] static bool peek(data_t &byte)
{
if (sm_rxBuf.head == sm_rxBuf.tail)
return false;
uint8_t tmpTail = (sm_rxBuf.tail + 1) % RX_BUFFER_SIZE;
std::uint8_t tmpTail = (sm_rxBuf.tail + 1) % RX_BUFFER_SIZE;
byte = sm_rxBuf.buf[tmpTail];
return true;
}
static bool peek() FORCE_INLINE
[[gnu::always_inline]] static bool peek()
{
return (sm_rxBuf.head != sm_rxBuf.tail);
}
static void flushTx() FORCE_INLINE
[[gnu::always_inline]] static void flushTx()
{
while (sm_txBuf.head != sm_txBuf.tail)
;
@ -378,11 +374,11 @@ class InterruptHardware {
}
protected:
static void rxIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void rxIntHandler()
{
const auto data = HardwareImpl::rxByteInterrupt();
const uint8_t tmpHead = (sm_rxBuf.head + 1) % RX_BUFFER_SIZE;
const std::uint8_t tmpHead = (sm_rxBuf.head + 1) % RX_BUFFER_SIZE;
if (tmpHead != sm_rxBuf.tail) {
sm_rxBuf.head = tmpHead;
@ -392,10 +388,10 @@ class InterruptHardware {
}
}
static void dataRegEmptyIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void dataRegEmptyIntHandler()
{
if (sm_txBuf.head != sm_txBuf.tail) {
const uint8_t tmpTail = (sm_txBuf.tail + 1) % TX_BUFFER_SIZE;
const std::uint8_t tmpTail = (sm_txBuf.tail + 1) % TX_BUFFER_SIZE;
sm_txBuf.tail = tmpTail;
HardwareImpl::txByteInterrupt(sm_txBuf.buf[tmpTail]);
} else
@ -425,5 +421,3 @@ volatile RingBuffer<typename InterruptHardware<Registers, CtrlFlagsA, CtrlFlagsB
} // namespace detail
} // namespace uart
#undef FORCE_INLINE

View File

@ -1,6 +1,6 @@
#pragma once
#include <stdint.h>
#include <cstdint>
#include <avr/interrupt.h>
#include <avr/io.h>
@ -9,8 +9,6 @@
#include "config.hpp"
#include "hardware.hpp"
#define FORCE_INLINE __attribute__((always_inline))
namespace uart {
namespace detail {
@ -32,12 +30,12 @@ The workaround therefore is to disable the pointer cast and dereference macro _M
#define _MMIO_BYTE
struct Registers0 {
static constexpr uintptr_t IO_REG_ADDR = UDR0;
static constexpr uintptr_t CTRL_STAT_REG_A_ADDR = UCSR0A;
static constexpr uintptr_t CTRL_STAT_REG_B_ADDR = UCSR0B;
static constexpr uintptr_t CTRL_STAT_REG_C_ADDR = UCSR0C;
static constexpr uintptr_t BAUD_REG_L_ADDR = UBRR0L;
static constexpr uintptr_t BAUD_REG_H_ADDR = UBRR0H;
static constexpr std::uintptr_t IO_REG_ADDR = UDR0;
static constexpr std::uintptr_t CTRL_STAT_REG_A_ADDR = UCSR0A;
static constexpr std::uintptr_t CTRL_STAT_REG_B_ADDR = UCSR0B;
static constexpr std::uintptr_t CTRL_STAT_REG_C_ADDR = UCSR0C;
static constexpr std::uintptr_t BAUD_REG_L_ADDR = UBRR0L;
static constexpr std::uintptr_t BAUD_REG_H_ADDR = UBRR0H;
};
#pragma pop_macro("_MMIO_BYTE")
@ -102,7 +100,7 @@ class Hardware0<cfg, Driven::INTERRUPT, mode>
: public detail::InterruptHardware<detail::Registers0, detail::ControlFlagsA0, detail::ControlFlagsB0,
detail::ControlFlagsC0, cfg, mode> {
public:
static void init() FORCE_INLINE
[[gnu::always_inline]] static void init()
{
HardwareImpl::init();
sei();
@ -119,12 +117,12 @@ class Hardware0<cfg, Driven::INTERRUPT, mode>
template <class Driver>
friend class Uart;
static void rxIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void rxIntHandler()
{
InterruptHardwareImpl::rxIntHandler();
}
static void dataRegEmptyIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void dataRegEmptyIntHandler()
{
InterruptHardwareImpl::dataRegEmptyIntHandler();
}
@ -152,5 +150,3 @@ void USART0_UDRE_vect() __attribute__((signal));
} \
struct _##uart_type {}
// clang-format on
#undef FORCE_INLINE

View File

@ -1,6 +1,6 @@
#pragma once
#include <stdint.h>
#include <cstdint>
#include <avr/interrupt.h>
#include <avr/io.h>
@ -9,8 +9,6 @@
#include "config.hpp"
#include "hardware.hpp"
#define FORCE_INLINE __attribute__((always_inline))
namespace uart {
namespace detail {
@ -32,12 +30,12 @@ The workaround therefore is to disable the pointer cast and dereference macro _M
#define _MMIO_BYTE
struct Registers1 {
static constexpr uintptr_t IO_REG_ADDR = UDR1;
static constexpr uintptr_t CTRL_STAT_REG_A_ADDR = UCSR1A;
static constexpr uintptr_t CTRL_STAT_REG_B_ADDR = UCSR1B;
static constexpr uintptr_t CTRL_STAT_REG_C_ADDR = UCSR1C;
static constexpr uintptr_t BAUD_REG_L_ADDR = UBRR1L;
static constexpr uintptr_t BAUD_REG_H_ADDR = UBRR1H;
static constexpr std::uintptr_t IO_REG_ADDR = UDR1;
static constexpr std::uintptr_t CTRL_STAT_REG_A_ADDR = UCSR1A;
static constexpr std::uintptr_t CTRL_STAT_REG_B_ADDR = UCSR1B;
static constexpr std::uintptr_t CTRL_STAT_REG_C_ADDR = UCSR1C;
static constexpr std::uintptr_t BAUD_REG_L_ADDR = UBRR1L;
static constexpr std::uintptr_t BAUD_REG_H_ADDR = UBRR1H;
};
#pragma pop_macro("_MMIO_BYTE")
@ -99,7 +97,7 @@ class Hardware1<cfg, Driven::INTERRUPT, mode>
: public detail::InterruptHardware<detail::Registers1, detail::ControlFlagsA1, detail::ControlFlagsB1,
detail::ControlFlagsC1, cfg, mode> {
public:
static void init() FORCE_INLINE
[[gnu::always_inline]] static void init()
{
HardwareImpl::init();
sei();
@ -116,12 +114,12 @@ class Hardware1<cfg, Driven::INTERRUPT, mode>
template <class Driver>
friend class Uart;
static void rxIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void rxIntHandler()
{
InterruptHardwareImpl::rxIntHandler();
}
static void dataRegEmptyIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void dataRegEmptyIntHandler()
{
InterruptHardwareImpl::dataRegEmptyIntHandler();
}
@ -157,4 +155,3 @@ void USART1_UDRE_vect() __attribute__((signal));
#endif
#undef FORCE_INLINE

View File

@ -3,7 +3,7 @@
#include "config.hpp"
#include "../io/io.hpp"
#include "../util/type.hpp"
#include "../util/util.hpp"
namespace uart {

View File

@ -1,6 +1,8 @@
#pragma once
#include <stdint.h>
#include <limits>
#include <cstdint>
#include "config.hpp"
#include "software.hpp"
@ -9,18 +11,17 @@
#include "hardware1.hpp"
#include "../flash/flash.hpp"
#define FORCE_INLINE __attribute__((always_inline))
#include "../util/util.hpp"
namespace uart {
namespace detail {
template <typename T, T Limit, size_t Base>
static constexpr size_t cntDigits()
template <typename T, T Limit, std::size_t Base>
static constexpr std::size_t cntDigits()
{
T num = Limit;
size_t cnt = 0;
std::size_t cnt = 0;
do {
num /= Base;
@ -30,11 +31,11 @@ static constexpr size_t cntDigits()
return cnt;
}
template <typename T, size_t Base>
static constexpr size_t maxNumDigits()
template <typename T, std::size_t Base>
static constexpr std::size_t maxNumDigits()
{
constexpr T MinVal = util::numeric_limits<T>::min();
constexpr T MaxVal = util::numeric_limits<T>::max();
constexpr T MinVal = std::numeric_limits<T>::min();
constexpr T MaxVal = std::numeric_limits<T>::max();
constexpr T MinDigits = cntDigits<T, MinVal, Base>();
constexpr T MaxDigits = cntDigits<T, MaxVal, Base>();
@ -109,16 +110,16 @@ class Uart {
txByte(ch);
}
template <typename T, size_t Base = 10, size_t Padding = 0, char PadChar = '0', bool LowerCase = true>
template <typename T, std::size_t Base = 10, std::size_t Padding = 0, char PadChar = '0', bool LowerCase = true>
static void txNumber(const T &val)
{
static_assert(util::is_integral_v<T>, "Only supported on integral types");
static_assert(std::is_integral_v<T>, "Only supported on integral types");
static_assert(Base >= 2, "Numbers with base less than 2 make no sense");
static_assert(Base <= 16, "Numbers with base higher than 16 are not supported");
static_assert(Padding <= detail::maxNumDigits<T, Base>(), "Cannot pad more than maximum length of number");
constexpr char AlphaChar = (LowerCase) ? 'a' : 'A';
constexpr size_t NumDigits = detail::maxNumDigits<T, Base>();
constexpr std::size_t NumDigits = detail::maxNumDigits<T, Base>();
T digits = val;
@ -137,10 +138,10 @@ class Uart {
} while (digits > 0);
if (Padding > 0) {
size_t strLen = buffer + NumDigits - (bufEnd + 1);
std::size_t strLen = buffer + NumDigits - (bufEnd + 1);
if (Padding > strLen) {
for (size_t i = Padding; i > strLen && bufEnd >= buffer; --i) {
for (std::size_t i = Padding; i > strLen && bufEnd >= buffer; --i) {
*bufEnd-- = PadChar;
}
}
@ -258,7 +259,7 @@ class Uart {
Uart &operator<<(const void *val)
{
txString(F("0x"));
txNumber<uint16_t, 16, 4, '0', false>(reinterpret_cast<uint16_t>(val));
txNumber<std::uint16_t, 16, 4, '0', false>(reinterpret_cast<std::uint16_t>(val));
return *this;
}
@ -364,12 +365,12 @@ class Uart {
friend void ::USART1_UDRE_vect();
#endif
static void rxIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void rxIntHandler()
{
Driver::rxIntHandler();
}
static void dataRegEmptyIntHandler() FORCE_INLINE
[[gnu::always_inline]] static void dataRegEmptyIntHandler()
{
Driver::dataRegEmptyIntHandler();
}
@ -385,5 +386,4 @@ using Uart1 = Uart<Hardware1<cfg, Driven::INTERRUPT, Mode::ASYNCHRONOUS>>;
} // namespace uart
#undef FORCE_INLINE
#undef HAS_UART1