arch/riscv/esp32c3: Add the USB-Serial Driver.

Signed-off-by: Abdelatif Guettouche <abdelatif.guettouche@espressif.com>
This commit is contained in:
Abdelatif Guettouche 2021-10-19 15:15:45 +02:00 committed by Alan Carvalho de Assis
parent 17cf3edf46
commit ebd94961c7
8 changed files with 578 additions and 11 deletions

View File

@ -229,6 +229,12 @@ config ESP32C3_UART1
select UART1_SERIALDRIVER
select ARCH_HAVE_SERIAL_TERMIOS
config ESP32C3_USBSERIAL
bool "USB-Serial Driver"
default n
select OTHER_UART_SERIALDRIVER
select ARCH_HAVE_SERIAL_TERMIOS
config ESP32C3_I2C0
bool "I2C 0"
default n

View File

@ -64,6 +64,10 @@ ifeq ($(CONFIG_ESP32C3_UART),y)
CHIP_CSRCS += esp32c3_serial.c
endif
ifeq ($(CONFIG_ESP32C3_USBSERIAL),y)
CHIP_CSRCS += esp32c3_usbserial.c
endif
ifeq ($(CONFIG_ESP32C3_RNG),y)
CHIP_CSRCS += esp32c3_rng.c
endif

View File

@ -49,15 +49,23 @@
*/
#undef HAVE_SERIAL_CONSOLE
#undef CONSOLE_UART
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_ESP32C3_UART0)
# undef CONFIG_UART1_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
# define CONSOLE_UART 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_ESP32C3_UART1)
# undef CONFIG_UART0_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
# define CONSOLE_UART 1
#else
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
#endif
#ifdef CONFIG_ESP32C3_USBSERIAL
# define HAVE_SERIAL_CONSOLE 1
# define HAVE_UART_DEVICE 1
#endif
#endif /* __ARCH_RISCV_SRC_ESP32C3_ESP32C3_CONFIG_H */

View File

