You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by je...@apache.org on 2021/02/01 10:44:40 UTC

[mynewt-core] branch master updated (c3991db -> b65788b)

This is an automated email from the ASF dual-hosted git repository.

jerzy pushed a change to branch master
in repository https://gitbox.apache.org/repos/asf/mynewt-core.git.


    from c3991db  hw/drivers/i2s: Add I2S driver for DA1469x family
     new d4b7ca6  hw/mcu/da1469x: Add UART driver
     new b65788b  hw/mcu/da1469x: Add UART driver to MCU peripherals

The 2 revisions listed above as "new" are entirely new to this
repository and will be described in separate emails.  The revisions
listed as "add" were already present in the repository and have only
been added to this reference.


Summary of changes:
 .../include/uart_da1469x/uart_da1469x.h            |  70 +++
 hw/drivers/uart/{uart_hal => uart_da1469x}/pkg.yml |   4 +-
 hw/drivers/uart/uart_da1469x/src/uart_da1469x.c    | 563 +++++++++++++++++++++
 .../drivers/uart/uart_da1469x}/syscfg.yml          |  15 +-
 hw/mcu/dialog/da1469x/pkg.yml                      |   5 +-
 hw/mcu/dialog/da1469x/src/da1469x_periph.c         |  42 +-
 hw/mcu/dialog/da1469x/syscfg.yml                   |   4 +
 7 files changed, 681 insertions(+), 22 deletions(-)
 create mode 100644 hw/drivers/uart/uart_da1469x/include/uart_da1469x/uart_da1469x.h
 copy hw/drivers/uart/{uart_hal => uart_da1469x}/pkg.yml (92%)
 create mode 100644 hw/drivers/uart/uart_da1469x/src/uart_da1469x.c
 copy {apps/lorashell => hw/drivers/uart/uart_da1469x}/syscfg.yml (77%)


[mynewt-core] 01/02: hw/mcu/da1469x: Add UART driver

Posted by je...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

jerzy pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/mynewt-core.git

commit d4b7ca6682614697b7faf2ecd596bd2c92c0af07
Author: Jerzy Kasenberg <je...@codecoup.pl>
AuthorDate: Mon Dec 14 12:35:33 2020 +0100

    hw/mcu/da1469x: Add UART driver
    
    Driver that shuts down UART when RX line goes low to minimize
    power consumption.
---
 .../include/uart_da1469x/uart_da1469x.h            |  70 +++
 hw/drivers/uart/uart_da1469x/pkg.yml               |  28 +
 hw/drivers/uart/uart_da1469x/src/uart_da1469x.c    | 563 +++++++++++++++++++++
 hw/drivers/uart/uart_da1469x/syscfg.yml            |  25 +
 4 files changed, 686 insertions(+)

