[dif_uart] Introduce UART DIF library

This change introduces an UART DIF, a low level library for UART
hardware manipulation. The set of functions in this library can be
used in an ISR context, as well as normal execution context (It is up
to the higher level driver or OS to guard against the race conditions).

The init function is responsible for initialising the UART state,
which must be passed to all other DIF API.

This change is written to RFC #1043, and fixes issue #1076

Limitations:
* Implementation expects that only one thread of execution exclusively
  owns the hardware resource. This is a subject to implementation in a
  higher level driver, or OS.
* Implementation does not protect against race conditions that can
  occur between the ISR context and normal execution context. This
  responsibility also lies on a higher level driver or OS.

Current state:
* Fundamental API has been introduced, which should be sufficient for an UART
  driver needs, however it may be evolved and extended. For example, private
  user data could be added to the state structure.
* This API is largely untested

Signed-off-by: Silvestrs Timofejevs <silvestrst@lowrisc.org>
diff --git a/sw/device/lib/dif/dif_uart.c b/sw/device/lib/dif/dif_uart.c
new file mode 100644
index 0000000..5f9ac79
--- /dev/null
+++ b/sw/device/lib/dif/dif_uart.c
@@ -0,0 +1,412 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "sw/device/lib/dif/dif_uart.h"
+
+#include <stddef.h>
+
+#include "sw/device/lib/base/mmio.h"
+#include "uart_regs.h"  // Generated.
+
+// Fake base address
+#define UART0_BASE_ADDR 0x0
+
+#define UART_RX_FIFO_SIZE_BYTES 32u
+#define UART_TX_FIFO_SIZE_BYTES 32u
+
+static bool uart_tx_full(const dif_uart_t *uart) {
+  return mmio_region_get_bit32(uart->base_addr, UART_STATUS(0),
+                               UART_STATUS_TXFULL);
+}
+
+static bool uart_tx_empty(const dif_uart_t *uart) {
+  return mmio_region_get_bit32(uart->base_addr, UART_STATUS(0),
+                               UART_STATUS_TXEMPTY);
+}
+
+static bool uart_rx_empty(const dif_uart_t *uart) {
+  return mmio_region_get_bit32(uart->base_addr, UART_STATUS(0),
+                               UART_STATUS_RXEMPTY);
+}
+
+static uint8_t uart_rx_fifo_read(const dif_uart_t *uart) {
+  uint32_t reg = mmio_region_read32(uart->base_addr, UART_RDATA(0));
+
+  return reg & UART_RDATA_MASK;
+}
+
+static void uart_tx_fifo_write(const dif_uart_t *uart, uint8_t byte) {
+  uint32_t reg = (byte & UART_WDATA_MASK) << UART_WDATA_OFFSET;
+  mmio_region_write32(uart->base_addr, UART_WDATA(0), reg);
+}
+
+/**
+ * Get the corresponding interrupt register bit offset. INTR_STATE, INTR_ENABLE
+ * and INTR_TEST registers have the same bit offsets, so this routine can be
+ * reused.
+ */
+static ptrdiff_t uart_irq_offset_get(dif_uart_interrupt_t irq_type) {
+  ptrdiff_t offset;
+  switch (irq_type) {
+    case kDifUartInterruptTxWatermark:
+      offset = UART_INTR_STATE_TX_WATERMARK;
+      break;
+    case kDifUartInterruptRxWatermark:
+      offset = UART_INTR_STATE_RX_WATERMARK;
+      break;
+    case kDifUartInterruptTxEmpty:
+      offset = UART_INTR_STATE_TX_EMPTY;
+      break;
+    case kDifUartInterruptRxOverflow:
+      offset = UART_INTR_STATE_RX_OVERFLOW;
+      break;
+    case kDifUartInterruptRxFrameErr:
+      offset = UART_INTR_STATE_RX_FRAME_ERR;
+      break;
+    case kDifUartInterruptRxBreakErr:
+      offset = UART_INTR_STATE_RX_BREAK_ERR;
+      break;
+    case kDifUartInterruptRxTimeout:
+      offset = UART_INTR_STATE_RX_TIMEOUT;
+      break;
+    case kDifUartInterruptRxParityErr:
+      offset = UART_INTR_STATE_RX_PARITY_ERR;
+      break;
+    default:
+      __builtin_unreachable();
+  }
+
+  return offset;
+}
+
+/**
+ * Performs fundamental UART configuration.
+ */
+static bool uart_configure(const dif_uart_t *uart,
+                           const dif_uart_config_t *config) {
+  if (config->baudrate == 0 || config->clk_freq_hz == 0) {
+    return false;
+  }
+
+  // Calculation formula: NCO = 2^20 * baud / fclk
+  uint64_t nco = ((uint64_t)config->baudrate << 20) / config->clk_freq_hz;
+  uint32_t nco_masked = nco & UART_CTRL_NCO_MASK;
+
+  // Requested baudrate is too high for the given clock frequency
+  if (nco != nco_masked) {
+    return false;
+  }
+
+  // Set baudrate, enable RX and TX, configure parity
+  uint32_t reg = (nco_masked << UART_CTRL_NCO_OFFSET);
+  reg |= (1u << UART_CTRL_TX);
+  reg |= (1u << UART_CTRL_RX);
+  if (config->parity_enable == kDifUartEnable) {
+    reg |= (1u << UART_CTRL_PARITY_EN);
+  }
+  if (config->parity == kDifUartParityOdd) {
+    reg |= (1u << UART_CTRL_PARITY_ODD);
+  }
+  mmio_region_write32(uart->base_addr, UART_CTRL(0), reg);
+
+  // Reset RX/TX FIFOs
+  reg = (1u << UART_FIFO_CTRL_RXRST);
+  reg |= (1u << UART_FIFO_CTRL_TXRST);
+  mmio_region_write32(uart->base_addr, UART_FIFO_CTRL(0), reg);
+
+  // Disable interrupts
+  mmio_region_write32(uart->base_addr, UART_INTR_ENABLE(0), 0u);
+
+  return true;
+}
+
+/**
+ * Write up to |bytes_requested| number of bytes to the TX FIFO.
+ */
+static size_t uart_bytes_send(const dif_uart_t *uart, const uint8_t *data,
+                              size_t bytes_requested) {
+  size_t bytes_written = 0;
+  while ((bytes_written < bytes_requested) && !uart_tx_full(uart)) {
+    uart_tx_fifo_write(uart, data[bytes_written]);
+    ++bytes_written;
+  }
+
+  return bytes_written;
+}
+
+/**
+ * Read up to |bytes_requested| number of bytes from the RX FIFO.
+ */
+static size_t uart_bytes_receive(const dif_uart_t *uart, size_t bytes_requested,
+                                 uint8_t *data) {
+  size_t bytes_read = 0;
+  while ((bytes_read < bytes_requested) && !uart_rx_empty(uart)) {
+    data[bytes_read] = uart_rx_fifo_read(uart);
+    ++bytes_read;
+  }
+
+  return bytes_read;
+}
+
+bool dif_uart_init(mmio_region_t base_addr, const dif_uart_config_t *config,
+                   dif_uart_t *uart) {
+  if (uart == NULL || config == NULL || base_addr.base == NULL) {
+    return false;
+  }
+
+  uart->base_addr = base_addr;
+
+  return uart_configure(uart, config);
+}
+
+bool dif_uart_configure(const dif_uart_t *uart,
+                        const dif_uart_config_t *config) {
+  if ((uart == NULL) || (config == NULL)) {
+    return false;
+  }
+
+  return uart_configure(uart, config);
+}
+
+bool dif_uart_watermark_rx_set(const dif_uart_t *uart,
+                               dif_uart_watermark_t watermark) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Check if the requested watermark is valid, and get a corresponding
+  // register definition to be written
+  uint32_t rxi_level;
+  switch (watermark) {
+    case kDifUartWatermarkByte1:
+      rxi_level = UART_FIFO_CTRL_RXILVL_RXLVL1;
+      break;
+    case kDifUartWatermarkByte4:
+      rxi_level = UART_FIFO_CTRL_RXILVL_RXLVL4;
+      break;
+    case kDifUartWatermarkByte8:
+      rxi_level = UART_FIFO_CTRL_RXILVL_RXLVL8;
+      break;
+    case kDifUartWatermarkByte16:
+      rxi_level = UART_FIFO_CTRL_RXILVL_RXLVL16;
+      break;
+    case kDifUartWatermarkByte30:
+      rxi_level = UART_FIFO_CTRL_RXILVL_RXLVL30;
+      break;
+    default:
+      return false;
+  }
+
+  // Set watermark level
+  mmio_region_nonatomic_set_mask32(uart->base_addr, UART_FIFO_CTRL(0),
+                                   rxi_level, UART_FIFO_CTRL_RXILVL_OFFSET);
+
+  return true;
+}
+
+bool dif_uart_watermark_tx_set(const dif_uart_t *uart,
+                               dif_uart_watermark_t watermark) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Check if the requested watermark is valid, and get a corresponding
+  // register definition to be written.
+  uint32_t txi_level;
+  switch (watermark) {
+    case kDifUartWatermarkByte1:
+      txi_level = UART_FIFO_CTRL_TXILVL_TXLVL1;
+      break;
+    case kDifUartWatermarkByte4:
+      txi_level = UART_FIFO_CTRL_TXILVL_TXLVL4;
+      break;
+    case kDifUartWatermarkByte8:
+      txi_level = UART_FIFO_CTRL_TXILVL_TXLVL8;
+      break;
+    case kDifUartWatermarkByte16:
+      txi_level = UART_FIFO_CTRL_TXILVL_TXLVL16;
+      break;
+    default:
+      // The minimal TX watermark is 1 byte, maximal 16 bytes
+      return false;
+  }
+
+  // Set watermark level
+  mmio_region_nonatomic_set_mask32(uart->base_addr, UART_FIFO_CTRL(0),
+                                   txi_level, UART_FIFO_CTRL_TXILVL_OFFSET);
+
+  return true;
+}
+
+bool dif_uart_bytes_send(const dif_uart_t *uart, const uint8_t *data,
+                         size_t bytes_requested, size_t *bytes_written) {
+  if (uart == NULL || bytes_written == NULL) {
+    return false;
+  }
+
+  // |bytes_written| is an optional parameter
+  size_t res = uart_bytes_send(uart, data, bytes_requested);
+  if (bytes_written != NULL) {
+    *bytes_written = res;
+  }
+
+  return true;
+}
+
+bool dif_uart_bytes_receive(const dif_uart_t *uart, size_t bytes_requested,
+                            uint8_t *data, size_t *bytes_read) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // |bytes_read| is an optional parameter
+  size_t res = uart_bytes_receive(uart, bytes_requested, data);
+  if (bytes_read != NULL) {
+    *bytes_read = res;
+  }
+
+  return true;
+}
+
+bool dif_uart_byte_send_polled(const dif_uart_t *uart, uint8_t byte) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Busy wait for the TX FIFO to free up
+  while (uart_tx_full(uart)) {
+  }
+
+  (void)uart_bytes_send(uart, &byte, 1);
+
+  // Busy wait for the TX FIFO to be drained (the byte has been processed by
+  // the UART hardware).
+  while (!uart_tx_empty(uart)) {
+  }
+
+  return true;
+}
+
+bool dif_uart_byte_receive_polled(const dif_uart_t *uart, uint8_t *byte) {
+  if (uart == NULL || byte == NULL) {
+    return false;
+  }
+
+  // Busy wait for the RX message in the FIFO
+  while (uart_rx_empty(uart)) {
+  }
+
+  (void)uart_bytes_receive(uart, 1, byte);
+
+  return true;
+}
+
+bool dif_uart_irq_state_get(const dif_uart_t *uart,
+                            dif_uart_interrupt_t irq_type,
+                            dif_uart_enable_t *state) {
+  if (uart == NULL || state == NULL) {
+    return false;
+  }
+
+  // Get the requested interrupt state (enabled/disabled)
+  ptrdiff_t offset = uart_irq_offset_get(irq_type);
+  bool enabled =
+      mmio_region_get_bit32(uart->base_addr, UART_INTR_STATE(0), offset);
+  if (enabled) {
+    *state = kDifUartEnable;
+  } else {
+    *state = kDifUartDisable;
+  }
+
+  return true;
+}
+
+bool dif_uart_irqs_disable(const dif_uart_t *uart, uint32_t *state) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Get the current interrupts state
+  uint32_t reg = mmio_region_read32(uart->base_addr, UART_INTR_ENABLE(0));
+
+  // Disable all UART interrupts
+  mmio_region_write32(uart->base_addr, UART_INTR_ENABLE(0), 0u);
+
+  // Pass the previous interrupt state to the caller
+  if (state != NULL) {
+    *state = reg;
+  }
+
+  return true;
+}
+
+bool dif_uart_irqs_restore(const dif_uart_t *uart, uint32_t state) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Restore the interrupt state
+  mmio_region_write32(uart->base_addr, UART_INTR_ENABLE(0), state);
+
+  return true;
+}
+
+bool dif_uart_irq_enable(const dif_uart_t *uart, dif_uart_interrupt_t irq_type,
+                         dif_uart_enable_t enable) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Enable/disable the requested interrupt
+  ptrdiff_t offset = uart_irq_offset_get(irq_type);
+  if (enable == kDifUartEnable) {
+    mmio_region_nonatomic_set_bit32(uart->base_addr, UART_INTR_ENABLE(0),
+                                    offset);
+  } else {
+    mmio_region_nonatomic_clear_bit32(uart->base_addr, UART_INTR_ENABLE(0),
+                                      offset);
+  }
+
+  return true;
+}
+
+bool dif_uart_irq_force(const dif_uart_t *uart, dif_uart_interrupt_t irq_type) {
+  if (uart == NULL) {
+    return false;
+  }
+
+  // Force the requested interrupt
+  ptrdiff_t offset = uart_irq_offset_get(irq_type);
+  mmio_region_nonatomic_set_bit32(uart->base_addr, UART_INTR_TEST(0), offset);
+
+  return true;
+}
+
+bool dif_uart_rx_bytes_available(const dif_uart_t *uart, size_t *num_bytes) {
+  if (uart == NULL || num_bytes == NULL) {
+    return false;
+  }
+
+  // RX FIFO fill level (in bytes)
+  *num_bytes = (size_t)mmio_region_read_mask32(
+      uart->base_addr, UART_FIFO_STATUS(0), UART_FIFO_STATUS_RXLVL_MASK,
+      UART_FIFO_STATUS_RXLVL_OFFSET);
+
+  return true;
+}
+
+bool dif_uart_tx_bytes_available(const dif_uart_t *uart, size_t *num_bytes) {
+  if (uart == NULL || num_bytes == NULL) {
+    return false;
+  }
+
+  // TX FIFO fill level (in bytes)
+  uint32_t fill_bytes = mmio_region_read_mask32(
+      uart->base_addr, UART_FIFO_STATUS(0), UART_FIFO_STATUS_TXLVL_MASK,
+      UART_FIFO_STATUS_TXLVL_OFFSET);
+
+  *num_bytes = UART_TX_FIFO_SIZE_BYTES - fill_bytes;
+
+  return true;
+}
diff --git a/sw/device/lib/dif/dif_uart.h b/sw/device/lib/dif/dif_uart.h
new file mode 100644
index 0000000..602a3ac
--- /dev/null
+++ b/sw/device/lib/dif/dif_uart.h
@@ -0,0 +1,283 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _SW_DEVICE_LIB_DIF_UART_H_
+#define _SW_DEVICE_LIB_DIF_UART_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+
+#include "sw/device/lib/base/mmio.h"
+
+/**
+ * UART interrupt configuration
+ *
+ * Enumeration used to enable, disable, test and query the UART interrupts.
+ * Please see the comportability specification for more information:
+ * https://docs.opentitan.org/doc/rm/comportability_specification/
+ */
+typedef enum dif_uart_interrupt {
+  kDifUartInterruptTxWatermark = 0, /**< TX FIFO dipped below watermark */
+  kDifUartInterruptRxWatermark,     /**< RX FIFO reached high watermark */
+  kDifUartInterruptTxEmpty,         /**< TX FIFO empty */
+  kDifUartInterruptRxOverflow,      /**< RX FIFO overflow */
+  kDifUartInterruptRxFrameErr,      /**< RX framing error */
+  kDifUartInterruptRxBreakErr,      /**< RX break condition */
+  kDifUartInterruptRxTimeout, /**< RX FIFO timeout (not empty in a set time) */
+  kDifUartInterruptRxParityErr, /**< RX parity error detection */
+} dif_uart_interrupt_t;
+
+/**
+ * TX and RX FIFO depth configuration
+ *
+ * Enumeration used to set the upper limit of bytes to queue.
+ */
+typedef enum dif_uart_watermark {
+  kDifUartWatermarkByte1 = 0, /**< 1 byte */
+  kDifUartWatermarkByte4,     /**< 4 bytes */
+  kDifUartWatermarkByte8,     /**< 8 bytes */
+  kDifUartWatermarkByte16,    /**< 16 bytes */
+  kDifUartWatermarkByte30,    /**< 30 bytes */
+} dif_uart_watermark_t;
+
+/**
+ * Generic enable/disable enumeration
+ *
+ * Enumeration used to enable/disable bits, flags, ...
+ */
+typedef enum dif_uart_enable {
+  kDifUartEnable = 0, /**< enable */
+  kDifUartDisable,    /**< disable */
+} dif_uart_enable_t;
+
+/**
+ * UART parity enumeration
+ *
+ * Enumeration used to convey parity information
+ */
+typedef enum dif_uart_parity {
+  kDifUartParityOdd = 0, /**< odd */
+  kDifUartParityEven,    /**< even */
+} dif_uart_parity_t;
+
+/**
+ * UART configuration data
+ *
+ * The fundamental data used to configure an UART instance
+ */
+typedef struct dif_uart_config {
+  uint32_t baudrate;               /**< Requested baudrate */
+  uint32_t clk_freq_hz;            /**< Input clock frequency */
+  dif_uart_enable_t parity_enable; /**< Enable parity check */
+  dif_uart_parity_t parity;        /**< Set parity (even by default) */
+} dif_uart_config_t;
+
+/**
+ * UART instance state
+ *
+ * UART persistent data that is required by all UART API. |base_address| must
+ * be initialised by the caller, before passing into the UART DIF init routine.
+ */
+typedef struct dif_uart {
+  mmio_region_t base_addr; /**< UART base address */
+} dif_uart_t;
+
+/**
+ * Initialise an instance of UART
+ *
+ * Initialise UART instance using the configuration data in @p arg2.
+ * Information that must be retained, and is required to program UART must be
+ * stored in @p arg3.
+ * @param base_addr Base address of an instance of UART IP block
+ * @param config UART configuration data
+ * @param uart UART state data
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_init(mmio_region_t base_addr, const dif_uart_config_t *config,
+                   dif_uart_t *uart);
+
+/**
+ * Configure an instance of UART
+ *
+ * Configure UART using the configuration data in @p arg2. This operation
+ * performs fundamental configuration.
+ *
+ * @param uart UART state data
+ * @param config UART configuration data
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_configure(const dif_uart_t *uart,
+                        const dif_uart_config_t *config);
+
+/**
+ * Set the RX FIFO watermark
+ *
+ * Set the RX FIFO watermark, is only useful when the corresponding interrupt
+ * is enabled. When the queued RX FIFO number of bytes rises to or above this
+ * level, the RX watermark interrupt is raised.
+ *
+ * @param uart UART state data
+ * @param watermark RX FIFO watermark
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_watermark_rx_set(const dif_uart_t *uart,
+                               dif_uart_watermark_t watermark);
+/**
+ * Set the TX FIFO watermark
+ *
+ * Set the TX FIFO watermark, is only useful when the corresponding interrupt
+ * is enabled. When the queued TX FIFO number of bytes falls to or below this
+ * level, the TX watermark interrupt is raised.
+ *
+ * @param uart UART state data
+ * @param watermark TX FIFO watermark
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_watermark_tx_set(const dif_uart_t *uart,
+                               dif_uart_watermark_t watermark);
+
+/**
+ * UART send bytes
+ *
+ * Non-blocking UART send bytes routine. Can be used from inside an UART ISR.
+ * This function attempts to write @p arg3 number of bytes to the UART TX FIFO
+ * from @p arg3, and passes @p arg4 back to the caller.
+ *
+ * @param uart UART state data
+ * @param data Data to be written
+ * @param bytes_requested Number of bytes requested to be written by the caller
+ * @param bytes_written Number of bytes written (optional)
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_bytes_send(const dif_uart_t *uart, const uint8_t *data,
+                         size_t bytes_requested, size_t *bytes_written);
+
+/**
+ * UART receive bytes
+ *
+ * Non-blocking UART receive bytes routine. Can be used from inside an UART ISR.
+ * This function attempts to read @p arg2 number of bytes from the UART RX FIFO
+ * into @p arg3, and passes @p arg4 back to the caller.
+ *
+ * @param uart UART state data
+ * @param bytes_requested Number of bytes requested to be read by the caller
+ * @param data Data to be read
+ * @param bytes_read Number of bytes read (optional)
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_bytes_receive(const dif_uart_t *uart, size_t bytes_requested,
+                            uint8_t *data, size_t *bytes_read);
+
+/**
+ * Transmit a single UART byte (polled)
+ *
+ * Transmit a single UART byte @p arg2. This operation is polled, and will busy
+ * wait until a byte has been sent. Must not be used inside an ISR.
+ *
+ * @param uart UART state data
+ * @param byte Byte to be transmitted
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_byte_send_polled(const dif_uart_t *uart, uint8_t byte);
+
+/**
+ * Receive a single UART byte (polled)
+ *
+ * Receive a single UART byte and store it in @p arg2. This operation is polled,
+ * and will busy wait until a byte has been read. Must not be used inside an
+ * ISR.
+ *
+ * @param uart UART state data
+ * @param byte Received byte
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_byte_receive_polled(const dif_uart_t *uart, uint8_t *byte);
+
+/**
+ * UART get requested IRQ state
+ *
+ * Get the state of the requested IRQ in @p arg2.
+ *
+ * @para uart UART state data
+ * @param irq_type IRQ to get the state of
+ * @param state IRQ state passed back to the caller
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_irq_state_get(const dif_uart_t *uart,
+                            dif_uart_interrupt_t irq_type,
+                            dif_uart_enable_t *state);
+
+/**
+ * UART disable interrupts
+ *
+ * Disable generation of all UART interrupts, and pass previous interrupt state
+ * in @p arg3 back to the caller. Parameter @p arg2 is ignored if NULL.
+ *
+ * @param uart UART state data
+ * @param state IRQ state passed back to the caller
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_irqs_disable(const dif_uart_t *uart, uint32_t *state);
+
+/**
+ * UART restore IRQ state
+ *
+ * Restore previous UART IRQ state. This function is used to restore the
+ * UART interrupt state prior to dif_uart_irqs_disable function call.
+ *
+ * @param uart UART state data
+ * @param state IRQ state to restore
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_irqs_restore(const dif_uart_t *uart, uint32_t state);
+
+/**
+ * UART interrupt control
+ *
+ * Enable/disable an UART interrupt specified in @p arg3.
+ *
+ * @param uart UART state data
+ * @param irq_type UART interrupt type
+ * @param enable enable or disable the interrupt
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_irq_enable(const dif_uart_t *uart, dif_uart_interrupt_t irq_type,
+                         dif_uart_enable_t enable);
+
+/**
+ * UART interrupt force
+ *
+ * Force interrupt specified in @p arg2.
+ *
+ * @param uart UART state data
+ * @param irq_type UART interrupt type to be forced
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_irq_force(const dif_uart_t *uart, dif_uart_interrupt_t irq_type);
+
+/**
+ * UART RX bytes available
+ *
+ * Get the number of bytes available to be read from the UART RX FIFO. This
+ * function can be used to check FIFO full and empty conditions.
+ *
+ * @param uart UART state data
+ * @param num_bytes Number of bytes available to be read
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_rx_bytes_available(const dif_uart_t *uart, size_t *num_bytes);
+
+/**
+ * UART TX bytes available
+ *
+ * Get the number of bytes available to be written to the UART TX FIFO. This
+ * function can be used to check FIFO full and empty conditions.
+ *
+ * @param uart UART state data
+ * @param num_bytes Number of bytes available to be written
+ * @return true if the function was successful, false otherwise
+ */
+bool dif_uart_tx_bytes_available(const dif_uart_t *uart, size_t *num_bytes);
+
+#endif
diff --git a/sw/device/lib/dif/meson.build b/sw/device/lib/dif/meson.build
new file mode 100644
index 0000000..2edd53e
--- /dev/null
+++ b/sw/device/lib/dif/meson.build
@@ -0,0 +1,18 @@
+# Copyright lowRISC contributors.
+# Licensed under the Apache License, Version 2.0, see LICENSE for details.
+# SPDX-License-Identifier: Apache-2.0
+
+# UART DIF library (dif_uart)
+dif_uart = declare_dependency(
+  sources: [hw_ip_uart_reg_h],
+  link_with: static_library(
+    'uart_ot',
+    sources: [
+      hw_ip_uart_reg_h,
+      'dif_uart.c',
+    ],
+    dependencies: [
+      sw_lib_mmio,
+    ]
+  )
+)