@ -45,6 +45,7 @@
#include "esp32c3_clockconfig.h"
#include "esp32c3_config.h"
#include "esp32c3_gpio.h"
#include "esp32c3_usbserial.h"
#include "esp32c3_lowputc.h"
@ -800,7 +801,7 @@ void esp32c3_lowputc_restore_pins(const struct esp32c3_uart_s *priv)
void riscv_lowputc(char ch)
{
#ifdef HAVE_SERIAL_CONSOLE
#ifdef CONSOLE_UART
# if defined(CONFIG_UART0_SERIAL_CONSOLE)
struct esp32c3_uart_s *priv = &g_uart0_config;
@ -816,7 +817,9 @@ void riscv_lowputc(char ch)
esp32c3_lowputc_send_byte(priv, ch);
#endif /* HAVE_CONSOLE */
#elif defined (CONFIG_ESP32C3_USBSERIAL)
esp32c3_usbserial_write(ch);
#endif /* CONSOLE_UART */
}
/****************************************************************************

View File

@ -52,6 +52,10 @@
#include "esp32c3_irq.h"
#include "esp32c3_lowputc.h"
#ifdef CONFIG_ESP32C3_USBSERIAL
# include "esp32c3_usbserial.h"
#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -72,7 +76,7 @@
* the console and the corresponding peripheral was also selected.
*/
#ifdef HAVE_SERIAL_CONSOLE
#ifdef CONSOLE_UART
# if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart0_dev /* UART0 is console */
# define TTYS0_DEV g_uart0_dev /* UART0 is ttyS0 */
@ -82,7 +86,7 @@
# define TTYS0_DEV g_uart1_dev /* UART1 is ttyS0 */
# define UART1_ASSIGNED 1
# endif /* CONFIG_UART0_SERIAL_CONSOLE */
#else /* No console */
#else /* No UART console */
# undef CONSOLE_DEV
# if defined(CONFIG_ESP32C3_UART0)
# define TTYS0_DEV g_uart0_dev /* UART0 is ttyS0 */
@ -91,7 +95,12 @@
# define TTYS0_DEV g_uart1_dev /* UART1 is ttyS0 */
# define UART1_ASSIGNED 1
# endif
#endif /* HAVE_SERIAL_CONSOLE */
#endif /* CONSOLE_UART */
#ifdef CONFIG_ESP32C3_USBSERIAL
# define CONSOLE_DEV g_uart_usbserial
# define TTYACM0_DEV g_uart_usbserial
#endif
/* Pick ttys1 */
@ -109,6 +118,8 @@
* Private Function Prototypes
****************************************************************************/
#ifdef CONFIG_ESP32C3_UART
/* Serial driver methods */
static int esp32c3_setup(struct uart_dev_s *dev);
@ -127,11 +138,14 @@ static int esp32c3_ioctl(struct file *filep, int cmd, unsigned long arg);
static bool esp32c3_rxflowcontrol(struct uart_dev_s *dev,
unsigned int nbuffered, bool upper);
#endif
#endif
/****************************************************************************
* Private Data
****************************************************************************/
#ifdef CONFIG_ESP32C3_UART
/* Operations */
static struct uart_ops_s g_uart_ops =
@ -219,10 +233,14 @@ static uart_dev_t g_uart1_dev =
#endif
#endif /* CONFIG_ESP32C3_UART */
/****************************************************************************
* Private Functions
****************************************************************************/
#ifdef CONFIG_ESP32C3_UART
/****************************************************************************
* Name: uart_interrupt
*
@ -992,6 +1010,7 @@ static bool esp32c3_rxflowcontrol(struct uart_dev_s *dev,
return ret;
}
#endif
#endif /* CONFIG_ESP32C3_UART */
/****************************************************************************
* Public Functions
@ -1019,7 +1038,10 @@ void riscv_earlyserialinit(void)
/* Disable all UARTS interrupts */
#ifdef TTYS0_DEV
esp32c3_lowputc_disable_all_uart_int(TTYS0_DEV.priv, NULL);
#endif
#ifdef TTYS1_DEV
esp32c3_lowputc_disable_all_uart_int(TTYS1_DEV.priv, NULL);
#endif
@ -1029,7 +1051,7 @@ void riscv_earlyserialinit(void)
* open.
*/
#ifdef HAVE_SERIAL_CONSOLE
#ifdef CONSOLE_UART
esp32c3_setup(&CONSOLE_DEV);
#endif
}
@ -1051,13 +1073,17 @@ void riscv_serialinit(void)
uart_register("/dev/console", &CONSOLE_DEV);
#endif
/* At least one UART char driver will logically be registered */
#ifdef TTYS0_DEV
uart_register("/dev/ttyS0", &TTYS0_DEV);
#endif
#ifdef TTYS1_DEV
#ifdef TTYS1_DEV
uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif
#ifdef CONFIG_ESP32C3_USBSERIAL
uart_register("/dev/ttyACM0", &TTYACM0_DEV);
#endif
}
/****************************************************************************
@ -1070,10 +1096,11 @@ void riscv_serialinit(void)
int up_putc(int ch)
{
#ifdef HAVE_SERIAL_CONSOLE
#ifdef CONSOLE_UART
uint32_t int_status;
esp32c3_lowputc_disable_all_uart_int(CONSOLE_DEV.priv, &int_status);
#endif
/* Check for LF */
@ -1085,6 +1112,8 @@ int up_putc(int ch)
}
riscv_lowputc(ch);
#ifdef CONSOLE_UART
esp32c3_lowputc_restore_all_uart_int(CONSOLE_DEV.priv, &int_status);
#endif
return ch;
@ -1104,10 +1133,11 @@ int up_putc(int ch)
int up_putc(int ch)
{
#ifdef HAVE_SERIAL_CONSOLE
#ifdef CONSOLE_UART
uint32_t int_status;
esp32c3_lowputc_disable_all_uart_int(CONSOLE_DEV.priv, &int_status);
#endif
/* Check for LF */
@ -1119,6 +1149,8 @@ int up_putc(int ch)
}
riscv_lowputc(ch);
#ifdef CONSOLE_UART
esp32c3_lowputc_restore_all_uart_int(CONSOLE_DEV.priv, &int_status);
#endif
return ch;