diff --git a/hw/drivers/uart/uart_da1469x/include/uart_da1469x/uart_da1469x.h b/hw/drivers/uart/uart_da1469x/include/uart_da1469x/uart_da1469x.h
new file mode 100644
index 0000000..7360207
--- /dev/null
+++ b/hw/drivers/uart/uart_da1469x/include/uart_da1469x/uart_da1469x.h
@@ -0,0 +1,70 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance
+ * with the License.  You may obtain a copy of the License at
+ *
+ *  http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+ * KIND, either express or implied.  See the License for the
+ * specific language governing permissions and limitations
+ * under the License.
+ */
+
+#ifndef __DRIVERS_UART_DA1469X_H_
+#define __DRIVERS_UART_DA1469X_H_
+
+#include "uart/uart.h"
+#include "mcu/da1469x_hal.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+struct da1469x_uart_hw_data;
+
+struct da1469x_uart_dev {
+    struct uart_dev dev;
+    /* Common UART parameters. */
+    struct uart_conf uc;
+    /* DA1469x specific configuration. */
+    struct da1469x_uart_cfg da1469x_cfg;
+
+    /* driver state data */
+    uint8_t active : 1;
+    uint8_t tx_started : 1;
+    uint8_t rx_started : 1;
+    uint8_t rx_stalled : 1;
+    uint8_t rx_data;
+
+    /* Callout used to re-enable UART after it RX pin went high. */
+    struct os_callout wakeup_callout;
+    /* Event raised from interrupt (busy/break) that will setup RX pin to GPIO with interrupt in task context. */
+    struct os_event setup_wakeup_event;
+    /* Hardware configuration, register addresses bit mask and such. */
+    const struct da1469x_uart_hw_data *hw;
+};
+
+/**
+ * Creates UART OS device
+ *
+ * @param dev - device structure to initialize
+ * @param name - device name (must end with character 0|1|2 like "uart0")
+ * @param priority - priority for os_dev_create
+ * @param da1469x_cfg - UART parameters
+ * @return 0 on success,
+ */
+int da1469x_uart_dev_create(struct da1469x_uart_dev *dev, const char *name, uint8_t priority,
+                            const struct da1469x_uart_cfg *da1469x_cfg);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __DRIVERS_UART_DA1469X_H_ */
diff --git a/hw/drivers/uart/uart_da1469x/pkg.yml b/hw/drivers/uart/uart_da1469x/pkg.yml
new file mode 100644
index 0000000..cd1a182
--- /dev/null
+++ b/hw/drivers/uart/uart_da1469x/pkg.yml
@@ -0,0 +1,28 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance
+# with the License.  You may obtain a copy of the License at
+#
+#  http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing,
+# software distributed under the License is distributed on an
+# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+# KIND, either express or implied.  See the License for the
+# specific language governing permissions and limitations
+# under the License.
+#
+
+pkg.name: hw/drivers/uart/uart_da1469x
+pkg.description: UART driver for DA1469X
+pkg.author: "Apache Mynewt <de...@mynewt.apache.org>"
+pkg.homepage: "http://mynewt.apache.org/"
+pkg.keywords:
+pkg.apis:
+pkg.deps:
+    - "@apache-mynewt-core/hw/hal"
+    - "@apache-mynewt-core/hw/drivers/uart"
diff --git a/hw/drivers/uart/uart_da1469x/src/uart_da1469x.c b/hw/drivers/uart/uart_da1469x/src/uart_da1469x.c
new file mode 100644
index 0000000..c40686a
--- /dev/null
+++ b/hw/drivers/uart/uart_da1469x/src/uart_da1469x.c
@@ -0,0 +1,563 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance
+ * with the License.  You may obtain a copy of the License at
+ *
+ *  http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+ * KIND, either express or implied.  See the License for the
+ * specific language governing permissions and limitations
+ * under the License.
+ */
+
+#include <assert.h>
+#include <string.h>
+#include <bsp.h>
+#include "uart/uart.h"
+#include "mcu/da1469x_pd.h"
+#include "mcu/da1469x_hal.h"
+#include "hal/hal_gpio.h"
+#include "uart_da1469x/uart_da1469x.h"
+
+static void da1469x_uart_uart_isr(void);
+static void da1469x_uart_uart2_isr(void);
+static void da1469x_uart_uart3_isr(void);
+
+struct da1469x_uart_hw_data {
+    UART2_Type *regs;
+    IRQn_Type irqn;
+    mcu_gpio_func rx_pin_func;
+    mcu_gpio_func tx_pin_func;
+    mcu_gpio_func rts_pin_func;
+    mcu_gpio_func cts_pin_func;
+    /* Mask for (RE)SET_CLK_COM_REG */
+    uint8_t clk_com_mask;
+    void (*isr)(void);
+};
+
+static const struct da1469x_uart_hw_data da1469x_uart0_hw = {
+    .regs = (UART2_Type *)UART,
+    .irqn = UART_IRQn,
+    .rx_pin_func = MCU_GPIO_FUNC_UART_RX,
+    .tx_pin_func = MCU_GPIO_FUNC_UART_TX,
+    .rts_pin_func = MCU_GPIO_FUNC_GPIO,
+    .cts_pin_func = MCU_GPIO_FUNC_GPIO,
+    .clk_com_mask = CRG_COM_RESET_CLK_COM_REG_UART_ENABLE_Msk,
+    .isr = da1469x_uart_uart_isr,
+};
+
+static const struct da1469x_uart_hw_data da1469x_uart1_hw = {
+    .regs = (UART2_Type *)UART2,
+    .irqn = UART2_IRQn,
+    .rx_pin_func = MCU_GPIO_FUNC_UART2_RX,
+    .tx_pin_func = MCU_GPIO_FUNC_UART2_TX,
+    .rts_pin_func = MCU_GPIO_FUNC_UART2_RTSN,
+    .cts_pin_func = MCU_GPIO_FUNC_UART2_CTSN,
+    .clk_com_mask = CRG_COM_RESET_CLK_COM_REG_UART2_ENABLE_Msk,
+    .isr = da1469x_uart_uart2_isr,
+};
+
+static const struct da1469x_uart_hw_data da1469x_uart2_hw = {
+    .regs = (UART2_Type *)UART3,
+    .irqn = UART3_IRQn,
+    .rx_pin_func = MCU_GPIO_FUNC_UART3_RX,
+    .tx_pin_func = MCU_GPIO_FUNC_UART3_TX,
+    .rts_pin_func = MCU_GPIO_FUNC_UART3_RTSN,
+    .cts_pin_func = MCU_GPIO_FUNC_UART3_CTSN,
+    .clk_com_mask = CRG_COM_RESET_CLK_COM_REG_UART3_ENABLE_Msk,
+    .isr = da1469x_uart_uart3_isr,
+};
+
+static struct da1469x_uart_dev *da1469x_dev0;
+static struct da1469x_uart_dev *da1469x_dev1;
+static struct da1469x_uart_dev *da1469x_dev2;
+
+static void da1469x_uart_uart_configure(struct da1469x_uart_dev *dev);
+static void da1469x_uart_uart_shutdown(struct da1469x_uart_dev *dev);
+
+static void
+da1469x_uart_on_wakeup_callout_cb(struct os_event *ev)
+{
+    struct da1469x_uart_dev *dev = ev->ev_arg;
+
+    da1469x_uart_uart_configure(dev);
+}
+
+static void
+da1469x_uart_on_wakeup_gpio_cb(void *arg)
+{
+    struct da1469x_uart_dev *dev = arg;
+
+    hal_gpio_irq_disable(dev->da1469x_cfg.pin_rx);
+    hal_gpio_irq_release(dev->da1469x_cfg.pin_rx);
+
+    os_callout_reset(&dev->wakeup_callout,
+                     os_time_ms_to_ticks32(MYNEWT_VAL(UART_DA1469X_WAKEUP_DELAY_MS)));
+}
+
+static void
+da1469x_uart_on_setup_wakeup_cb(struct os_event *ev)
+{
+    struct da1469x_uart_dev *dev = ev->ev_arg;
+
+    hal_gpio_irq_init(dev->da1469x_cfg.pin_rx, da1469x_uart_on_wakeup_gpio_cb, dev,
+                      HAL_GPIO_TRIG_RISING, HAL_GPIO_PULL_NONE);
+    hal_gpio_irq_enable(dev->da1469x_cfg.pin_rx);
+}
+
+static void
+da1469x_uart_setup_wakeup(struct da1469x_uart_dev *dev)
+{
+    os_eventq_put(os_eventq_dflt_get(), &dev->setup_wakeup_event);
+}
+
+static inline void
+da1469x_uart_tx_intr_enable(struct da1469x_uart_dev *dev)
+{
+    dev->hw->regs->UART2_IER_DLH_REG |= UART2_UART2_IER_DLH_REG_PTIME_DLH7_Msk |
+                                        UART2_UART2_IER_DLH_REG_ETBEI_DLH1_Msk;
+}
+
+static inline void
+da1469x_uart_tx_intr_disable(struct da1469x_uart_dev *dev)
+{
+    dev->hw->regs->UART2_IER_DLH_REG &= ~(UART2_UART2_IER_DLH_REG_PTIME_DLH7_Msk |
+                                          UART2_UART2_IER_DLH_REG_ETBEI_DLH1_Msk);
+}
+
+static inline void
+da1469x_uart_lsr_intr_enable(struct da1469x_uart_dev *dev)
+{
+    dev->hw->regs->UART2_IER_DLH_REG |= UART2_UART2_IER_DLH_REG_ELSI_DLH2_Msk;
+}
+
+static inline void
+da1469x_uart_rx_intr_enable(struct da1469x_uart_dev *dev)
+{
+    dev->hw->regs->UART2_IER_DLH_REG |= UART2_UART2_IER_DLH_REG_ERBFI_DLH0_Msk;
+}
+
+static inline void
+da1469x_uart_rx_intr_disable(struct da1469x_uart_dev *dev)
+{
+    dev->hw->regs->UART2_IER_DLH_REG &= ~UART2_UART2_IER_DLH_REG_ERBFI_DLH0_Msk;
+}
+
+static void
+da1469x_uart_isr_thr_empty(struct da1469x_uart_dev *dev)
+{
+    struct uart_conf *uc = &dev->uc;
+    int ch;
+
+    while (dev->hw->regs->UART2_USR_REG & UART2_UART2_USR_REG_UART_TFNF_Msk) {
+        ch = uc->uc_tx_char(uc->uc_cb_arg);
+        if (ch < 0) {
+            da1469x_uart_tx_intr_disable(dev);
+            dev->tx_started = 0;
+            if (uc->uc_tx_done) {
+                uc->uc_tx_done(uc->uc_cb_arg);
+            }
+            break;
+        }
+
+        dev->hw->regs->UART2_RBR_THR_DLL_REG = ch;
+    }
+}
+
+static void
+da1469x_uart_isr_recv_data(struct da1469x_uart_dev *dev)
+{
+    int ch;
+
+    dev->rx_data = dev->hw->regs->UART2_RBR_THR_DLL_REG;
+
+    ch = dev->uc.uc_rx_char(dev->uc.uc_cb_arg, dev->rx_data);
+    if (ch < 0) {
+        da1469x_uart_rx_intr_disable(dev);
+        dev->rx_stalled = 1;
+    }
+}
+
+static void
+da1469x_uart_isr(struct da1469x_uart_dev *dev)
+{
+    UART2_Type *uart = dev->hw->regs;
+    bool no_intr = false;
+
+    os_trace_isr_enter();
+
+    while (!no_intr) {
+        /*
+         * NOTE: should be UART2_UART2_IIR_FCR_REG_IIR_FCR_Msk below but this is
+         *     defined (incorrectly) as 0xFF so incorrect value is read.
+         */
+        switch (uart->UART2_IIR_FCR_REG & 0x0F) {
+        case 0x01: /* no interrupt pending */
+            no_intr = true;
+            break;
+        case 0x02: /* THR empty */
+            da1469x_uart_isr_thr_empty(dev);
+            break;
+        case 0x04: /* received data available */
+            da1469x_uart_isr_recv_data(dev);
+            break;
+        case 0x06: /* receiver line status */
+            if (uart->UART2_LSR_REG & UART2_UART2_LSR_REG_UART_BI_Msk) {
+                da1469x_uart_uart_shutdown(dev);
+                da1469x_uart_setup_wakeup(dev);
+                no_intr = true;
+            }
+            break;
+        case 0x07: /* busy detect */
+            (void)uart->UART2_USR_REG;
+            da1469x_uart_uart_shutdown(dev);
+            da1469x_uart_setup_wakeup(dev);
+            no_intr = true;
+            break;
+        case 0x0c: /* character timeout */
+            break;
+        default:
+            assert(0);
+            break;
+        }
+    }
+
+    os_trace_isr_exit();
+}
+
+static void
+da1469x_uart_uart_isr(void)
+{
+    da1469x_uart_isr(da1469x_dev0);
+}
+
+static void
+da1469x_uart_uart2_isr(void)
+{
+    da1469x_uart_isr(da1469x_dev1);
+}
+
+static void
+da1469x_uart_uart3_isr(void)
+{
+    da1469x_uart_isr(da1469x_dev2);
+}
+
+static void
+da1469x_uart_uart_configure(struct da1469x_uart_dev *dev)
+{
+    struct uart_conf *uc = &dev->uc;
+    uint32_t baudrate_cfg;
+    uint32_t reg;
+    UART2_Type *uart = dev->hw->regs;
+    IRQn_Type irqn = dev->hw->irqn;
+
+    da1469x_pd_acquire(MCU_PD_DOMAIN_COM);
+
+    NVIC_DisableIRQ(irqn);
+
+    if (dev->da1469x_cfg.pin_rx >= 0) {
+        /* Turn RX pin to GPIO input during configuration to avoid busy state */
+        mcu_gpio_set_pin_function(dev->da1469x_cfg.pin_rx, MCU_GPIO_MODE_INPUT,
+                                  MCU_GPIO_FUNC_GPIO);
+    }
+
+    /* Reset UART */
+    CRG_COM->RESET_CLK_COM_REG = dev->hw->clk_com_mask;
+    CRG_COM->SET_CLK_COM_REG = dev->hw->clk_com_mask;
+    uart->UART2_SRR_REG = UART2_UART2_SRR_REG_UART_UR_Msk |
+                          UART2_UART2_SRR_REG_UART_RFR_Msk |
+                          UART2_UART2_SRR_REG_UART_XFR_Msk;
+
+    /* Configure baudrate */
+    baudrate_cfg = (32000000 - 1 + (uc->uc_speed / 2)) / uc->uc_speed;
+    uart->UART2_LCR_REG |= UART2_UART2_LCR_REG_UART_DLAB_Msk;
+    uart->UART2_IER_DLH_REG = (baudrate_cfg >> 12) & 0xff;
+    uart->UART2_RBR_THR_DLL_REG = (baudrate_cfg >> 4) & 0xff;
+    uart->UART2_DLF_REG = baudrate_cfg & 0x0f;
+    uart->UART2_LCR_REG &= ~UART2_UART2_LCR_REG_UART_DLAB_Msk;
+
+    /* Configure frame */
+    reg = 0;
+    switch (uc->uc_parity) {
+    case UART_PARITY_NONE:
+        break;
+    case UART_PARITY_EVEN:
+        reg |= UART2_UART2_LCR_REG_UART_EPS_Msk;
+        /* no break */
+    case UART_PARITY_ODD:
+        reg |= UART2_UART2_LCR_REG_UART_PEN_Msk;
+        break;
+    }
+    reg |= (uc->uc_stopbits - 1) << UART2_UART2_LCR_REG_UART_STOP_Pos;
+    reg |= (uc->uc_databits - 5) << UART2_UART2_LCR_REG_UART_DLS_Pos;
+    uart->UART2_LCR_REG = reg;
+
+    /* Enable flow-control if requested and supported */
+    if (uc->uc_flow_ctl == UART_FLOW_CTL_RTS_CTS) {
+        uart->UART2_MCR_REG |= UART2_UART2_MCR_REG_UART_AFCE_Msk |
+                               UART2_UART2_MCR_REG_UART_RTS_Msk;
+    }
+    /* Enable hardware FIFO */
+    uart->UART2_SFE_REG = UART2_UART2_SFE_REG_UART_SHADOW_FIFO_ENABLE_Msk;
+    uart->UART2_SRT_REG = 0;
+    uart->UART2_STET_REG = 0;
+
+    dev->active = 1;
+    dev->rx_stalled = 0;
+    dev->tx_started = 0;
+
+    da1469x_uart_lsr_intr_enable(dev);
+
+    mcu_gpio_set_pin_function(dev->da1469x_cfg.pin_tx, MCU_GPIO_MODE_OUTPUT,
+                              dev->hw->tx_pin_func);
+
+    if (dev->da1469x_cfg.pin_rx >= 0) {
+        mcu_gpio_set_pin_function(dev->da1469x_cfg.pin_rx,
+                                  dev->da1469x_cfg.rx_pullup ? MCU_GPIO_MODE_INPUT_PULLUP : MCU_GPIO_MODE_INPUT,
+                                  dev->hw->rx_pin_func);
+        da1469x_uart_rx_intr_enable(dev);
+    }
+
+    if (dev->da1469x_cfg.pin_rts >= 0) {
+        mcu_gpio_set_pin_function(dev->da1469x_cfg.pin_rts, MCU_GPIO_MODE_OUTPUT,
+                                  dev->hw->rts_pin_func);
+    }
+
+    if (dev->da1469x_cfg.pin_cts >= 0) {
+        mcu_gpio_set_pin_function(dev->da1469x_cfg.pin_cts, MCU_GPIO_MODE_INPUT,
+                                  dev->hw->cts_pin_func);
+    }
+
+    NVIC_ClearPendingIRQ(irqn);
+    NVIC_EnableIRQ(irqn);
+}
+
+static void
+da1469x_uart_uart_shutdown(struct da1469x_uart_dev *dev)
+{
+    dev->active = 0;
+
+    /*
+     * Reset UART before disabling clock to avoid any unexpected behavior after
+     * clock is enabled again.
+     */
+    dev->hw->regs->UART2_SRR_REG = UART2_UART2_SRR_REG_UART_UR_Msk |
+                                   UART2_UART2_SRR_REG_UART_RFR_Msk |
+                                   UART2_UART2_SRR_REG_UART_XFR_Msk;
+    NVIC_DisableIRQ(dev->hw->irqn);
+    NVIC_ClearPendingIRQ(dev->hw->irqn);
+
+    CRG_COM->RESET_CLK_COM_REG = dev->hw->clk_com_mask;
+
+    da1469x_pd_release(MCU_PD_DOMAIN_COM);
+}
+
+static int
+da1469x_uart_open(struct os_dev *odev, uint32_t wait, void *arg)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)odev;
+    struct uart_conf *uc = (struct uart_conf *)arg;
+    (void)wait;
+
+    if (!uc) {
+        return OS_EINVAL;
+    }
+
+    if (odev->od_flags & OS_DEV_F_STATUS_OPEN) {
+        return OS_EBUSY;
+    }
+
+    dev->uc = *uc;
+
+    if (uc->uc_speed < 1200 || uc->uc_speed > 1000000) {
+        return OS_INVALID_PARM;
+    }
+
+    if ((uc->uc_databits < 5) || (uc->uc_databits > 8) ||
+        (uc->uc_stopbits < 1) || (uc->uc_stopbits > 2)) {
+        return OS_INVALID_PARM;
+    }
+
+    if ((uc->uc_parity != UART_PARITY_NONE) &&
+        (uc->uc_parity != UART_PARITY_ODD) &&
+        (uc->uc_parity != UART_PARITY_EVEN)) {
+        return OS_INVALID_PARM;
+    }
+
+    if (uc->uc_flow_ctl == UART_FLOW_CTL_RTS_CTS) {
+#if MYNEWT_VAL(UART_0)
+        if (dev->hw->regs == (UART2_Type *)UART) {
+            return OS_INVALID_PARM;
+        }
+#endif
+        if (dev->da1469x_cfg.pin_rts < 0 || dev->da1469x_cfg.pin_cts < 0) {
+            return OS_INVALID_PARM;
+        }
+    }
+
+    da1469x_uart_uart_configure(dev);
+
+    return OS_OK;
+}
+
+static int
+da1469x_uart_close(struct os_dev *odev)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)odev;
+
+    da1469x_uart_uart_shutdown(dev);
+
+    return OS_OK;
+}
+
+static void
+da1469x_uart_drain_tx(struct da1469x_uart_dev *dev)
+{
+    struct uart_conf *uc = &dev->uc;
+    int ch;
+
+    while (1) {
+        ch = uc->uc_tx_char(uc->uc_cb_arg);
+        if (ch < 0) {
+            if (uc->uc_tx_done) {
+                uc->uc_tx_done(uc->uc_cb_arg);
+            }
+            break;
+        }
+    }
+}
+
+static void
+da1469x_uart_start_tx(struct uart_dev *udev)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)udev;
+    os_sr_t sr;
+
+    if (!dev->active) {
+        da1469x_uart_drain_tx(dev);
+        return;
+    }
+
+    OS_ENTER_CRITICAL(sr);
+
+    if (dev->tx_started == 0) {
+        dev->tx_started = 1;
+        da1469x_uart_tx_intr_enable(dev);
+    }
+
+    OS_EXIT_CRITICAL(sr);
+}
+
+static void
+da1469x_uart_start_rx(struct uart_dev *udev)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)udev;
+    int ch;
+    os_sr_t sr;
+
+    OS_ENTER_CRITICAL(sr);
+
+    if (dev->rx_stalled) {
+        ch = dev->uc.uc_rx_char(dev->uc.uc_cb_arg, dev->rx_data);
+        if (ch >= 0) {
+            dev->rx_stalled = 0;
+            da1469x_uart_rx_intr_enable(dev);
+        }
+    }
+
+    OS_EXIT_CRITICAL(sr);
+}
+
+static void
+da1469x_uart_blocking_tx(struct uart_dev *udev, uint8_t byte)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)udev;
+    UART2_Type *uart = dev->hw->regs;
+
+    if (!dev->active) {
+        return;
+    }
+
+    while (!(uart->UART2_USR_REG & UART2_UART2_USR_REG_UART_TFNF_Msk)) {
+        /* Wait until FIFO has free space */
+    }
+
+    uart->UART2_RBR_THR_DLL_REG = byte;
+
+    while (!(uart->UART2_USR_REG & UART2_UART2_USR_REG_UART_TFE_Msk) ||
+            (uart->UART2_USR_REG & UART2_UART2_USR_REG_UART_BUSY_Msk)) {
+        /* Wait until FIFO is empty and UART finished tx */
+    }
+}
+
+static int
+da1469x_uart_init(struct os_dev *odev, void *arg)
+{
+    struct da1469x_uart_dev *dev = (struct da1469x_uart_dev *)odev;
+    struct da1469x_uart_cfg *cfg = arg;
+
+    if (cfg->pin_rx >= 0) {
+        os_callout_init(&dev->wakeup_callout, os_eventq_dflt_get(),
+                        da1469x_uart_on_wakeup_callout_cb, dev);
+
+        dev->setup_wakeup_event.ev_cb = da1469x_uart_on_setup_wakeup_cb;
+        dev->setup_wakeup_event.ev_arg = dev;
+    }
+
+    OS_DEV_SETHANDLERS(odev, da1469x_uart_open, da1469x_uart_close);
+
+    dev->dev.ud_funcs.uf_start_tx = da1469x_uart_start_tx;
+    dev->dev.ud_funcs.uf_start_rx = da1469x_uart_start_rx;
+    dev->dev.ud_funcs.uf_blocking_tx = da1469x_uart_blocking_tx;
+
+    dev->da1469x_cfg = *cfg;
+
+    NVIC_DisableIRQ(dev->hw->irqn);
+    NVIC_SetPriority(dev->hw->irqn, (1 << __NVIC_PRIO_BITS) - 1);
+    NVIC_SetVector(dev->hw->irqn, (uint32_t)dev->hw->isr);
+
+    return OS_OK;
+}
+
+int
+da1469x_uart_dev_create(struct da1469x_uart_dev *dev, const char *name, uint8_t priority,
+                        const struct da1469x_uart_cfg *da1469x_cfg)
+{
+    size_t uart_num_idx;
+    int uart_num;
+
+    if (dev == NULL || name == NULL || da1469x_cfg == NULL) {
+        return OS_EINVAL;
+    }
+
+    /* Get UART number from device name last character. */
+    uart_num_idx = strlen(name) - 1;
+    uart_num = name[uart_num_idx] - '0';
+
+    if (MYNEWT_VAL(UART_0) && uart_num == 0) {
+        dev->hw = &da1469x_uart0_hw;
+        assert(da1469x_dev0 == NULL);
+        da1469x_dev0 = dev;
+    } else if (MYNEWT_VAL(UART_1) && uart_num == 1) {
+        dev->hw = &da1469x_uart1_hw;
+        assert(da1469x_dev1 == NULL);
+        da1469x_dev1 = dev;
+    } else if (MYNEWT_VAL(UART_2) && uart_num == 2) {
+        dev->hw = &da1469x_uart2_hw;
+        assert(da1469x_dev2 == NULL);
+        da1469x_dev2 = dev;
+    } else {
+        return OS_ENOENT;
+    }
+
+    return os_dev_create((struct os_dev *)dev, name, OS_DEV_INIT_PRIMARY, priority, da1469x_uart_init,
+                         (void *)da1469x_cfg);
+}
diff --git a/hw/drivers/uart/uart_da1469x/syscfg.yml b/hw/drivers/uart/uart_da1469x/syscfg.yml
new file mode 100644
index 0000000..ca71fdb
--- /dev/null
+++ b/hw/drivers/uart/uart_da1469x/syscfg.yml
@@ -0,0 +1,25 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance
+# with the License.  You may obtain a copy of the License at
+#
+#  http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing,
+# software distributed under the License is distributed on an
+# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+# KIND, either express or implied.  See the License for the
+# specific language governing permissions and limitations
+# under the License.
+#
+
+syscfg.defs:
+    UART_DA1469X_WAKEUP_DELAY_MS:
+       description: >
+          Delay between detected high state on RX line (i.e. UART is attached)
+          and configuring UART. This is to ensure RX is debounced properly.
+       value: 100


[mynewt-core] 02/02: hw/mcu/da1469x: Add UART driver to MCU peripherals

Posted by je...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

jerzy pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/mynewt-core.git

commit b65788b8422817d72bdbf06319bcf04a7f621cdf
Author: Jerzy Kasenberg <je...@codecoup.pl>
AuthorDate: Mon Dec 14 12:42:42 2020 +0100

    hw/mcu/da1469x: Add UART driver to MCU peripherals
    
    uart_hal driver was used for devices created in da1469x_periph_create().
    Now da1469x_uart driver will be used by default.
    
    When UART_HAL syscfg value is set to 1 original uart_hal driver
    will be used instead.
---
 hw/mcu/dialog/da1469x/pkg.yml              |  5 +++-
 hw/mcu/dialog/da1469x/src/da1469x_periph.c | 42 +++++++++++++++++++++++-------
 hw/mcu/dialog/da1469x/syscfg.yml           |  4 +++
 3 files changed, 41 insertions(+), 10 deletions(-)

diff --git a/hw/mcu/dialog/da1469x/pkg.yml b/hw/mcu/dialog/da1469x/pkg.yml
index 1338720..ef753b1 100644
--- a/hw/mcu/dialog/da1469x/pkg.yml
+++ b/hw/mcu/dialog/da1469x/pkg.yml
@@ -39,9 +39,12 @@ pkg.deps.TRNG:
 pkg.deps.CRYPTO:
     - "@apache-mynewt-core/hw/drivers/crypto/crypto_da1469x"
 