View File

@ -0,0 +1,462 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/esp32c3_usbserial.c
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <assert.h>
#include <debug.h>
#ifdef CONFIG_SERIAL_TERMIOS
# include <termios.h>
#endif
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <nuttx/kmalloc.h>
#include <nuttx/serial/serial.h>
#include <arch/irq.h>
#include "riscv_arch.h"
#include "hardware/esp32c3_soc.h"
#include "hardware/esp32c3_system.h"
#include "hardware/esp32c3_usb_serial_jtag.h"
#include "esp32c3_config.h"
#include "esp32c3_irq.h"
/****************************************************************************
* Pre-processor Macros
****************************************************************************/
/* The hardware buffer has a fixed size of 64 bytes */
#define ESP32C3_USBCDC_BUFFERSIZE 64
/****************************************************************************
* Private Types
****************************************************************************/
struct esp32c3_priv_s
{
const uint8_t periph; /* peripheral ID */
const uint8_t irq; /* IRQ number assigned to the peripheral */
int cpuint; /* CPU interrupt assigned */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int esp32c3_interrupt(int irq, void *context, void *arg);
/* Serial driver methods */
static int esp32c3_setup(struct uart_dev_s *dev);
static void esp32c3_shutdown(struct uart_dev_s *dev);
static int esp32c3_attach(struct uart_dev_s *dev);
static void esp32c3_detach(struct uart_dev_s *dev);
static void esp32c3_txint(struct uart_dev_s *dev, bool enable);
static void esp32c3_rxint(struct uart_dev_s *dev, bool enable);
static bool esp32c3_rxavailable(struct uart_dev_s *dev);
static bool esp32c3_txready(struct uart_dev_s *dev);
static void esp32c3_send(struct uart_dev_s *dev, int ch);
static int esp32c3_receive(struct uart_dev_s *dev, unsigned int *status);
static int esp32c3_ioctl(struct file *filep, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static char g_rxbuffer[ESP32C3_USBCDC_BUFFERSIZE];
static char g_txbuffer[ESP32C3_USBCDC_BUFFERSIZE];
static struct esp32c3_priv_s g_usbserial_priv =
{
.periph = ESP32C3_PERIPH_USB,
.irq = ESP32C3_IRQ_USB,
};
static struct uart_ops_s g_uart_ops =
{
.setup = esp32c3_setup,
.shutdown = esp32c3_shutdown,
.attach = esp32c3_attach,
.detach = esp32c3_detach,
.txint = esp32c3_txint,
.rxint = esp32c3_rxint,
.rxavailable = esp32c3_rxavailable,
.txready = esp32c3_txready,
.txempty = NULL,
.send = esp32c3_send,
.receive = esp32c3_receive,
.ioctl = esp32c3_ioctl,
};
/****************************************************************************
* Public Data
****************************************************************************/
uart_dev_t g_uart_usbserial =
{
.isconsole = true,
.recv =
{
.size = ESP32C3_USBCDC_BUFFERSIZE,
.buffer = g_rxbuffer,
},
.xmit =
{
.size = ESP32C3_USBCDC_BUFFERSIZE,
.buffer = g_txbuffer,
},
.ops = &g_uart_ops,
.priv = &g_usbserial_priv,
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: esp32c3_interrupt
*
* Description:
* This is the common UART interrupt handler. It will be invoked
* when an interrupt received on the device. It should call
* uart_transmitchars or uart_receivechar to perform the appropriate data
* transfers.
*
****************************************************************************/
static int esp32c3_interrupt(int irq, void *context, void *arg)
{
struct uart_dev_s *dev = (struct uart_dev_s *)arg;
uint32_t regval;
regval = getreg32(USB_SERIAL_JTAG_INT_ST_REG);
/* Send buffer has room and can accept new data. */
if (regval & USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ST)
{
putreg32(USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_CLR,
USB_SERIAL_JTAG_INT_CLR_REG);
uart_xmitchars(dev);
}
/* Data from the host are available to read. */
if (regval & USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ST)
{
putreg32(USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_CLR,
USB_SERIAL_JTAG_INT_CLR_REG);
uart_recvchars(dev);
}
return OK;
}
/****************************************************************************
* Name: esp32c3_setup
*
* Description:
* This method is called the first time that the serial port is opened.
*
****************************************************************************/
static int esp32c3_setup(struct uart_dev_s *dev)
{
return OK;
}
/****************************************************************************
* Name: esp32c3_shutdown
*
* Description:
* This method is called when the serial port is closed.
*
****************************************************************************/
static void esp32c3_shutdown(struct uart_dev_s *dev)
{
}
/****************************************************************************
* Name: esp32c3_txint
*
* Description:
* Call to enable or disable TX interrupts
*
****************************************************************************/
static void esp32c3_txint(struct uart_dev_s *dev, bool enable)
{
if (enable)
{
modifyreg32(USB_SERIAL_JTAG_INT_ENA_REG, 0,
USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ENA);
}
else
{
modifyreg32(USB_SERIAL_JTAG_INT_ENA_REG,
USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ENA, 0);
}
}
/****************************************************************************
* Name: esp32c3_rxint
*
* Description:
* Call to enable or disable RXRDY interrupts
*
****************************************************************************/
static void esp32c3_rxint(struct uart_dev_s *dev, bool enable)
{
if (enable)
{
modifyreg32(USB_SERIAL_JTAG_INT_ENA_REG, 0,
USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ENA);
}
else
{
modifyreg32(USB_SERIAL_JTAG_INT_ENA_REG,
USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ENA, 0);
}
}
/****************************************************************************
* Name: esp32c3_attach
*
* Description:
* Configure the UART to operation in interrupt driven mode. This method
* is called when the serial port is opened. Normally, this is just after
* the the setup() method is called, however, the serial console may
* operate in a non-interrupt driven mode during the boot phase.
*
* RX and TX interrupts are not enabled by the attach method (unless
* the hardware supports multiple levels of interrupt enabling). The RX
* and TX interrupts are not enabled until the txint() and rxint() methods
* are called.
*
****************************************************************************/
static int esp32c3_attach(struct uart_dev_s *dev)
{
struct esp32c3_priv_s *priv = dev->priv;
int ret;
DEBUGASSERT(priv->cpuint == -ENOMEM);
/* Try to attach the IRQ to a CPU int */
priv->cpuint = esp32c3_request_irq(priv->periph,
ESP32C3_INT_PRIO_DEF,
ESP32C3_INT_LEVEL);
if (priv->cpuint < 0)
{
return priv->cpuint;
}
/* Attach and enable the IRQ */
ret = irq_attach(priv->irq, esp32c3_interrupt, dev);
if (ret == OK)
{
up_enable_irq(priv->cpuint);
}
else
{
up_disable_irq(priv->cpuint);
}
return ret;
}
/****************************************************************************
* Name: esp32c3_detach
*
* Description:
* Detach UART interrupts. This method is called when the serial port is
* closed normally just before the shutdown method is called. The
* exception is the serial console which is never shutdown.
*
****************************************************************************/
static void esp32c3_detach(struct uart_dev_s *dev)
{
struct esp32c3_priv_s *priv = dev->priv;
DEBUGASSERT(priv->cpuint != -ENOMEM);
up_disable_irq(priv->cpuint);
irq_detach(priv->irq);
esp32c3_free_cpuint(priv->periph);
priv->cpuint = -ENOMEM;
}
/****************************************************************************
* Name: esp32c3_rxavailable
*
* Description:
* Return true if the receive holding register is not empty
*
****************************************************************************/
static bool esp32c3_rxavailable(struct uart_dev_s *dev)
{
uint32_t regval;
regval = getreg32(USB_SERIAL_JTAG_EP1_CONF_REG);
return regval & USB_SERIAL_JTAG_SERIAL_OUT_EP_DATA_AVAIL;
}
/****************************************************************************
* Name: esp32c3_txready
*
* Description:
* Return true if the transmit holding register is empty (TXRDY)
*
****************************************************************************/
static bool esp32c3_txready(struct uart_dev_s *dev)
{
uint32_t regval;
regval = getreg32(USB_SERIAL_JTAG_EP1_CONF_REG);
return regval & USB_SERIAL_JTAG_SERIAL_IN_EP_DATA_FREE;
}
/****************************************************************************
* Name: esp32c3_send
*
* Description:
* This method will send one byte on the UART.
*
****************************************************************************/
static void esp32c3_send(struct uart_dev_s *dev, int ch)
{
/* Write the character to the buffer. */
putreg32(ch, USB_SERIAL_JTAG_EP1_REG);
/* Flush the character out. */
putreg32(1, USB_SERIAL_JTAG_EP1_CONF_REG);
}
/****************************************************************************
* Name: esp32_receive
*
* Description:
* Called (usually) from the interrupt level to receive one character.
*
****************************************************************************/
static int esp32c3_receive(struct uart_dev_s *dev, unsigned int *status)
{
*status = 0;
return getreg32(USB_SERIAL_JTAG_EP1_REG) & USB_SERIAL_JTAG_RDWR_BYTE;
}
/****************************************************************************
* Name: esp32c3_ioctl
*
* Description:
* All ioctl calls will be routed through this method
*
****************************************************************************/
static int esp32c3_ioctl(struct file *filep, int cmd, unsigned long arg)
{
#if defined(CONFIG_SERIAL_TERMIOS)
struct inode *inode = filep->f_inode;
struct uart_dev_s *dev = inode->i_private;
#endif
int ret = OK;
switch (cmd)
{
#ifdef CONFIG_SERIAL_TERMIOS
case TCGETS:
{
struct termios *termiosp = (struct termios *)arg;
if (!termiosp)
{
ret = -EINVAL;
}
else
{
/* The USB Serial Console has fixed configuration of:
* 9600 baudrate, no parity, 8 bits, 1 stopbit.
*/
termiosp->c_cflag = CS8;
cfsetispeed(termiosp, 9600);
}
}
break;
case TCSETS:
ret = -ENOTTY;
break;
#endif /* CONFIG_SERIAL_TERMIOS */
default:
ret = -ENOTTY;
break;
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32c3_usbserial_write
*
* Description:
* Write one character through the USB serial. Used mainly for early
* debugging.
*
****************************************************************************/
void esp32c3_usbserial_write(char ch)
{
while (!esp32c3_txready(&g_uart_usbserial));
esp32c3_send(&g_uart_usbserial, ch);
}

View File

@ -0,0 +1,51 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/esp32c3_usbserial.h
*
* 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 __ARCH_RISCV_SRC_ESP32C3_ESP32C3_USBSERIAL_H
#define __ARCH_RISCV_SRC_ESP32C3_ESP32C3_USBSERIAL_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/serial/serial.h>
/****************************************************************************
* Public Data
****************************************************************************/
extern uart_dev_t g_uart_usbserial;
/****************************************************************************
* Public Functions Prototypes
****************************************************************************/
/****************************************************************************
* Name: esp32c3_usbserial_write
*
* Description:
* Write one character through the USB serial. Used mainly for early
* debugging.
*
****************************************************************************/
void esp32c3_usbserial_write(char ch);
#endif /* __ARCH_RISCV_SRC_ESP32C3_ESP32C3_USBSERIAL_H */

View File

@ -73,6 +73,7 @@
#define DR_REG_TWAI_BASE 0x6002B000
#define DR_REG_I2S0_BASE 0x6002D000
#define DR_REG_APB_SARADC_BASE 0x60040000
#define DR_REG_USB_SERIAL_JTAG_BASE 0x60043000
#define DR_REG_AES_XTS_BASE 0x600CC000
/* Registers Operation */