-pkg.deps.'UART_0 || UART_1 || UART_2':
+pkg.deps.'(UART_0 || UART_1 || UART_2) && HAL_UART':
     - "@apache-mynewt-core/hw/drivers/uart/uart_hal"
 
+pkg.deps.'(UART_0 || UART_1 || UART_2) && !HAL_UART':
+    - "@apache-mynewt-core/hw/drivers/uart/uart_da1469x"
+
 pkg.deps.'(I2C_0 || I2C_1) && BUS_DRIVER_PRESENT':
     - "@apache-mynewt-core/hw/bus/drivers/i2c_hal"
 
diff --git a/hw/mcu/dialog/da1469x/src/da1469x_periph.c b/hw/mcu/dialog/da1469x/src/da1469x_periph.c
index 0e2945b..c75483f 100644
--- a/hw/mcu/dialog/da1469x/src/da1469x_periph.c
+++ b/hw/mcu/dialog/da1469x/src/da1469x_periph.c
@@ -27,7 +27,11 @@
 
 #if MYNEWT_VAL(UART_0) || MYNEWT_VAL(UART_1) || MYNEWT_VAL(UART_2)
 #include "uart/uart.h"
+#if MYNEWT_VAL(HAL_UART)
 #include "uart_hal/uart_hal.h"
+#else
+#include "uart_da1469x/uart_da1469x.h"
+#endif
 #endif
 #if MYNEWT_VAL(BUS_DRIVER_PRESENT)
 #include "bus/bus.h"
@@ -89,7 +93,11 @@ static struct crypto_dev os_bsp_crypto;
 #endif
 
 #if MYNEWT_VAL(UART_0)
+#if MYNEWT_VAL(UART_HAL)
 static struct uart_dev os_bsp_uart0;
+#else
+static struct da1469x_uart_dev os_bsp_uart0;
+#endif
 static const struct da1469x_uart_cfg os_bsp_uart0_cfg = {
     .pin_tx = MYNEWT_VAL(UART_0_PIN_TX),
     .pin_rx = MYNEWT_VAL(UART_0_PIN_RX),
@@ -99,7 +107,11 @@ static const struct da1469x_uart_cfg os_bsp_uart0_cfg = {
 };
 #endif
 #if MYNEWT_VAL(UART_1)
+#if MYNEWT_VAL(UART_HAL)
 static struct uart_dev os_bsp_uart1;
+#else
+static struct da1469x_uart_dev os_bsp_uart1;
+#endif
 static const struct da1469x_uart_cfg os_bsp_uart1_cfg = {
     .pin_tx = MYNEWT_VAL(UART_1_PIN_TX),
     .pin_rx = MYNEWT_VAL(UART_1_PIN_RX),
@@ -109,7 +121,11 @@ static const struct da1469x_uart_cfg os_bsp_uart1_cfg = {
 };
 #endif
 #if MYNEWT_VAL(UART_2)
+#if MYNEWT_VAL(UART_HAL)
 static struct uart_dev os_bsp_uart2;
+#else
+static struct da1469x_uart_dev os_bsp_uart2;
+#endif
 static const struct da1469x_uart_cfg os_bsp_uart2_cfg = {
     .pin_tx = MYNEWT_VAL(UART_2_PIN_TX),
     .pin_rx = MYNEWT_VAL(UART_2_PIN_RX),
@@ -334,6 +350,20 @@ da1469x_periph_create_adc(void)
 #endif
 }
 
+static int
+da1469x_uart_create(struct da1469x_uart_dev *dev, const char *name, uint8_t priority,
+                    const struct da1469x_uart_cfg *cfg)
+{
+#if MYNEWT_VAL(HAL_UART)
+    return os_dev_create(&dev->ud_dev, "uart0",
+                         OS_DEV_INIT_PRIMARY, priority, uart_hal_init,
+                         (void *)&os_bsp_uart0_cfg);
+#else
+    (void)priority;
+    return da1469x_uart_dev_create(dev, name, priority, cfg);
+#endif
+}
+
 static void
 da1469x_periph_create_uart(void)
 {
@@ -342,21 +372,15 @@ da1469x_periph_create_uart(void)
     (void)rc;
 
 #if MYNEWT_VAL(UART_0)
-    rc = os_dev_create(&os_bsp_uart0.ud_dev, "uart0",
-                       OS_DEV_INIT_PRIMARY, 0, uart_hal_init,
-                       (void *)&os_bsp_uart0_cfg);
+    rc = da1469x_uart_create(&os_bsp_uart0, "uart0", 0, &os_bsp_uart0_cfg);
     assert(rc == 0);
 #endif
 #if MYNEWT_VAL(UART_1)
-    rc = os_dev_create(&os_bsp_uart1.ud_dev, "uart1",
-                       OS_DEV_INIT_PRIMARY, 1, uart_hal_init,
-                       (void *)&os_bsp_uart1_cfg);
+    rc = da1469x_uart_create(&os_bsp_uart1, "uart1", 1, &os_bsp_uart1_cfg);
     assert(rc == 0);
 #endif
 #if MYNEWT_VAL(UART_2)
-    rc = os_dev_create(&os_bsp_uart1.ud_dev, "uart2",
-                       OS_DEV_INIT_PRIMARY, 2, uart_hal_init,
-                       (void *)&os_bsp_uart2_cfg);
+    rc = da1469x_uart_create(&os_bsp_uart2, "uart2", 2, &os_bsp_uart2_cfg);
     assert(rc == 0);
 #endif
 }
diff --git a/hw/mcu/dialog/da1469x/syscfg.yml b/hw/mcu/dialog/da1469x/syscfg.yml
index 6bfb1a7..aff0113 100644
--- a/hw/mcu/dialog/da1469x/syscfg.yml
+++ b/hw/mcu/dialog/da1469x/syscfg.yml
@@ -336,6 +336,10 @@ syscfg.defs:
         description: 'SS pin for SPI_1_SLAVE'
         value: ''
 
+    HAL_UART:
+        description: 'Use hal_uart driver instead of da1469x_uart.'
+        value: 0
+
     UART_0:
         description: Enable DA1469x UART 0 (UART peripheral)
         value: 1