From 18be454011eb29652b9e740f33b5b5677d50e7b7 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Fri, 5 Mar 2021 01:38:49 +0900 Subject: [PATCH 01/20] added board files --- hw/bsp/gr_citrus/board.mk | 54 +++++++++ hw/bsp/gr_citrus/gr_citrus.c | 217 ++++++++++++++++++++++++++++++++++ hw/bsp/gr_citrus/hwinit.c | 31 +++++ hw/bsp/gr_citrus/r5f5631fd.ld | 127 ++++++++++++++++++++ 4 files changed, 429 insertions(+) create mode 100644 hw/bsp/gr_citrus/board.mk create mode 100644 hw/bsp/gr_citrus/gr_citrus.c create mode 100644 hw/bsp/gr_citrus/hwinit.c create mode 100644 hw/bsp/gr_citrus/r5f5631fd.ld diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk new file mode 100644 index 00000000..8675d853 --- /dev/null +++ b/hw/bsp/gr_citrus/board.mk @@ -0,0 +1,54 @@ +CFLAGS += \ + -nostartfiles \ + -nostdinc \ + -ffunction-sections \ + -fdata-sections \ + -mcpu=rx610 \ + -misa=v1 \ + -mlittle-endian-data \ + -DCFG_TUSB_MCU=OPT_MCU_RX63X + +# Cross Compiler for RX +CROSS_COMPILE = rx-elf- + +ifeq ($(CMDEXE),1) +OPTLIBINC="$(shell for /F "usebackq delims=" %%i in (`where rx-elf-gcc`) do echo %%~dpi..\rx-elf\optlibinc)" +else +OPTLIBINC=$(shell dirname `which rx-elf-gcc`)../rx-elf/optlibinc +endif + +# mcu driver cause following warnings +CFLAGS += -isystem $(OPTLIBINC) + +LIBS += -loptm -loptc + +MCU_DIR = hw/mcu/renesas/rx63n + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/r5f5631fd.ld + +SRC_C += \ + $(MCU_DIR)/vects.c + +INC += \ + $(TOP)/hw/bsp/$(BOARD) \ + $(TOP)/$(MCU_DIR) + +SRC_S += $(MCU_DIR)/start.S + +# For TinyUSB port source +VENDOR = renesas +CHIP_FAMILY = usba + +# For freeRTOS port source +FREERTOS_PORT = RX600 + +# For flash-jlink target +JLINK_DEVICE = R5F5631F +JLINK_IF = JTAG + +# For flash-pyocd target +PYOCD_TARGET = + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/gr_citrus/gr_citrus.c b/hw/bsp/gr_citrus/gr_citrus.c new file mode 100644 index 00000000..3fa568cc --- /dev/null +++ b/hw/bsp/gr_citrus/gr_citrus.c @@ -0,0 +1,217 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, Koji Kitayama + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" +#include "iodefine.h" +#include "interrupt_handlers.h" + +#define IRQ_PRIORITY_CMT0 5 +#define IRQ_PRIORITY_USBI0 5 +#define IRQ_PRIORITY_SCI0 5 + +#define SYSTEM_PRCR_PRC1 (1<<1) +#define SYSTEM_PRCR_PRKEY (0xA5u<<8) + +#define CMT_PCLK 48000000 +#define CMT_CMCR_CKS_DIV_128 2 +#define CMT_CMCR_CMIE (1<<6) +#define MPC_PFS_ISEL (1<<6) + +#define SCI_PCLK 48000000 +#define SCI_SSR_FER (1<<4) +#define SCI_SSR_ORER (1<<5) + +#define SCI_SCR_TEIE (1u<<2) +#define SCI_SCR_RE (1u<<4) +#define SCI_SCR_TE (1u<<5) +#define SCI_SCR_RIE (1u<<6) +#define SCI_SCR_TIE (1u<<7) + +//--------------------------------------------------------------------+ +// SCI0 handling +//--------------------------------------------------------------------+ +typedef struct { + uint8_t *buf; + uint32_t cnt; +} sci_buf_t; +static volatile sci_buf_t sci0_buf[2]; + +void INT_Excep_SCI0_TXI0(void) +{ + uint8_t *buf = sci0_buf[0].buf; + uint32_t cnt = sci0_buf[0].cnt; + + if (!buf || !cnt) { + SCI0.SCR.BYTE &= ~(SCI_SCR_TEIE | SCI_SCR_TE | SCI_SCR_TIE); + return; + } + SCI0.TDR = *buf; + if (--cnt) { + ++buf; + } else { + buf = NULL; + SCI0.SCR.BIT.TIE = 0; + SCI0.SCR.BIT.TEIE = 1; + } + sci0_buf[0].buf = buf; + sci0_buf[0].cnt = cnt; +} + +void INT_Excep_SCI0_TEI0(void) +{ + SCI0.SCR.BYTE &= ~(SCI_SCR_TEIE | SCI_SCR_TE | SCI_SCR_TIE); +} + +void INT_Excep_SCI0_RXI0(void) +{ + uint8_t *buf = sci0_buf[1].buf; + uint32_t cnt = sci0_buf[1].cnt; + + if (!buf || !cnt || + (SCI0.SSR.BYTE & (SCI_SSR_FER | SCI_SSR_ORER))) { + sci0_buf[1].buf = NULL; + SCI0.SSR.BYTE = 0; + SCI0.SCR.BYTE &= ~(SCI_SCR_RE | SCI_SCR_RIE); + return; + } + *buf = SCI0.RDR; + if (--cnt) { + ++buf; + } else { + buf = NULL; + SCI0.SCR.BYTE &= ~(SCI_SCR_RE | SCI_SCR_RIE); + } + sci0_buf[1].buf = buf; + sci0_buf[1].cnt = cnt; +} + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void INT_Excep_USB0_USBI0(void) +{ + tud_int_handler(0); +} + +void board_init(void) +{ +#if CFG_TUSB_OS == OPT_OS_NONE + /* Enable CMT0 */ + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY | SYSTEM_PRCR_PRC1; + MSTP(CMT0) = 0; + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY; + /* Setup 1ms tick timer */ + CMT0.CMCNT = 0; + CMT0.CMCOR = CMT_PCLK / 1000 / 128; + CMT0.CMCR.WORD = CMT_CMCR_CMIE | CMT_CMCR_CKS_DIV_128; + IR(CMT0, CMI0) = 0; + IPR(CMT0, CMI0) = IRQ_PRIORITY_CMT0; + IEN(CMT0, CMI0) = 1; + CMT.CMSTR0.BIT.STR0 = 1; +#endif + + /* Unlock MPC registers */ + MPC.PWPR.BIT.B0WI = 0; + MPC.PWPR.BIT.PFSWE = 1; + /* LED PA0 */ + PORTA.PMR.BIT.B0 = 0U; + PORTA.PODR.BIT.B0 = 0U; + PORTA.PDR.BIT.B0 = 1U; + /* UART TXD0 => P20, RXD0 => P21 */ + PORT2.PMR.BIT.B0 = 1U; + PORT2.PCR.BIT.B0 = 1U; + MPC.P20PFS.BYTE = 0b01010; + PORT2.PMR.BIT.B1 = 1U; + MPC.P21PFS.BYTE = 0b01010; + /* USB VBUS -> P16, RXD0 => P21, TXD0 => P20 */ + PORT1.PMR.BIT.B6 = 1U; + MPC.P16PFS.BYTE = MPC_PFS_ISEL | 0b10001; + /* Lock MPC registers */ + MPC.PWPR.BIT.PFSWE = 0; + MPC.PWPR.BIT.B0WI = 1; + + IPR(USB0, USBI0) = IRQ_PRIORITY_USBI0; + + /* Enable SCI0 */ + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY | SYSTEM_PRCR_PRC1; + MSTP(SCI0) = 0; + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY; + SCI0.BRR = (SCI_PCLK / (32 * 115200)) - 1; + IR(SCI0, RXI0) = 0; + IR(SCI0, TXI0) = 0; + IR(SCI0, TEI0) = 0; + IPR(SCI0, RXI0) = IRQ_PRIORITY_SCI0; + IPR(SCI0, TXI0) = IRQ_PRIORITY_SCI0; + IPR(SCI0, TEI0) = IRQ_PRIORITY_SCI0; + IEN(SCI0, RXI0) = 1; + IEN(SCI0, TXI0) = 1; + IEN(SCI0, TEI0) = 1; +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + PORTA.PODR.BIT.B0 = state ? 1 : 0; +} + +uint32_t board_button_read(void) +{ + return 0; +} + +int board_uart_read(uint8_t* buf, int len) +{ + sci0_buf[1].buf = buf; + sci0_buf[1].cnt = len; + SCI0.SCR.BYTE |= SCI_SCR_RE | SCI_SCR_RIE; + while (SCI0.SCR.BIT.RE) ; + return len - sci0_buf[1].cnt; +} + +int board_uart_write(void const *buf, int len) +{ + sci0_buf[0].buf = (uint8_t*)buf; + sci0_buf[0].cnt = len; + SCI0.SCR.BYTE |= SCI_SCR_TE | SCI_SCR_TIE; + while (SCI0.SCR.BIT.TE) ; + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void INT_Excep_CMT0_CMI0(void) +{ + ++system_ticks; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif diff --git a/hw/bsp/gr_citrus/hwinit.c b/hw/bsp/gr_citrus/hwinit.c new file mode 100644 index 00000000..8245d774 --- /dev/null +++ b/hw/bsp/gr_citrus/hwinit.c @@ -0,0 +1,31 @@ +/************************************************************************/ +/* File Version: V1.00 */ +/* Date Generated: 08/07/2013 */ +/************************************************************************/ + +#include "iodefine.h" +#ifdef __cplusplus +extern "C" { +#endif +extern void HardwareSetup(void); +#ifdef __cplusplus +} +#endif + +void HardwareSetup(void) +{ + SYSTEM.PRCR.WORD = 0xA503u; + SYSTEM.SOSCCR.BYTE = 0x01u; + SYSTEM.MOSCWTCR.BYTE = 0x0Du; + SYSTEM.PLLWTCR.BYTE = 0x0Eu; + SYSTEM.PLLCR.WORD = 0x0F00u; + SYSTEM.MOSCCR.BYTE = 0x00u; + SYSTEM.PLLCR2.BYTE = 0x00u; + for (unsigned i = 0; i < 2075u; ++i) __asm("nop"); + SYSTEM.SCKCR.LONG = 0x21021211u; + SYSTEM.SCKCR2.WORD = 0x0033u; + SYSTEM.SCKCR3.WORD = 0x0400u; + SYSTEM.SYSCR0.WORD = 0x5A01; + SYSTEM.MSTPCRB.BIT.MSTPB15 = 0; + SYSTEM.PRCR.WORD = 0xA500u; +} diff --git a/hw/bsp/gr_citrus/r5f5631fd.ld b/hw/bsp/gr_citrus/r5f5631fd.ld new file mode 100644 index 00000000..166a9e7c --- /dev/null +++ b/hw/bsp/gr_citrus/r5f5631fd.ld @@ -0,0 +1,127 @@ +__USTACK_SIZE = 0x00000200; +__ISTACK_SIZE = 0x00000100; + +MEMORY +{ + RAM : ORIGIN = 0x4, LENGTH = 0x3fffc + ROM : ORIGIN = 0xFFE00000, LENGTH = 0x200000 +} +SECTIONS +{ + .fvectors 0xFFFFFF80: AT(0xFFFFFF80) + { + KEEP(*(.fvectors)) + } > ROM + .text 0xFFE00000: AT(0xFFE00000) + { + *(.text) + *(.text.*) + *(P) + etext = .; + } > ROM + .rvectors ALIGN(4): + { + _rvectors_start = .; + KEEP(*(.rvectors)) + _rvectors_end = .; + } > ROM + .init : + { + KEEP(*(.init)) + __preinit_array_start = .; + KEEP(*(.preinit_array)) + __preinit_array_end = .; + __init_array_start = (. + 3) & ~ 3; + KEEP(*(.init_array)) + KEEP(*(SORT(.init_array.*))) + __init_array_end = .; + __fini_array_start = .; + KEEP(*(.fini_array)) + KEEP(*(SORT(.fini_array.*))) + __fini_array_end = .; + } > ROM + .fini : + { + KEEP(*(.fini)) + } > ROM + .got : + { + *(.got) + *(.got.plt) + } > ROM + .rodata : + { + *(.rodata) + *(.rodata.*) + *(C_1) + *(C_2) + *(C) + _erodata = .; + } > ROM + .eh_frame_hdr : + { + *(.eh_frame_hdr) + } > ROM + .eh_frame : + { + *(.eh_frame) + } > ROM + .jcr : + { + *(.jcr) + } > ROM + .tors : + { + __CTOR_LIST__ = .; + . = ALIGN(2); + ___ctors = .; + *(.ctors) + ___ctors_end = .; + __CTOR_END__ = .; + __DTOR_LIST__ = .; + ___dtors = .; + *(.dtors) + ___dtors_end = .; + __DTOR_END__ = .; + . = ALIGN(2); + _mdata = .; + } > ROM + .data : AT(_mdata) + { + _data = .; + *(.data) + *(.data.*) + *(D) + *(D_1) + *(D_2) + _edata = .; + } > RAM + .gcc_exc : + { + *(.gcc_exc) + } > RAM + .bss : + { + _bss = .; + *(.bss) + *(.bss.**) + *(COMMON) + *(B) + *(B_1) + *(B_2) + _ebss = .; + _end = .; + } > RAM + .ustack (COPY) : + { + . = ALIGN(8); + . = . + __USTACK_SIZE; + PROVIDE(_ustack = .); + } > RAM + .istack (COPY) : + { + . = ALIGN(8); + . = . + __ISTACK_SIZE; + PROVIDE(_istack = .); + } > RAM +} From 13735eb21de8d21a88871e69859f69db02af93c6 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 7 Mar 2021 14:53:21 +0900 Subject: [PATCH 02/20] added dcd for Renesas USBa --- src/portable/renesas/usba/dcd_usba.c | 755 +++++++++++++++++++++++++++ 1 file changed, 755 insertions(+) create mode 100644 src/portable/renesas/usba/dcd_usba.c diff --git a/src/portable/renesas/usba/dcd_usba.c b/src/portable/renesas/usba/dcd_usba.c new file mode 100644 index 00000000..b0fa1749 --- /dev/null +++ b/src/portable/renesas/usba/dcd_usba.c @@ -0,0 +1,755 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 Koji Kitayama + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "tusb_option.h" + +#if TUSB_OPT_DEVICE_ENABLED && ( CFG_TUSB_MCU == OPT_MCU_RX63X ) + +#include "device/dcd.h" +#include "iodefine.h" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ +#define SYSTEM_PRCR_PRC1 (1<<1) +#define SYSTEM_PRCR_PRKEY (0xA5u<<8) + +#define USB_FIFOSEL_TX ((uint16_t)(1u<<5)) +#define USB_FIFOSEL_MBW_8 ((uint16_t)(0u<<10)) +#define USB_FIFOSEL_MBW_16 ((uint16_t)(1u<<10)) +#define USB_IS0_CTSQ ((uint16_t)(7u)) +#define USB_IS0_DVSQ ((uint16_t)(7u<<4)) +#define USB_IS0_VALID ((uint16_t)(1u<<3)) +#define USB_IS0_BRDY ((uint16_t)(1u<<8)) +#define USB_IS0_NRDY ((uint16_t)(1u<<9)) +#define USB_IS0_BEMP ((uint16_t)(1u<<10)) +#define USB_IS0_CTRT ((uint16_t)(1u<<11)) +#define USB_IS0_DVST ((uint16_t)(1u<<12)) +#define USB_IS0_SOFR ((uint16_t)(1u<<13)) +#define USB_IS0_RESM ((uint16_t)(1u<<14)) +#define USB_IS0_VBINT ((uint16_t)(1u<<15)) +#define USB_IS1_SACK ((uint16_t)(1u<<4)) +#define USB_IS1_SIGN ((uint16_t)(1u<<5)) +#define USB_IS1_EOFERR ((uint16_t)(1u<<6)) +#define USB_IS1_ATTCH ((uint16_t)(1u<<11)) +#define USB_IS1_DTCH ((uint16_t)(1u<<12)) +#define USB_IS1_BCHG ((uint16_t)(1u<<14)) +#define USB_IS1_OVRCR ((uint16_t)(1u<<15)) + +#define USB_IS0_CTSQ_MSK (7u) +#define USB_IS0_CTSQ_SETUP (1u) +#define USB_IS0_DVSQ_DEF (1u<<4) +#define USB_IS0_DVSQ_ADDR (2u<<4) +#define USB_IS0_DVSQ_SUSP (4u<<4) + +#define USB_PIPECTR_PID_NAK (0u) +#define USB_PIPECTR_PID_BUF (1u) +#define USB_PIPECTR_PID_STALL (2u) +#define USB_PIPECTR_CCPL (1u<<2) +#define USB_PIPECTR_SQMON (1u<<6) +#define USB_PIPECTR_SQCLR (1u<<8) +#define USB_PIPECTR_ACLRM (1u<<9) +#define USB_PIPECTR_BSTS (1u<<15) + +#define USB_FIFOCTR_DTLN (0x1FF) +#define USB_FIFOCTR_FRDY (1u<<13) +#define USB_FIFOCTR_BCLR (1u<<14) +#define USB_FIFOCTR_BVAL (1u<<15) + +#define USB_PIPECFG_SHTNAK (1u<<7) +#define USB_PIPECFG_DBLB (1u<<9) +#define USB_PIPECFG_BULK (1u<<14) +#define USB_PIPECFG_ISO (3u<<14) +#define USB_PIPECFG_INT (2u<<14) + +#define FIFO_REQ_CLR (1u) +#define FIFO_COMPLETE (1u<<1) + +typedef struct { + union { + struct { + uint16_t : 8; + uint16_t TRCLR: 1; + uint16_t TRENB: 1; + uint16_t : 0; + }; + uint16_t TRE; + }; + uint16_t TRN; +} reg_pipetre_t; + +typedef union { + struct { + volatile uint16_t u8: 8; + volatile uint16_t : 0; + }; + volatile uint16_t u16; +} hw_fifo_t; + +typedef struct TU_ATTR_PACKED +{ + uintptr_t addr; + uint16_t length; + uint16_t remaining; + struct { + uint32_t ep : 8; + uint32_t data: 1; + uint32_t : 0; + }; +} pipe_state_t; + +typedef struct +{ + pipe_state_t pipe[9]; + uint8_t ep[2][16]; /* index for pipe number */ +} dcd_data_t; + +//--------------------------------------------------------------------+ +// INTERNAL OBJECT & FUNCTION DECLARATION +//--------------------------------------------------------------------+ +CFG_TUSB_MEM_SECTION static dcd_data_t _dcd; + +static uint32_t disable_interrupt(void) +{ + uint32_t pswi; + pswi = __builtin_rx_mvfc(0) & 0x010000; + __builtin_rx_clrpsw('I'); + return pswi; +} + +static void enable_interrupt(uint32_t pswi) +{ + __builtin_rx_mvtc(0, __builtin_rx_mvfc(0) | pswi); +} + +static unsigned find_pipe(unsigned xfer) +{ + switch (xfer) { + case TUSB_XFER_ISOCHRONOUS: + for (int i = 1; i <= 2; ++i) { + if (0 == _dcd.pipe[i].ep) return i; + } + break; + case TUSB_XFER_BULK: + for (int i = 3; i <= 5; ++i) { + if (0 == _dcd.pipe[i].ep) return i; + } + for (int i = 1; i <= 1; ++i) { + if (0 == _dcd.pipe[i].ep) return i; + } + break; + case TUSB_XFER_INTERRUPT: + for (int i = 6; i <= 9; ++i) { + if (0 == _dcd.pipe[i].ep) return i; + } + break; + default: + /* No support for control transfer */ + break; + } + return 0; +} + +static volatile uint16_t* get_pipectr(unsigned num) +{ + volatile uint16_t *ctr = NULL; + if (num) { + ctr = (volatile uint16_t*)&USB0.PIPE1CTR.WORD; + ctr += num - 1; + } else { + ctr = (volatile uint16_t*)&USB0.DCPCTR.WORD; + } + return ctr; +} + +static volatile reg_pipetre_t* get_pipetre(unsigned num) +{ + volatile reg_pipetre_t* tre = NULL; + if ((1 <= num) && (num <= 5)) { + tre = (volatile reg_pipetre_t*)&USB0.PIPE1TRE.WORD; + tre += num - 1; + } + return tre; +} + +static volatile uint16_t* ep_addr_to_pipectr(uint8_t rhport, unsigned ep_addr) +{ + (void)rhport; + volatile uint16_t *ctr = NULL; + const unsigned epn = ep_addr & 0xFu; + if (epn) { + const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned num = _dcd.ep[dir][epn]; + if (num) { + ctr = (volatile uint16_t*)&USB0.PIPE1CTR.WORD; + ctr += num - 1; + } + } else { + ctr = (volatile uint16_t*)&USB0.DCPCTR.WORD; + } + return ctr; +} + + +/* 1 less than 64 bytes were written + * 2 no bytes were written + * 0 64 bytes were written */ +static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) +{ + unsigned rem = pipe->remaining; + if (!rem) return 2; + unsigned len = (rem < mps) ? rem: mps; + + hw_fifo_t *reg = (hw_fifo_t*)fifo; + uintptr_t addr = pipe->addr + pipe->length - rem; + if (addr & 1u) { + /* addr is not 2-byte aligned */ + reg->u8 = *(const uint8_t *)addr; + ++addr; + --len; + } + while (len >= 2) { + reg->u16 = *(const uint16_t *)addr; + addr += 2; + len -= 2; + } + if (len) { + reg->u8 = *(const uint8_t *)addr; + ++addr; + } + if (rem < mps) return 1; + return 0; +} + +/* 1 if the number of bytes read is less than 64 bytes + * 0 otherwise */ +static int read_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, size_t len) +{ + unsigned rem = pipe->remaining; + if (!rem) return 2; + if (rem < len) len = rem; + pipe->remaining = rem - len; + + hw_fifo_t *reg = (hw_fifo_t*)fifo; + uintptr_t addr = pipe->addr; + while (len--) { + *(uint8_t *)addr = reg->u8; + ++addr; + } + pipe->addr = addr; + if (rem < mps) return 1; + return 0; +} + +static void process_setup_packet(uint8_t rhport) +{ + uint16_t setup_packet[4]; + if (0 == (USB0.INTSTS0.WORD & USB_IS0_VALID)) return; + USB0.CFIFOCTR.WORD = USB_FIFOCTR_BCLR; + setup_packet[0] = USB0.USBREQ.WORD; + setup_packet[1] = USB0.USBVAL; + setup_packet[2] = USB0.USBINDX; + setup_packet[3] = USB0.USBLENG; + USB0.INTSTS0.WORD = ~USB_IS0_VALID; + dcd_event_setup_received(rhport, (const uint8_t*)&setup_packet[0], true); + // TU_LOG1("S\r\n"); +} + +static void process_status_completion(uint8_t rhport) +{ + uint8_t ep_addr; + /* Check the data stage direction */ + if (USB0.CFIFOSEL.WORD & USB_FIFOSEL_TX) { + /* IN transfer. */ + ep_addr = tu_edpt_addr(0, TUSB_DIR_IN); + } else { + /* OUT transfer. */ + ep_addr = tu_edpt_addr(0, TUSB_DIR_OUT); + } + dcd_event_xfer_complete(rhport, ep_addr, 0, XFER_RESULT_SUCCESS, true); + // TU_LOG1("C\r\n"); +} + +static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) +{ + (void)rhport; + + pipe_state_t *pipe = &_dcd.pipe[0]; + /* set fifo direction */ + if (ep_addr) { /* IN */ + USB0.CFIFOSEL.WORD = USB_FIFOSEL_TX | USB_FIFOSEL_MBW_16; + while (!(USB0.CFIFOSEL.WORD & USB_FIFOSEL_TX)) ; + } else { /* OUT */ + USB0.CFIFOSEL.WORD = USB_FIFOSEL_MBW_8; + while (USB0.CFIFOSEL.WORD & USB_FIFOSEL_TX) ; + } + if (total_bytes) { + pipe->addr = (uintptr_t)buffer; + pipe->length = total_bytes; + pipe->remaining = total_bytes; + pipe->data = USB0.DCPCTR.BIT.SQMON; + if (ep_addr) { /* IN */ + TU_ASSERT(USB0.DCPCTR.BIT.BSTS && (USB0.USBREQ.WORD & 0x80)); + if (write_fifo(&USB0.CFIFO.WORD, pipe, 64)) { + USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; + } + } + USB0.DCPCTR.WORD = USB_PIPECTR_PID_BUF; + // TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); + } else { + /* ZLP */ + pipe->addr = 0; + pipe->length = 0; + pipe->remaining = 0; + pipe->data = USB0.DCPCTR.BIT.SQMON; + USB0.DCPCTR.WORD = USB_PIPECTR_CCPL | USB_PIPECTR_PID_BUF; + // TU_LOG1("Z %x\r\n", USB0.DCPCTR.WORD); + } + return true; +} + +static void process_edpt0_bemp(uint8_t rhport) +{ + pipe_state_t *pipe = &_dcd.pipe[0]; + unsigned data = pipe->data; + if (USB0.DCPCTR.BIT.SQMON == data) { + TU_LOG1("W %x\r\n", USB0.DCPCTR.WORD); + /* retry transfer */ + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); + if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; + return; + } + const unsigned rem = pipe->remaining; + if (rem > 64) { + pipe->remaining = rem - 64; + pipe->data = data ^ 1; + TU_LOG1("Y %d %x\r\n", rem - 64, USB0.DCPCTR.WORD); + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); + if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; + return; + } + pipe->addr = 0; + pipe->remaining = 0; + dcd_event_xfer_complete(rhport, tu_edpt_addr(0, TUSB_DIR_IN), + pipe->length, XFER_RESULT_SUCCESS, true); + // TU_LOG1("c\r\n"); +} + +static void process_edpt0_brdy(uint8_t rhport) +{ + size_t len = USB0.CFIFOCTR.BIT.DTLN; + int cplt = read_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, len); + if (cplt || (len < 64)) { + if (2 != cplt) { + USB0.CFIFOCTR.WORD = USB_FIFOCTR_BCLR; + } + dcd_event_xfer_complete(rhport, tu_edpt_addr(0, TUSB_DIR_OUT), + _dcd.pipe[0].length - _dcd.pipe[0].remaining, + XFER_RESULT_SUCCESS, true); + // TU_LOG1("c\r\n"); + } +} + +static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) +{ + (void)rhport; + + const unsigned epn = ep_addr & 0xFu; + const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned num = _dcd.ep[dir][epn]; + + TU_ASSERT(num); + + pipe_state_t *pipe = &_dcd.pipe[num]; + pipe->addr = (uintptr_t)buffer; + pipe->length = total_bytes; + pipe->remaining = total_bytes; + + USB0.PIPESEL.WORD = num; + const unsigned mps = USB0.PIPEMAXP.WORD; + if (dir) { /* IN */ + USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; + while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; + if (write_fifo(&USB0.D0FIFO.WORD, pipe, mps)) { + USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + } + USB0.D0FIFOSEL.WORD = 0; + } else { + volatile reg_pipetre_t *pt = get_pipetre(num); + if (pt) { + volatile uint16_t *ctr = get_pipectr(num); + if (*ctr & 0x3) *ctr = USB_PIPECTR_PID_NAK; + pt->TRE = 1u << 8; + pt->TRN = (total_bytes + mps - 1) / mps; + pt->TRENB = 1; + *ctr = USB_PIPECTR_PID_BUF; + } + } + TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); + return true; +} + +static void process_pipe_bemp(uint8_t rhport, unsigned num) +{ + pipe_state_t *pipe = &_dcd.pipe[num]; + const unsigned rem = pipe->remaining; + if (rem > 64) { + pipe->remaining = rem - 64; + TU_LOG1("Y %d\r\n", rem - 64); + USB0.PIPESEL.WORD = num; + const unsigned mps = USB0.PIPEMAXP.WORD; + USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; + while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; + int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + return; + } + pipe->addr = 0; + pipe->remaining = 0; + dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, + XFER_RESULT_SUCCESS, true); + // TU_LOG1("cE\r\n"); +} + +static void process_pipe_brdy(uint8_t rhport, unsigned num) +{ + pipe_state_t *pipe = &_dcd.pipe[num]; + USB0.PIPESEL.WORD = num; + const unsigned mps = USB0.PIPEMAXP.WORD; + USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_8; + while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; + unsigned ctr; + do { + ctr = USB0.D0FIFOCTR.WORD; + } while (!(ctr & USB_FIFOCTR_FRDY)); + const unsigned len = ctr & USB_FIFOCTR_DTLN; + TU_LOG1(">> %d %x %x\r\n", num, USB0.D0FIFOSEL.WORD, ctr); + int cplt = read_fifo(&USB0.D0FIFO.WORD, pipe, mps, len); + if (cplt || (len < mps)) { + if (2 != cplt) { + USB0.D0FIFO.WORD = USB_FIFOCTR_BCLR; + } + USB0.D0FIFOSEL.WORD = 0; + dcd_event_xfer_complete(rhport, pipe->ep, + pipe->length - pipe->remaining, + XFER_RESULT_SUCCESS, true); + TU_LOG1("c\r\n"); + } else { + USB0.D0FIFOSEL.WORD = 0; + } +} + +static void process_bus_reset(uint8_t rhport) +{ + USB0.BEMPENB.WORD = 1; + USB0.BRDYENB.WORD = 1; + USB0.CFIFOCTR.WORD = USB_FIFOCTR_BCLR; + USB0.D0FIFOSEL.WORD = 0; + USB0.D1FIFOSEL.WORD = 0; + volatile uint16_t *ctr = (volatile uint16_t*)((uintptr_t)(&USB0.PIPE1CTR.WORD)); + volatile uint16_t *tre = (volatile uint16_t*)((uintptr_t)(&USB0.PIPE1TRE.WORD)); + for (int i = 1; i <= 5; ++i) { + USB0.PIPESEL.WORD = i; + USB0.PIPECFG.WORD = 0; + *ctr = USB_PIPECTR_ACLRM; + *ctr = 0; + ++ctr; + *tre = (1u<<8); + tre += 2; + } + for (int i = 6; i <= 9; ++i) { + USB0.PIPESEL.WORD = i; + USB0.PIPECFG.WORD = 0; + *ctr = USB_PIPECTR_ACLRM; + *ctr = 0; + ++ctr; + } + tu_varclr(&_dcd); + dcd_event_bus_reset(rhport, TUSB_SPEED_FULL, true); + TU_LOG1("R\r\n"); +} + +static void process_set_address(uint8_t rhport) +{ + const uint32_t addr = USB0.USBADDR.BIT.USBADDR; + if (!addr) return; + const tusb_control_request_t setup_packet = { + .bmRequestType = 0, + .bRequest = 5, + .wValue = addr, + .wIndex = 0, + .wLength = 0, + }; + dcd_event_setup_received(rhport, (const uint8_t*)&setup_packet, true); +} + +/*------------------------------------------------------------------*/ +/* Device API + *------------------------------------------------------------------*/ +void dcd_init(uint8_t rhport) +{ + (void)rhport; + /* Enable USB0 */ + uint32_t pswi = disable_interrupt(); + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY | SYSTEM_PRCR_PRC1; + MSTP(USB0) = 0; + SYSTEM.PRCR.WORD = SYSTEM_PRCR_PRKEY; + enable_interrupt(pswi); + USB0.SYSCFG.BIT.SCKE = 1; + while (!USB0.SYSCFG.BIT.SCKE) ; + USB0.SYSCFG.BIT.DRPD = 0; + USB0.SYSCFG.BIT.DCFM = 0; + USB0.SYSCFG.BIT.USBE = 1; + + IR(USB0, USBI0) = 0; + + /* Setup default control pipe */ + USB0.DCPMAXP.BIT.MXPS = 64; + USB0.INTENB0.WORD = USB_IS0_VBINT | USB_IS0_BRDY | USB_IS0_BEMP | USB_IS0_DVST | USB_IS0_CTRT; + USB0.BEMPENB.WORD = 1; + USB0.BRDYENB.WORD = 1; + + TU_LOG1("INIT\r\n"); + if (USB0.INTSTS0.BIT.VBSTS) { + dcd_connect(rhport); + } +} + +void dcd_int_enable(uint8_t rhport) +{ + (void)rhport; + IEN(USB0, USBI0) = 1; +} + +void dcd_int_disable(uint8_t rhport) +{ + (void)rhport; + IEN(USB0, USBI0) = 0; +} + +void dcd_set_address(uint8_t rhport, uint8_t dev_addr) +{ + (void)rhport; + (void)dev_addr; +} + +void dcd_remote_wakeup(uint8_t rhport) +{ + (void)rhport; + /* TODO */ +} + +void dcd_connect(uint8_t rhport) +{ + (void)rhport; + USB0.SYSCFG.BIT.DPRPU = 1; +} + +void dcd_disconnect(uint8_t rhport) +{ + (void)rhport; + USB0.SYSCFG.BIT.DPRPU = 0; +} + +//--------------------------------------------------------------------+ +// Endpoint API +//--------------------------------------------------------------------+ +bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) +{ + (void)rhport; + + const unsigned ep_addr = ep_desc->bEndpointAddress; + const unsigned epn = ep_addr & 0xFu; + const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned xfer = ep_desc->bmAttributes.xfer; + + const unsigned mps = ep_desc->wMaxPacketSize.size; + if (xfer == TUSB_XFER_ISOCHRONOUS && mps > 256) { + /* USBB support up to 256 bytes */ + return false; + } + + const unsigned num = find_pipe(xfer); + if (!num) return false; + _dcd.pipe[num].ep = ep_addr; + _dcd.ep[dir][epn] = num; + + /* setup pipe */ + USB0.PIPESEL.WORD = num; + USB0.PIPEMAXP.WORD = mps; + volatile uint16_t *ctr = get_pipectr(num); + *ctr = USB_PIPECTR_ACLRM; + *ctr = 0; + unsigned cfg = (dir << 4) | epn; + if (xfer == TUSB_XFER_BULK) { + cfg |= USB_PIPECFG_BULK | USB_PIPECFG_SHTNAK | USB_PIPECFG_DBLB; + } else if (xfer == TUSB_XFER_INTERRUPT) { + cfg |= USB_PIPECFG_INT; + } else { + cfg |= USB_PIPECFG_ISO | USB_PIPECFG_DBLB; + } + USB0.PIPECFG.WORD = cfg; + if (dir) { + USB0.BEMPENB.WORD |= 1u << num; + *ctr = USB_PIPECTR_PID_BUF; + } else { + USB0.BRDYENB.WORD |= 1u << num; + if (xfer != TUSB_XFER_BULK) { + *ctr = USB_PIPECTR_PID_BUF; + } + } + TU_LOG1("O %d %x %x\r\n", USB0.PIPESEL.WORD, USB0.PIPECFG.WORD, USB0.PIPEMAXP.WORD); + + return true; +} + +void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr) +{ + (void)rhport; + const unsigned epn = ep_addr & 0xFu; + const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned num = _dcd.ep[dir][epn]; + + USB0.BEMPENB.WORD &= ~(1u << num); + USB0.BRDYENB.WORD &= ~(1u << num); + volatile uint16_t *ctr = get_pipectr(num); + *ctr = 0; + USB0.PIPESEL.WORD = num; + USB0.PIPECFG.WORD = 0; + _dcd.pipe[num].ep = 0; + _dcd.ep[dir][epn] = 0; +} + +bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) +{ + bool r; + const unsigned epn = ep_addr & 0xFu; + dcd_int_disable(rhport); + if (0 == epn) { + r = process_edpt0_xfer(rhport, ep_addr, buffer, total_bytes); + } else { + r = process_pipe_xfer(rhport, ep_addr, buffer, total_bytes); + } + dcd_int_enable(rhport); + return r; +} + +void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr) +{ + volatile uint16_t *ctr = ep_addr_to_pipectr(rhport, ep_addr); + if (!ctr) return; + dcd_int_disable(rhport); + const uint32_t pid = *ctr & 0x3; + *ctr = pid | USB_PIPECTR_PID_STALL; + *ctr = USB_PIPECTR_PID_STALL; + dcd_int_enable(rhport); +} + +void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr) +{ + volatile uint16_t *ctr = ep_addr_to_pipectr(rhport, ep_addr); + if (!ctr) return; + dcd_int_disable(rhport); + *ctr = USB_PIPECTR_SQCLR; + + if (ep_addr & TUSB_DIR_IN_MASK) { + *ctr = USB_PIPECTR_PID_BUF; + } else { + /* TODO */ + } + dcd_int_enable(rhport); +} + +//--------------------------------------------------------------------+ +// ISR +//--------------------------------------------------------------------+ +void dcd_int_handler(uint8_t rhport) +{ + (void)rhport; + + unsigned is0 = USB0.INTSTS0.WORD; + /* clear bits except VALID */ + USB0.INTSTS0.WORD = USB_IS0_VALID; + if (is0 & USB_IS0_VBINT) { + if (USB0.INTSTS0.BIT.VBSTS) { + dcd_connect(rhport); + } else { + dcd_disconnect(rhport); + } + } + if (is0 & USB_IS0_DVST) { + switch (is0 & USB_IS0_DVSQ) { + case USB_IS0_DVSQ_DEF: + process_bus_reset(rhport); + break; + case USB_IS0_DVSQ_ADDR: + process_set_address(rhport); + break; + default: + break; + } + } + if (is0 & USB_IS0_CTRT) { + if (is0 & USB_IS0_CTSQ_SETUP) { + /* A setup packet has been received. */ + process_setup_packet(rhport); + } else if (0 == (is0 & USB_IS0_CTSQ_MSK)) { + /* A ZLP has been sent/received. */ + process_status_completion(rhport); + } + } + if (is0 & USB_IS0_BEMP) { + const unsigned m = USB0.BEMPENB.WORD; + unsigned s = USB0.BEMPSTS.WORD & m; + USB0.BEMPSTS.WORD = 0; + if (s & 1) { + process_edpt0_bemp(rhport); + s &= ~1; + } + while (s) { + const unsigned num = __builtin_ctz(s); + process_pipe_bemp(rhport, num); + s &= ~(1< Date: Wed, 24 Mar 2021 00:53:55 +0900 Subject: [PATCH 03/20] update for gr_citurs --- hw/bsp/gr_citrus/board.mk | 5 +- hw/bsp/gr_citrus/gr_citrus.c | 8 +- src/portable/renesas/usba/dcd_usba.c | 169 +++++++++++++++++++++------ src/tusb_option.h | 3 + 4 files changed, 141 insertions(+), 44 deletions(-) diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk index 8675d853..53f85aa7 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/gr_citrus/board.mk @@ -28,6 +28,7 @@ MCU_DIR = hw/mcu/renesas/rx63n LD_FILE = hw/bsp/$(BOARD)/r5f5631fd.ld SRC_C += \ + src/portable/renesas/usba/dcd_usba.c \ $(MCU_DIR)/vects.c INC += \ @@ -36,10 +37,6 @@ INC += \ SRC_S += $(MCU_DIR)/start.S -# For TinyUSB port source -VENDOR = renesas -CHIP_FAMILY = usba - # For freeRTOS port source FREERTOS_PORT = RX600 diff --git a/hw/bsp/gr_citrus/gr_citrus.c b/hw/bsp/gr_citrus/gr_citrus.c index 3fa568cc..f8cf8b18 100644 --- a/hw/bsp/gr_citrus/gr_citrus.c +++ b/hw/bsp/gr_citrus/gr_citrus.c @@ -29,7 +29,7 @@ #include "interrupt_handlers.h" #define IRQ_PRIORITY_CMT0 5 -#define IRQ_PRIORITY_USBI0 5 +#define IRQ_PRIORITY_USBI0 6 #define IRQ_PRIORITY_SCI0 5 #define SYSTEM_PRCR_PRC1 (1<<1) @@ -146,13 +146,17 @@ void board_init(void) MPC.P20PFS.BYTE = 0b01010; PORT2.PMR.BIT.B1 = 1U; MPC.P21PFS.BYTE = 0b01010; - /* USB VBUS -> P16, RXD0 => P21, TXD0 => P20 */ + /* USB VBUS -> P16 DPUPE -> P14 */ + PORT1.PMR.BIT.B4 = 1U; PORT1.PMR.BIT.B6 = 1U; + MPC.P14PFS.BYTE = 0b10001; MPC.P16PFS.BYTE = MPC_PFS_ISEL | 0b10001; + MPC.PFUSB0.BIT.PUPHZS = 1; /* Lock MPC registers */ MPC.PWPR.BIT.PFSWE = 0; MPC.PWPR.BIT.B0WI = 1; + IR(USB0, USBI0) = 0; IPR(USB0, USBI0) = IRQ_PRIORITY_USBI0; /* Enable SCI0 */ diff --git a/src/portable/renesas/usba/dcd_usba.c b/src/portable/renesas/usba/dcd_usba.c index b0fa1749..cc25a3a8 100644 --- a/src/portable/renesas/usba/dcd_usba.c +++ b/src/portable/renesas/usba/dcd_usba.c @@ -72,6 +72,7 @@ #define USB_PIPECTR_SQMON (1u<<6) #define USB_PIPECTR_SQCLR (1u<<8) #define USB_PIPECTR_ACLRM (1u<<9) +#define USB_PIPECTR_INBUFM (1u<<14) #define USB_PIPECTR_BSTS (1u<<15) #define USB_FIFOCTR_DTLN (0x1FF) @@ -213,13 +214,29 @@ static volatile uint16_t* ep_addr_to_pipectr(uint8_t rhport, unsigned ep_addr) return ctr; } +static unsigned wait_for_pipe_ready(void) +{ + unsigned ctr; + do { + ctr = USB0.D0FIFOCTR.WORD; + } while (!(ctr & USB_FIFOCTR_FRDY)); + return ctr; +} + +static unsigned select_pipe(unsigned num, unsigned attr) +{ + USB0.PIPESEL.WORD = num; + USB0.D0FIFOSEL.WORD = num | attr; + while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; + return wait_for_pipe_ready(); +} /* 1 less than 64 bytes were written * 2 no bytes were written - * 0 64 bytes were written */ -static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) + * 0 mps bytes were written */ +static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, unsigned ofs) { - unsigned rem = pipe->remaining; + unsigned rem = pipe->remaining - ofs; if (!rem) return 2; unsigned len = (rem < mps) ? rem: mps; @@ -243,6 +260,35 @@ static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) if (rem < mps) return 1; return 0; } +#if 1 +static int write_fifo2(volatile void *fifo, pipe_state_t* pipe, unsigned mps) +{ + unsigned rem = pipe->remaining; + if (!rem) return 2; + unsigned len = (rem < mps) ? rem: mps; + pipe->remaining = rem - len; + + hw_fifo_t *reg = (hw_fifo_t*)fifo; + uintptr_t addr = pipe->addr + pipe->length - rem; + if (addr & 1u) { + /* addr is not 2-byte aligned */ + reg->u8 = *(const uint8_t *)addr; + ++addr; + --len; + } + while (len >= 2) { + reg->u16 = *(const uint16_t *)addr; + addr += 2; + len -= 2; + } + if (len) { + reg->u8 = *(const uint8_t *)addr; + ++addr; + } + if (rem < mps) return 1; + return 0; +} +#endif /* 1 if the number of bytes read is less than 64 bytes * 0 otherwise */ @@ -313,7 +359,7 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, pipe->data = USB0.DCPCTR.BIT.SQMON; if (ep_addr) { /* IN */ TU_ASSERT(USB0.DCPCTR.BIT.BSTS && (USB0.USBREQ.WORD & 0x80)); - if (write_fifo(&USB0.CFIFO.WORD, pipe, 64)) { + if (write_fifo(&USB0.CFIFO.WORD, pipe, 64, 0)) { USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; } } @@ -321,11 +367,11 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, // TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); } else { /* ZLP */ - pipe->addr = 0; - pipe->length = 0; - pipe->remaining = 0; - pipe->data = USB0.DCPCTR.BIT.SQMON; - USB0.DCPCTR.WORD = USB_PIPECTR_CCPL | USB_PIPECTR_PID_BUF; + pipe->addr = 0; + pipe->length = 0; + pipe->remaining = 0; + pipe->data = USB0.DCPCTR.BIT.SQMON; + USB0.DCPCTR.WORD = USB_PIPECTR_CCPL | USB_PIPECTR_PID_BUF; // TU_LOG1("Z %x\r\n", USB0.DCPCTR.WORD); } return true; @@ -338,7 +384,7 @@ static void process_edpt0_bemp(uint8_t rhport) if (USB0.DCPCTR.BIT.SQMON == data) { TU_LOG1("W %x\r\n", USB0.DCPCTR.WORD); /* retry transfer */ - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, 0); if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; return; } @@ -347,7 +393,7 @@ static void process_edpt0_bemp(uint8_t rhport) pipe->remaining = rem - 64; pipe->data = data ^ 1; TU_LOG1("Y %d %x\r\n", rem - 64, USB0.DCPCTR.WORD); - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, 0); if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; return; } @@ -393,9 +439,23 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, if (dir) { /* IN */ USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; - if (write_fifo(&USB0.D0FIFO.WORD, pipe, mps)) { +#if 0 + unsigned ofs = 0; + if (USB0.PIPECFG.BIT.DBLB && (total_bytes > mps)) { + write_fifo(&USB0.D0FIFO.WORD, pipe, mps, 0); + } + if (write_fifo(&USB0.D0FIFO.WORD, pipe, mps, ofs)) { USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; } +#else + if (USB0.PIPECFG.BIT.DBLB && (total_bytes > mps)) { + write_fifo2(&USB0.D0FIFO.WORD, pipe, mps); + wait_for_pipe_ready(); + } + if (write_fifo2(&USB0.D0FIFO.WORD, pipe, mps)) { + USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + } +#endif USB0.D0FIFOSEL.WORD = 0; } else { volatile reg_pipetre_t *pt = get_pipetre(num); @@ -411,43 +471,76 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); return true; } - +#if 0 static void process_pipe_bemp(uint8_t rhport, unsigned num) { pipe_state_t *pipe = &_dcd.pipe[num]; - const unsigned rem = pipe->remaining; - if (rem > 64) { - pipe->remaining = rem - 64; - TU_LOG1("Y %d\r\n", rem - 64); - USB0.PIPESEL.WORD = num; - const unsigned mps = USB0.PIPEMAXP.WORD; - USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; - while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; - int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); - if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - USB0.D0FIFOSEL.WORD = 0; + unsigned rem = pipe->remaining; + USB0.PIPESEL.WORD = num; + const unsigned mps = USB0.PIPEMAXP.WORD; + + if (rem > mps) { + rem -= mps; + pipe->remaining = rem; + if (USB0.PIPECFG.BIT.DBLB) { + if (rem > mps) { + unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); + int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); + } + } else { + unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); + int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps, 0); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); + } return; } pipe->addr = 0; pipe->remaining = 0; + USB0.D0FIFOSEL.WORD = 0; dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, XFER_RESULT_SUCCESS, true); - // TU_LOG1("cE\r\n"); + TU_LOG1("cE\r\n"); } +#else +static void process_pipe_bemp(uint8_t rhport, unsigned num) +{ + pipe_state_t *pipe = &_dcd.pipe[num]; + const unsigned rem = pipe->remaining; + if (rem) { + USB0.PIPESEL.WORD = num; + const unsigned mps = USB0.PIPEMAXP.WORD; + unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); + int r = write_fifo2(&USB0.D0FIFO.WORD, pipe, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); + return; + } + if (*get_pipectr(num) & USB_PIPECTR_INBUFM) { + TU_LOG1("< SKIP\r\n"); + return; + } + pipe->addr = 0; + pipe->remaining = 0; + USB0.D0FIFOSEL.WORD = 0; + dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, + XFER_RESULT_SUCCESS, true); + TU_LOG1("cE\r\n"); +} +#endif static void process_pipe_brdy(uint8_t rhport, unsigned num) { - pipe_state_t *pipe = &_dcd.pipe[num]; - USB0.PIPESEL.WORD = num; - const unsigned mps = USB0.PIPEMAXP.WORD; - USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_8; - while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; - unsigned ctr; - do { - ctr = USB0.D0FIFOCTR.WORD; - } while (!(ctr & USB_FIFOCTR_FRDY)); - const unsigned len = ctr & USB_FIFOCTR_DTLN; - TU_LOG1(">> %d %x %x\r\n", num, USB0.D0FIFOSEL.WORD, ctr); + const unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_8); + const unsigned len = ctr & USB_FIFOCTR_DTLN; + const unsigned mps = USB0.PIPEMAXP.WORD; + pipe_state_t *pipe = &_dcd.pipe[num]; + // TU_LOG1("> %d %x %x\r\n", num, USB0.D0FIFOSEL.WORD, ctr); int cplt = read_fifo(&USB0.D0FIFO.WORD, pipe, mps, len); if (cplt || (len < mps)) { if (2 != cplt) { @@ -457,7 +550,7 @@ static void process_pipe_brdy(uint8_t rhport, unsigned num) dcd_event_xfer_complete(rhport, pipe->ep, pipe->length - pipe->remaining, XFER_RESULT_SUCCESS, true); - TU_LOG1("c\r\n"); + // TU_LOG1("c\r\n"); } else { USB0.D0FIFOSEL.WORD = 0; } @@ -589,7 +682,7 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) const unsigned mps = ep_desc->wMaxPacketSize.size; if (xfer == TUSB_XFER_ISOCHRONOUS && mps > 256) { - /* USBB support up to 256 bytes */ + /* USBa supports up to 256 bytes */ return false; } diff --git a/src/tusb_option.h b/src/tusb_option.h index d0ed78ac..644208ab 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -108,6 +108,9 @@ #define OPT_MCU_EFM32GG11 1301 ///< Silabs EFM32GG11 #define OPT_MCU_EFM32GG12 1302 ///< Silabs EFM32GG12 +// Renesas RX +#define OPT_MCU_RX63X 1400 ///< Renesas RX63N/631 + /** @} */ /** \defgroup group_supported_os Supported RTOS From e010ea30e57e0f8561f8aa7b66afefb01a9bc42d Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sat, 27 Mar 2021 14:42:19 +0900 Subject: [PATCH 04/20] using BRDY interruption for handling IN transfers. --- src/portable/renesas/usba/dcd_usba.c | 228 ++++++++------------------- 1 file changed, 62 insertions(+), 166 deletions(-) diff --git a/src/portable/renesas/usba/dcd_usba.c b/src/portable/renesas/usba/dcd_usba.c index cc25a3a8..e7518b01 100644 --- a/src/portable/renesas/usba/dcd_usba.c +++ b/src/portable/renesas/usba/dcd_usba.c @@ -200,9 +200,9 @@ static volatile uint16_t* ep_addr_to_pipectr(uint8_t rhport, unsigned ep_addr) { (void)rhport; volatile uint16_t *ctr = NULL; - const unsigned epn = ep_addr & 0xFu; + const unsigned epn = tu_edpt_number(ep_addr); if (epn) { - const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned dir = tu_edpt_dir(ep_addr); const unsigned num = _dcd.ep[dir][epn]; if (num) { ctr = (volatile uint16_t*)&USB0.PIPE1CTR.WORD; @@ -234,39 +234,11 @@ static unsigned select_pipe(unsigned num, unsigned attr) /* 1 less than 64 bytes were written * 2 no bytes were written * 0 mps bytes were written */ -static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, unsigned ofs) -{ - unsigned rem = pipe->remaining - ofs; - if (!rem) return 2; - unsigned len = (rem < mps) ? rem: mps; - - hw_fifo_t *reg = (hw_fifo_t*)fifo; - uintptr_t addr = pipe->addr + pipe->length - rem; - if (addr & 1u) { - /* addr is not 2-byte aligned */ - reg->u8 = *(const uint8_t *)addr; - ++addr; - --len; - } - while (len >= 2) { - reg->u16 = *(const uint16_t *)addr; - addr += 2; - len -= 2; - } - if (len) { - reg->u8 = *(const uint8_t *)addr; - ++addr; - } - if (rem < mps) return 1; - return 0; -} -#if 1 -static int write_fifo2(volatile void *fifo, pipe_state_t* pipe, unsigned mps) +static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) { unsigned rem = pipe->remaining; if (!rem) return 2; - unsigned len = (rem < mps) ? rem: mps; - pipe->remaining = rem - len; + unsigned len = TU_MIN(rem, mps); hw_fifo_t *reg = (hw_fifo_t*)fifo; uintptr_t addr = pipe->addr + pipe->length - rem; @@ -288,7 +260,6 @@ static int write_fifo2(volatile void *fifo, pipe_state_t* pipe, unsigned mps) if (rem < mps) return 1; return 0; } -#endif /* 1 if the number of bytes read is less than 64 bytes * 0 otherwise */ @@ -359,7 +330,7 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, pipe->data = USB0.DCPCTR.BIT.SQMON; if (ep_addr) { /* IN */ TU_ASSERT(USB0.DCPCTR.BIT.BSTS && (USB0.USBREQ.WORD & 0x80)); - if (write_fifo(&USB0.CFIFO.WORD, pipe, 64, 0)) { + if (write_fifo(&USB0.CFIFO.WORD, pipe, 64)) { USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; } } @@ -372,7 +343,6 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, pipe->remaining = 0; pipe->data = USB0.DCPCTR.BIT.SQMON; USB0.DCPCTR.WORD = USB_PIPECTR_CCPL | USB_PIPECTR_PID_BUF; - // TU_LOG1("Z %x\r\n", USB0.DCPCTR.WORD); } return true; } @@ -382,9 +352,8 @@ static void process_edpt0_bemp(uint8_t rhport) pipe_state_t *pipe = &_dcd.pipe[0]; unsigned data = pipe->data; if (USB0.DCPCTR.BIT.SQMON == data) { - TU_LOG1("W %x\r\n", USB0.DCPCTR.WORD); /* retry transfer */ - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, 0); + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; return; } @@ -392,16 +361,14 @@ static void process_edpt0_bemp(uint8_t rhport) if (rem > 64) { pipe->remaining = rem - 64; pipe->data = data ^ 1; - TU_LOG1("Y %d %x\r\n", rem - 64, USB0.DCPCTR.WORD); - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, 0); + int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; return; } pipe->addr = 0; pipe->remaining = 0; dcd_event_xfer_complete(rhport, tu_edpt_addr(0, TUSB_DIR_IN), - pipe->length, XFER_RESULT_SUCCESS, true); - // TU_LOG1("c\r\n"); + pipe->length, XFER_RESULT_SUCCESS, true); } static void process_edpt0_brdy(uint8_t rhport) @@ -414,8 +381,7 @@ static void process_edpt0_brdy(uint8_t rhport) } dcd_event_xfer_complete(rhport, tu_edpt_addr(0, TUSB_DIR_OUT), _dcd.pipe[0].length - _dcd.pipe[0].remaining, - XFER_RESULT_SUCCESS, true); - // TU_LOG1("c\r\n"); + XFER_RESULT_SUCCESS, true); } } @@ -423,8 +389,8 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, { (void)rhport; - const unsigned epn = ep_addr & 0xFu; - const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned epn = tu_edpt_number(ep_addr); + const unsigned dir = tu_edpt_dir(ep_addr); const unsigned num = _dcd.ep[dir][epn]; TU_ASSERT(num); @@ -439,120 +405,61 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, if (dir) { /* IN */ USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; -#if 0 - unsigned ofs = 0; - if (USB0.PIPECFG.BIT.DBLB && (total_bytes > mps)) { - write_fifo(&USB0.D0FIFO.WORD, pipe, mps, 0); - } - if (write_fifo(&USB0.D0FIFO.WORD, pipe, mps, ofs)) { - USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - } -#else - if (USB0.PIPECFG.BIT.DBLB && (total_bytes > mps)) { - write_fifo2(&USB0.D0FIFO.WORD, pipe, mps); - wait_for_pipe_ready(); - } - if (write_fifo2(&USB0.D0FIFO.WORD, pipe, mps)) { - USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - } -#endif + int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; USB0.D0FIFOSEL.WORD = 0; } else { volatile reg_pipetre_t *pt = get_pipetre(num); if (pt) { volatile uint16_t *ctr = get_pipectr(num); if (*ctr & 0x3) *ctr = USB_PIPECTR_PID_NAK; - pt->TRE = 1u << 8; + pt->TRE = TU_BIT(8); pt->TRN = (total_bytes + mps - 1) / mps; pt->TRENB = 1; *ctr = USB_PIPECTR_PID_BUF; } } - TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); + //TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); return true; } -#if 0 -static void process_pipe_bemp(uint8_t rhport, unsigned num) -{ - pipe_state_t *pipe = &_dcd.pipe[num]; - unsigned rem = pipe->remaining; - USB0.PIPESEL.WORD = num; - const unsigned mps = USB0.PIPEMAXP.WORD; - - if (rem > mps) { - rem -= mps; - pipe->remaining = rem; - if (USB0.PIPECFG.BIT.DBLB) { - if (rem > mps) { - unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); - int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps, mps); - if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - USB0.D0FIFOSEL.WORD = 0; - TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); - } - } else { - unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); - int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps, 0); - if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - USB0.D0FIFOSEL.WORD = 0; - TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); - } - return; - } - pipe->addr = 0; - pipe->remaining = 0; - USB0.D0FIFOSEL.WORD = 0; - dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, - XFER_RESULT_SUCCESS, true); - TU_LOG1("cE\r\n"); -} -#else -static void process_pipe_bemp(uint8_t rhport, unsigned num) -{ - pipe_state_t *pipe = &_dcd.pipe[num]; - const unsigned rem = pipe->remaining; - if (rem) { - USB0.PIPESEL.WORD = num; - const unsigned mps = USB0.PIPEMAXP.WORD; - unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_16); - int r = write_fifo2(&USB0.D0FIFO.WORD, pipe, mps); - if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - USB0.D0FIFOSEL.WORD = 0; - TU_LOG1("< %d %x %x %d\r\n", rem, ctr, *get_pipectr(num), r); - return; - } - if (*get_pipectr(num) & USB_PIPECTR_INBUFM) { - TU_LOG1("< SKIP\r\n"); - return; - } - pipe->addr = 0; - pipe->remaining = 0; - USB0.D0FIFOSEL.WORD = 0; - dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, - XFER_RESULT_SUCCESS, true); - TU_LOG1("cE\r\n"); -} -#endif static void process_pipe_brdy(uint8_t rhport, unsigned num) { - const unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_8); - const unsigned len = ctr & USB_FIFOCTR_DTLN; - const unsigned mps = USB0.PIPEMAXP.WORD; pipe_state_t *pipe = &_dcd.pipe[num]; - // TU_LOG1("> %d %x %x\r\n", num, USB0.D0FIFOSEL.WORD, ctr); - int cplt = read_fifo(&USB0.D0FIFO.WORD, pipe, mps, len); - if (cplt || (len < mps)) { - if (2 != cplt) { - USB0.D0FIFO.WORD = USB_FIFOCTR_BCLR; + if (!tu_edpt_dir(pipe->ep)) { + const unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_8); + const unsigned len = ctr & USB_FIFOCTR_DTLN; + const unsigned mps = USB0.PIPEMAXP.WORD; + int cplt = read_fifo(&USB0.D0FIFO.WORD, pipe, mps, len); + if (cplt || (len < mps)) { + if (2 != cplt) { + USB0.D0FIFO.WORD = USB_FIFOCTR_BCLR; + } + USB0.D0FIFOSEL.WORD = 0; + dcd_event_xfer_complete(rhport, pipe->ep, + pipe->length - pipe->remaining, + XFER_RESULT_SUCCESS, true); + return; } USB0.D0FIFOSEL.WORD = 0; - dcd_event_xfer_complete(rhport, pipe->ep, - pipe->length - pipe->remaining, - XFER_RESULT_SUCCESS, true); - // TU_LOG1("c\r\n"); } else { + select_pipe(num, USB_FIFOSEL_MBW_16); + const unsigned mps = USB0.PIPEMAXP.WORD; + unsigned rem = pipe->remaining; + rem -= TU_MIN(rem, mps); + pipe->remaining = rem; + if (rem) { + int r = 0; + r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + return; + } USB0.D0FIFOSEL.WORD = 0; + pipe->addr = 0; + pipe->remaining = 0; + dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, + XFER_RESULT_SUCCESS, true); } } @@ -571,7 +478,7 @@ static void process_bus_reset(uint8_t rhport) *ctr = USB_PIPECTR_ACLRM; *ctr = 0; ++ctr; - *tre = (1u<<8); + *tre = TU_BIT(8); tre += 2; } for (int i = 6; i <= 9; ++i) { @@ -583,7 +490,7 @@ static void process_bus_reset(uint8_t rhport) } tu_varclr(&_dcd); dcd_event_bus_reset(rhport, TUSB_SPEED_FULL, true); - TU_LOG1("R\r\n"); + // TU_LOG1("R\r\n"); } static void process_set_address(uint8_t rhport) @@ -626,7 +533,6 @@ void dcd_init(uint8_t rhport) USB0.BEMPENB.WORD = 1; USB0.BRDYENB.WORD = 1; - TU_LOG1("INIT\r\n"); if (USB0.INTSTS0.BIT.VBSTS) { dcd_connect(rhport); } @@ -676,8 +582,8 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) (void)rhport; const unsigned ep_addr = ep_desc->bEndpointAddress; - const unsigned epn = ep_addr & 0xFu; - const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned epn = tu_edpt_number(ep_addr); + const unsigned dir = tu_edpt_dir(ep_addr); const unsigned xfer = ep_desc->bmAttributes.xfer; const unsigned mps = ep_desc->wMaxPacketSize.size; @@ -692,6 +598,7 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) _dcd.ep[dir][epn] = num; /* setup pipe */ + dcd_int_disable(rhport); USB0.PIPESEL.WORD = num; USB0.PIPEMAXP.WORD = mps; volatile uint16_t *ctr = get_pipectr(num); @@ -705,17 +612,14 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) } else { cfg |= USB_PIPECFG_ISO | USB_PIPECFG_DBLB; } - USB0.PIPECFG.WORD = cfg; - if (dir) { - USB0.BEMPENB.WORD |= 1u << num; + USB0.PIPECFG.WORD = cfg; + USB0.BRDYSTS.WORD = 0x1FFu ^ TU_BIT(num); + USB0.BRDYENB.WORD |= TU_BIT(num); + if (dir || (xfer != TUSB_XFER_BULK)) { *ctr = USB_PIPECTR_PID_BUF; - } else { - USB0.BRDYENB.WORD |= 1u << num; - if (xfer != TUSB_XFER_BULK) { - *ctr = USB_PIPECTR_PID_BUF; - } } - TU_LOG1("O %d %x %x\r\n", USB0.PIPESEL.WORD, USB0.PIPECFG.WORD, USB0.PIPEMAXP.WORD); + // TU_LOG1("O %d %x %x\r\n", USB0.PIPESEL.WORD, USB0.PIPECFG.WORD, USB0.PIPEMAXP.WORD); + dcd_int_enable(rhport); return true; } @@ -723,12 +627,11 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc) void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr) { (void)rhport; - const unsigned epn = ep_addr & 0xFu; - const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT; + const unsigned epn = tu_edpt_number(ep_addr); + const unsigned dir = tu_edpt_dir(ep_addr); const unsigned num = _dcd.ep[dir][epn]; - USB0.BEMPENB.WORD &= ~(1u << num); - USB0.BRDYENB.WORD &= ~(1u << num); + USB0.BRDYENB.WORD &= ~TU_BIT(num); volatile uint16_t *ctr = get_pipectr(num); *ctr = 0; USB0.PIPESEL.WORD = num; @@ -740,7 +643,7 @@ void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr) bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) { bool r; - const unsigned epn = ep_addr & 0xFu; + const unsigned epn = tu_edpt_number(ep_addr); dcd_int_disable(rhport); if (0 == epn) { r = process_edpt0_xfer(rhport, ep_addr, buffer, total_bytes); @@ -816,17 +719,10 @@ void dcd_int_handler(uint8_t rhport) } } if (is0 & USB_IS0_BEMP) { - const unsigned m = USB0.BEMPENB.WORD; - unsigned s = USB0.BEMPSTS.WORD & m; + const unsigned s = USB0.BEMPSTS.WORD; USB0.BEMPSTS.WORD = 0; if (s & 1) { process_edpt0_bemp(rhport); - s &= ~1; - } - while (s) { - const unsigned num = __builtin_ctz(s); - process_pipe_bemp(rhport, num); - s &= ~(1< Date: Sat, 27 Mar 2021 16:00:56 +0900 Subject: [PATCH 05/20] fixed definitions for stack areas --- hw/bsp/gr_citrus/r5f5631fd.ld | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/hw/bsp/gr_citrus/r5f5631fd.ld b/hw/bsp/gr_citrus/r5f5631fd.ld index 166a9e7c..fa814293 100644 --- a/hw/bsp/gr_citrus/r5f5631fd.ld +++ b/hw/bsp/gr_citrus/r5f5631fd.ld @@ -1,5 +1,5 @@ __USTACK_SIZE = 0x00000200; -__ISTACK_SIZE = 0x00000100; +__ISTACK_SIZE = 0x00000200; MEMORY { @@ -112,13 +112,13 @@ SECTIONS _ebss = .; _end = .; } > RAM - .ustack (COPY) : + .ustack : { . = ALIGN(8); . = . + __USTACK_SIZE; PROVIDE(_ustack = .); } > RAM - .istack (COPY) : + .istack : { . = ALIGN(8); . = . + __ISTACK_SIZE; From a1f1941c3f965483e274993e43d18a9ede5e1f09 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sat, 27 Mar 2021 16:03:04 +0900 Subject: [PATCH 06/20] fixed a OUT transfer did not completed multiple of the max packet size --- src/portable/renesas/usba/dcd_usba.c | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/portable/renesas/usba/dcd_usba.c b/src/portable/renesas/usba/dcd_usba.c index e7518b01..844fa385 100644 --- a/src/portable/renesas/usba/dcd_usba.c +++ b/src/portable/renesas/usba/dcd_usba.c @@ -261,7 +261,7 @@ static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) return 0; } -/* 1 if the number of bytes read is less than 64 bytes +/* 1 if the number of bytes read is less than mps bytes * 0 otherwise */ static int read_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, size_t len) { @@ -272,12 +272,14 @@ static int read_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, size hw_fifo_t *reg = (hw_fifo_t*)fifo; uintptr_t addr = pipe->addr; - while (len--) { + unsigned loop = len; + while (loop--) { *(uint8_t *)addr = reg->u8; ++addr; } pipe->addr = addr; - if (rem < mps) return 1; + if (rem < mps) return 1; + if (rem == len) return 2; return 0; } @@ -419,7 +421,7 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, *ctr = USB_PIPECTR_PID_BUF; } } - //TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); + // TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); return true; } From eab214e07c53d84d33a74c5a73fe40c152e3b987 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sat, 27 Mar 2021 19:12:34 +0900 Subject: [PATCH 07/20] added settings for LWIP and FreeRTOS --- hw/bsp/gr_citrus/board.mk | 14 ++++++++++---- hw/bsp/gr_citrus/gr_citrus.c | 2 ++ 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk index 53f85aa7..241c12bc 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/gr_citrus/board.mk @@ -1,6 +1,5 @@ CFLAGS += \ -nostartfiles \ - -nostdinc \ -ffunction-sections \ -fdata-sections \ -mcpu=rx610 \ @@ -17,10 +16,17 @@ else OPTLIBINC=$(shell dirname `which rx-elf-gcc`)../rx-elf/optlibinc endif -# mcu driver cause following warnings -CFLAGS += -isystem $(OPTLIBINC) +ifeq ($(RX_NEWLIB),0) +# setup for optlib +CFLAGS += -nostdinc \ + -isystem $(OPTLIBINC) \ + -DLWIP_NO_INTTYPES_H -LIBS += -loptm -loptc +LIBS += -loptc -loptm +else +# setup for newlib +LIBS += -lm +endif MCU_DIR = hw/mcu/renesas/rx63n diff --git a/hw/bsp/gr_citrus/gr_citrus.c b/hw/bsp/gr_citrus/gr_citrus.c index f8cf8b18..aadd4139 100644 --- a/hw/bsp/gr_citrus/gr_citrus.c +++ b/hw/bsp/gr_citrus/gr_citrus.c @@ -218,4 +218,6 @@ uint32_t board_millis(void) { return system_ticks; } +#else +uint32_t SystemCoreClock = 96000000; #endif From 86dab3f7e9ce5880eb7f5eb340110735e8ace54f Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sat, 27 Mar 2021 20:22:32 +0900 Subject: [PATCH 08/20] added configurations for RX63X --- .../cdc_msc_freertos/src/FreeRTOSConfig.h | 12 ++++++++++++ .../cdc_msc_freertos/src/freertos_hook.c | 19 +++++++++++++++++++ examples/device/cdc_msc_freertos/src/main.c | 4 +++- .../src/FreeRTOSConfig.h | 12 ++++++++++++ .../src/freertos_hook.c | 19 +++++++++++++++++++ .../device/hid_composite_freertos/src/main.c | 4 +++- 6 files changed, 68 insertions(+), 2 deletions(-) diff --git a/examples/device/cdc_msc_freertos/src/FreeRTOSConfig.h b/examples/device/cdc_msc_freertos/src/FreeRTOSConfig.h index 7b2b93d7..b76d5970 100644 --- a/examples/device/cdc_msc_freertos/src/FreeRTOSConfig.h +++ b/examples/device/cdc_msc_freertos/src/FreeRTOSConfig.h @@ -132,6 +132,16 @@ extern uint32_t SystemCoreClock; #define configASSERT( x ) #endif +#ifdef __RX__ +/* Renesas RX series */ +#define vSoftwareInterruptISR INT_Excep_ICU_SWINT +#define vTickISR INT_Excep_CMT0_CMI0 +#define configPERIPHERAL_CLOCK_HZ (configCPU_CLOCK_HZ/2) +#define configKERNEL_INTERRUPT_PRIORITY 1 +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 4 + +#else + /* FreeRTOS hooks to NVIC vectors */ #define xPortPendSVHandler PendSV_Handler #define xPortSysTickHandler SysTick_Handler @@ -164,4 +174,6 @@ to all Cortex-M ports, and do not rely on any particular library functions. */ See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */ #define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) +#endif + #endif /* __FREERTOS_CONFIG__H */ diff --git a/examples/device/cdc_msc_freertos/src/freertos_hook.c b/examples/device/cdc_msc_freertos/src/freertos_hook.c index df15a8de..273ad46e 100644 --- a/examples/device/cdc_msc_freertos/src/freertos_hook.c +++ b/examples/device/cdc_msc_freertos/src/freertos_hook.c @@ -93,3 +93,22 @@ void vApplicationGetTimerTaskMemory( StaticTask_t **ppxTimerTaskTCBBuffer, Stack configTIMER_TASK_STACK_DEPTH is specified in words, not bytes. */ *pulTimerTaskStackSize = configTIMER_TASK_STACK_DEPTH; } + +#if CFG_TUSB_MCU == OPT_MCU_RX63X +#include "iodefine.h" +void vApplicationSetupTimerInterrupt(void) +{ + /* Enable CMT0 */ + SYSTEM.PRCR.WORD = (0xA5u<<8) | TU_BIT(1); + MSTP(CMT0) = 0; + SYSTEM.PRCR.WORD = (0xA5u<<8); + + CMT0.CMCNT = 0; + CMT0.CMCOR = (unsigned short)(((configPERIPHERAL_CLOCK_HZ/configTICK_RATE_HZ)-1)/128); + CMT0.CMCR.WORD = TU_BIT(6) | 2; + IR(CMT0, CMI0) = 0; + IPR(CMT0, CMI0) = configKERNEL_INTERRUPT_PRIORITY; + IEN(CMT0, CMI0) = 1; + CMT.CMSTR0.BIT.STR0 = 1; +} +#endif diff --git a/examples/device/cdc_msc_freertos/src/main.c b/examples/device/cdc_msc_freertos/src/main.c index 5779b7d4..abb95f4f 100644 --- a/examples/device/cdc_msc_freertos/src/main.c +++ b/examples/device/cdc_msc_freertos/src/main.c @@ -97,9 +97,11 @@ int main(void) // skip starting scheduler (and return) for ESP32-S2 #if CFG_TUSB_MCU != OPT_MCU_ESP32S2 vTaskStartScheduler(); +#if CFG_TUSB_MCU != OPT_MCU_RX63X NVIC_SystemReset(); - return 0; #endif +#endif + return 0; } #if CFG_TUSB_MCU == OPT_MCU_ESP32S2 diff --git a/examples/device/hid_composite_freertos/src/FreeRTOSConfig.h b/examples/device/hid_composite_freertos/src/FreeRTOSConfig.h index 7b2b93d7..b76d5970 100644 --- a/examples/device/hid_composite_freertos/src/FreeRTOSConfig.h +++ b/examples/device/hid_composite_freertos/src/FreeRTOSConfig.h @@ -132,6 +132,16 @@ extern uint32_t SystemCoreClock; #define configASSERT( x ) #endif +#ifdef __RX__ +/* Renesas RX series */ +#define vSoftwareInterruptISR INT_Excep_ICU_SWINT +#define vTickISR INT_Excep_CMT0_CMI0 +#define configPERIPHERAL_CLOCK_HZ (configCPU_CLOCK_HZ/2) +#define configKERNEL_INTERRUPT_PRIORITY 1 +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 4 + +#else + /* FreeRTOS hooks to NVIC vectors */ #define xPortPendSVHandler PendSV_Handler #define xPortSysTickHandler SysTick_Handler @@ -164,4 +174,6 @@ to all Cortex-M ports, and do not rely on any particular library functions. */ See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */ #define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) +#endif + #endif /* __FREERTOS_CONFIG__H */ diff --git a/examples/device/hid_composite_freertos/src/freertos_hook.c b/examples/device/hid_composite_freertos/src/freertos_hook.c index df15a8de..273ad46e 100644 --- a/examples/device/hid_composite_freertos/src/freertos_hook.c +++ b/examples/device/hid_composite_freertos/src/freertos_hook.c @@ -93,3 +93,22 @@ void vApplicationGetTimerTaskMemory( StaticTask_t **ppxTimerTaskTCBBuffer, Stack configTIMER_TASK_STACK_DEPTH is specified in words, not bytes. */ *pulTimerTaskStackSize = configTIMER_TASK_STACK_DEPTH; } + +#if CFG_TUSB_MCU == OPT_MCU_RX63X +#include "iodefine.h" +void vApplicationSetupTimerInterrupt(void) +{ + /* Enable CMT0 */ + SYSTEM.PRCR.WORD = (0xA5u<<8) | TU_BIT(1); + MSTP(CMT0) = 0; + SYSTEM.PRCR.WORD = (0xA5u<<8); + + CMT0.CMCNT = 0; + CMT0.CMCOR = (unsigned short)(((configPERIPHERAL_CLOCK_HZ/configTICK_RATE_HZ)-1)/128); + CMT0.CMCR.WORD = TU_BIT(6) | 2; + IR(CMT0, CMI0) = 0; + IPR(CMT0, CMI0) = configKERNEL_INTERRUPT_PRIORITY; + IEN(CMT0, CMI0) = 1; + CMT.CMSTR0.BIT.STR0 = 1; +} +#endif diff --git a/examples/device/hid_composite_freertos/src/main.c b/examples/device/hid_composite_freertos/src/main.c index 79dc2ec6..1b42cee4 100644 --- a/examples/device/hid_composite_freertos/src/main.c +++ b/examples/device/hid_composite_freertos/src/main.c @@ -98,9 +98,11 @@ int main(void) // skip starting scheduler (and return) for ESP32-S2 #if CFG_TUSB_MCU != OPT_MCU_ESP32S2 vTaskStartScheduler(); +#if CFG_TUSB_MCU != OPT_MCU_RX63X NVIC_SystemReset(); - return 0; #endif +#endif + return 0; } #if CFG_TUSB_MCU == OPT_MCU_ESP32S2 From 4c832a9195cfca5a2d840c30efc010da75f71b4b Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sat, 27 Mar 2021 22:20:15 +0900 Subject: [PATCH 09/20] Set newlib as the default library --- hw/bsp/gr_citrus/board.mk | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk index 241c12bc..39aef2e9 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/gr_citrus/board.mk @@ -10,22 +10,23 @@ CFLAGS += \ # Cross Compiler for RX CROSS_COMPILE = rx-elf- +RX_NEWLIB ?= 1 + ifeq ($(CMDEXE),1) OPTLIBINC="$(shell for /F "usebackq delims=" %%i in (`where rx-elf-gcc`) do echo %%~dpi..\rx-elf\optlibinc)" else OPTLIBINC=$(shell dirname `which rx-elf-gcc`)../rx-elf/optlibinc endif -ifeq ($(RX_NEWLIB),0) +ifeq ($(RX_NEWLIB),1) +CFLAGS += -DSSIZE_MAX=__INT_MAX__ +else # setup for optlib CFLAGS += -nostdinc \ -isystem $(OPTLIBINC) \ -DLWIP_NO_INTTYPES_H LIBS += -loptc -loptm -else -# setup for newlib -LIBS += -lm endif MCU_DIR = hw/mcu/renesas/rx63n From 5f4e6dafc564847728712ceac14bafa4577c3862 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 28 Mar 2021 00:10:53 +0900 Subject: [PATCH 10/20] added short-enums into CFLAGS --- hw/bsp/gr_citrus/board.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk index 39aef2e9..06262184 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/gr_citrus/board.mk @@ -2,6 +2,7 @@ CFLAGS += \ -nostartfiles \ -ffunction-sections \ -fdata-sections \ + -fshort-enums \ -mcpu=rx610 \ -misa=v1 \ -mlittle-endian-data \ From 0b76a2da88d01f5defcc22c25d3d8bb4068dbf8d Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 28 Mar 2021 00:34:29 +0900 Subject: [PATCH 11/20] added a setting for RX63X --- hw/bsp/board_mcu.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index 3c18f6d3..362e3289 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -123,6 +123,9 @@ #elif CFG_TUSB_MCU == OPT_MCU_EFM32GG || CFG_TUSB_MCU == OPT_MCU_EFM32GG11 || CFG_TUSB_MCU == OPT_MCU_EFM32GG12 #include "em_device.h" +#elif CFG_TUSB_MCU == OPT_MCU_RX63X + // no header needed + #else #error "Missing MCU header" #endif From 0e0f9a8da30780c9db711e08371465343247604e Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 28 Mar 2021 00:46:08 +0900 Subject: [PATCH 12/20] added a submodule for RX63N --- .gitmodules | 3 +++ hw/mcu/renesas | 1 + 2 files changed, 4 insertions(+) create mode 160000 hw/mcu/renesas diff --git a/.gitmodules b/.gitmodules index 1a5ae2c5..e075e0c6 100644 --- a/.gitmodules +++ b/.gitmodules @@ -116,3 +116,6 @@ [submodule "hw/mcu/silabs/cmsis-dfp-efm32gg12b"] path = hw/mcu/silabs/cmsis-dfp-efm32gg12b url = https://github.com/cmsis-packs/cmsis-dfp-efm32gg12b +[submodule "hw/mcu/renesas"] + path = hw/mcu/renesas + url = https://github.com/kkitayam/rx_device.git diff --git a/hw/mcu/renesas b/hw/mcu/renesas new file mode 160000 index 00000000..4a51dfe6 --- /dev/null +++ b/hw/mcu/renesas @@ -0,0 +1 @@ +Subproject commit 4a51dfe6ecdf936d2d89f223f069e24a2d109207 From 4a597c969844d9b279279db0f678aa6732bae1a5 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 28 Mar 2021 12:42:28 +0900 Subject: [PATCH 13/20] cleanup --- src/portable/renesas/usba/dcd_usba.c | 102 ++++++++++++--------------- 1 file changed, 46 insertions(+), 56 deletions(-) diff --git a/src/portable/renesas/usba/dcd_usba.c b/src/portable/renesas/usba/dcd_usba.c index 844fa385..06ea1a3f 100644 --- a/src/portable/renesas/usba/dcd_usba.c +++ b/src/portable/renesas/usba/dcd_usba.c @@ -112,12 +112,11 @@ typedef union { typedef struct TU_ATTR_PACKED { - uintptr_t addr; - uint16_t length; - uint16_t remaining; + uintptr_t addr; /* the start address of a transfer data buffer */ + uint16_t length; /* the number of bytes in the buffer */ + uint16_t remaining; /* the number of bytes remaining in the buffer */ struct { - uint32_t ep : 8; - uint32_t data: 1; + uint32_t ep : 8; /* an assigned endpoint address */ uint32_t : 0; }; } pipe_state_t; @@ -125,7 +124,7 @@ typedef struct TU_ATTR_PACKED typedef struct { pipe_state_t pipe[9]; - uint8_t ep[2][16]; /* index for pipe number */ + uint8_t ep[2][16]; /* a lookup table for a pipe index from an endpoint address */ } dcd_data_t; //--------------------------------------------------------------------+ @@ -231,10 +230,10 @@ static unsigned select_pipe(unsigned num, unsigned attr) return wait_for_pipe_ready(); } -/* 1 less than 64 bytes were written - * 2 no bytes were written - * 0 mps bytes were written */ -static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) +/* 1 less than mps bytes were written to FIFO + * 2 no bytes were written to FIFO + * 0 mps bytes were written to FIFO */ +static int fifo_write(volatile void *fifo, pipe_state_t* pipe, unsigned mps) { unsigned rem = pipe->remaining; if (!rem) return 2; @@ -261,9 +260,10 @@ static int write_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps) return 0; } -/* 1 if the number of bytes read is less than mps bytes - * 0 otherwise */ -static int read_fifo(volatile void *fifo, pipe_state_t* pipe, unsigned mps, size_t len) +/* 1 less than mps bytes were read from FIFO + * 2 the end of the buffer reached. + * 0 mps bytes were read from FIFO */ +static int fifo_read(volatile void *fifo, pipe_state_t* pipe, unsigned mps, size_t len) { unsigned rem = pipe->remaining; if (!rem) return 2; @@ -294,7 +294,6 @@ static void process_setup_packet(uint8_t rhport) setup_packet[3] = USB0.USBLENG; USB0.INTSTS0.WORD = ~USB_IS0_VALID; dcd_event_setup_received(rhport, (const uint8_t*)&setup_packet[0], true); - // TU_LOG1("S\r\n"); } static void process_status_completion(uint8_t rhport) @@ -309,7 +308,6 @@ static void process_status_completion(uint8_t rhport) ep_addr = tu_edpt_addr(0, TUSB_DIR_OUT); } dcd_event_xfer_complete(rhport, ep_addr, 0, XFER_RESULT_SUCCESS, true); - // TU_LOG1("C\r\n"); } static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) @@ -317,11 +315,11 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, (void)rhport; pipe_state_t *pipe = &_dcd.pipe[0]; - /* set fifo direction */ - if (ep_addr) { /* IN */ + /* configure fifo direction and access unit settings */ + if (ep_addr) { /* IN, 2 bytes */ USB0.CFIFOSEL.WORD = USB_FIFOSEL_TX | USB_FIFOSEL_MBW_16; while (!(USB0.CFIFOSEL.WORD & USB_FIFOSEL_TX)) ; - } else { /* OUT */ + } else { /* OUT, a byte */ USB0.CFIFOSEL.WORD = USB_FIFOSEL_MBW_8; while (USB0.CFIFOSEL.WORD & USB_FIFOSEL_TX) ; } @@ -329,21 +327,18 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, pipe->addr = (uintptr_t)buffer; pipe->length = total_bytes; pipe->remaining = total_bytes; - pipe->data = USB0.DCPCTR.BIT.SQMON; if (ep_addr) { /* IN */ TU_ASSERT(USB0.DCPCTR.BIT.BSTS && (USB0.USBREQ.WORD & 0x80)); - if (write_fifo(&USB0.CFIFO.WORD, pipe, 64)) { + if (fifo_write(&USB0.CFIFO.WORD, pipe, 64)) { USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; } } USB0.DCPCTR.WORD = USB_PIPECTR_PID_BUF; - // TU_LOG1("X %x %d\r\n", ep_addr, total_bytes); } else { /* ZLP */ pipe->addr = 0; pipe->length = 0; pipe->remaining = 0; - pipe->data = USB0.DCPCTR.BIT.SQMON; USB0.DCPCTR.WORD = USB_PIPECTR_CCPL | USB_PIPECTR_PID_BUF; } return true; @@ -352,18 +347,10 @@ static bool process_edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, static void process_edpt0_bemp(uint8_t rhport) { pipe_state_t *pipe = &_dcd.pipe[0]; - unsigned data = pipe->data; - if (USB0.DCPCTR.BIT.SQMON == data) { - /* retry transfer */ - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); - if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; - return; - } const unsigned rem = pipe->remaining; if (rem > 64) { pipe->remaining = rem - 64; - pipe->data = data ^ 1; - int r = write_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); + int r = fifo_write(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64); if (r) USB0.CFIFOCTR.WORD = USB_FIFOCTR_BVAL; return; } @@ -376,7 +363,7 @@ static void process_edpt0_bemp(uint8_t rhport) static void process_edpt0_brdy(uint8_t rhport) { size_t len = USB0.CFIFOCTR.BIT.DTLN; - int cplt = read_fifo(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, len); + int cplt = fifo_read(&USB0.CFIFO.WORD, &_dcd.pipe[0], 64, len); if (cplt || (len < 64)) { if (2 != cplt) { USB0.CFIFOCTR.WORD = USB_FIFOCTR_BCLR; @@ -407,7 +394,7 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, if (dir) { /* IN */ USB0.D0FIFOSEL.WORD = num | USB_FIFOSEL_MBW_16; while (!(USB0.D0FIFOSEL.BIT.CURPIPE != num)) ; - int r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); + int r = fifo_write(&USB0.D0FIFO.WORD, pipe, mps); if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; USB0.D0FIFOSEL.WORD = 0; } else { @@ -428,11 +415,29 @@ static bool process_pipe_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, static void process_pipe_brdy(uint8_t rhport, unsigned num) { pipe_state_t *pipe = &_dcd.pipe[num]; - if (!tu_edpt_dir(pipe->ep)) { + if (tu_edpt_dir(pipe->ep)) { /* IN */ + select_pipe(num, USB_FIFOSEL_MBW_16); + const unsigned mps = USB0.PIPEMAXP.WORD; + unsigned rem = pipe->remaining; + rem -= TU_MIN(rem, mps); + pipe->remaining = rem; + if (rem) { + int r = 0; + r = fifo_write(&USB0.D0FIFO.WORD, pipe, mps); + if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; + USB0.D0FIFOSEL.WORD = 0; + return; + } + USB0.D0FIFOSEL.WORD = 0; + pipe->addr = 0; + pipe->remaining = 0; + dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, + XFER_RESULT_SUCCESS, true); + } else { const unsigned ctr = select_pipe(num, USB_FIFOSEL_MBW_8); const unsigned len = ctr & USB_FIFOCTR_DTLN; const unsigned mps = USB0.PIPEMAXP.WORD; - int cplt = read_fifo(&USB0.D0FIFO.WORD, pipe, mps, len); + int cplt = fifo_read(&USB0.D0FIFO.WORD, pipe, mps, len); if (cplt || (len < mps)) { if (2 != cplt) { USB0.D0FIFO.WORD = USB_FIFOCTR_BCLR; @@ -444,24 +449,6 @@ static void process_pipe_brdy(uint8_t rhport, unsigned num) return; } USB0.D0FIFOSEL.WORD = 0; - } else { - select_pipe(num, USB_FIFOSEL_MBW_16); - const unsigned mps = USB0.PIPEMAXP.WORD; - unsigned rem = pipe->remaining; - rem -= TU_MIN(rem, mps); - pipe->remaining = rem; - if (rem) { - int r = 0; - r = write_fifo(&USB0.D0FIFO.WORD, pipe, mps); - if (r) USB0.D0FIFOCTR.WORD = USB_FIFOCTR_BVAL; - USB0.D0FIFOSEL.WORD = 0; - return; - } - USB0.D0FIFOSEL.WORD = 0; - pipe->addr = 0; - pipe->remaining = 0; - dcd_event_xfer_complete(rhport, pipe->ep, pipe->length, - XFER_RESULT_SUCCESS, true); } } @@ -492,7 +479,6 @@ static void process_bus_reset(uint8_t rhport) } tu_varclr(&_dcd); dcd_event_bus_reset(rhport, TUSB_SPEED_FULL, true); - // TU_LOG1("R\r\n"); } static void process_set_address(uint8_t rhport) @@ -674,10 +660,14 @@ void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr) dcd_int_disable(rhport); *ctr = USB_PIPECTR_SQCLR; - if (ep_addr & TUSB_DIR_IN_MASK) { + if (tu_edpt_dir(ep_addr)) { /* IN */ *ctr = USB_PIPECTR_PID_BUF; } else { - /* TODO */ + const unsigned num = _dcd.ep[0][tu_edpt_number(ep_addr)]; + USB0.PIPESEL.WORD = num; + if (USB0.PIPECFG.BIT.TYPE != 1) { + *ctr = USB_PIPECTR_PID_BUF; + } } dcd_int_enable(rhport); } From 30687daf9b769f7795e4b17b9c7f8b88d3d11690 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Sun, 28 Mar 2021 16:45:53 +0900 Subject: [PATCH 14/20] added a submodule dependency --- hw/bsp/gr_citrus/board.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/gr_citrus/board.mk index 06262184..9804f835 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/gr_citrus/board.mk @@ -1,3 +1,5 @@ +DEPS_SUBMODULES += hw/mcu/renesas + CFLAGS += \ -nostartfiles \ -ffunction-sections \ From 5a0c594c719a1bd86bf49ad60175be4d51154655 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 29 Mar 2021 23:54:44 +0700 Subject: [PATCH 15/20] move rx63n into its own family --- hw/bsp/{ => rx63n/boards}/gr_citrus/board.mk | 4 ++-- hw/bsp/{ => rx63n/boards}/gr_citrus/gr_citrus.c | 0 hw/bsp/{ => rx63n/boards}/gr_citrus/hwinit.c | 0 hw/bsp/{ => rx63n/boards}/gr_citrus/r5f5631fd.ld | 0 hw/bsp/rx63n/family.mk | 1 + 5 files changed, 3 insertions(+), 2 deletions(-) rename hw/bsp/{ => rx63n/boards}/gr_citrus/board.mk (94%) rename hw/bsp/{ => rx63n/boards}/gr_citrus/gr_citrus.c (100%) rename hw/bsp/{ => rx63n/boards}/gr_citrus/hwinit.c (100%) rename hw/bsp/{ => rx63n/boards}/gr_citrus/r5f5631fd.ld (100%) create mode 100644 hw/bsp/rx63n/family.mk diff --git a/hw/bsp/gr_citrus/board.mk b/hw/bsp/rx63n/boards/gr_citrus/board.mk similarity index 94% rename from hw/bsp/gr_citrus/board.mk rename to hw/bsp/rx63n/boards/gr_citrus/board.mk index 9804f835..e33f3b50 100644 --- a/hw/bsp/gr_citrus/board.mk +++ b/hw/bsp/rx63n/boards/gr_citrus/board.mk @@ -35,14 +35,14 @@ endif MCU_DIR = hw/mcu/renesas/rx63n # All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/r5f5631fd.ld +LD_FILE = $(BOARD_PATH)/r5f5631fd.ld SRC_C += \ src/portable/renesas/usba/dcd_usba.c \ $(MCU_DIR)/vects.c INC += \ - $(TOP)/hw/bsp/$(BOARD) \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/$(MCU_DIR) SRC_S += $(MCU_DIR)/start.S diff --git a/hw/bsp/gr_citrus/gr_citrus.c b/hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c similarity index 100% rename from hw/bsp/gr_citrus/gr_citrus.c rename to hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c diff --git a/hw/bsp/gr_citrus/hwinit.c b/hw/bsp/rx63n/boards/gr_citrus/hwinit.c similarity index 100% rename from hw/bsp/gr_citrus/hwinit.c rename to hw/bsp/rx63n/boards/gr_citrus/hwinit.c diff --git a/hw/bsp/gr_citrus/r5f5631fd.ld b/hw/bsp/rx63n/boards/gr_citrus/r5f5631fd.ld similarity index 100% rename from hw/bsp/gr_citrus/r5f5631fd.ld rename to hw/bsp/rx63n/boards/gr_citrus/r5f5631fd.ld diff --git a/hw/bsp/rx63n/family.mk b/hw/bsp/rx63n/family.mk new file mode 100644 index 00000000..d3c743ed --- /dev/null +++ b/hw/bsp/rx63n/family.mk @@ -0,0 +1 @@ +include $(TOP)/$(BOARD_PATH)/board.mk \ No newline at end of file From 94d29d8578cd0baf2c629e0f9455cebd7c033896 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 30 Mar 2021 00:06:06 +0700 Subject: [PATCH 16/20] add build-renesas for rx63n --- .github/workflows/build.yml | 67 +++++++++++++++++++++++++++++++++++++ 1 file changed, 67 insertions(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 0f2b9ea3..3e50980c 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -267,6 +267,73 @@ jobs: asset_name: ${{ matrix.family }}-tinyusb-${{ github.event.release.tag_name }}-examples.zip asset_content_type: application/zip + # --------------------------------------- + # Build Renesas family + # --------------------------------------- + build-renesas: + runs-on: ubuntu-latest + strategy: + fail-fast: false + matrix: + family: + # Alphabetical order + - 'rx63n' + steps: + - name: Setup Python + uses: actions/setup-python@v2 + + - name: Checkout TinyUSB + uses: actions/checkout@v2 + + - name: Checkout common submodules in lib + run: git submodule update --init lib/FreeRTOS-Kernel lib/lwip + + - name: Set Toolchain URL + run: echo >> $GITHUB_ENV TOOLCHAIN_URL=http://gcc-renesas.com/downloads/get.php?f=rx/8.3.0.202004-gnurx/gcc-8.3.0.202004-GNURX-ELF.run + + - name: Cache Toolchain + uses: actions/cache@v2 + id: cache-toolchain + with: + path: ~/cache/ + key: ${{ runner.os }}-21-03-30-${{ env.TOOLCHAIN_URL }} + + - name: Install Toolchain + if: steps.cache-toolchain.outputs.cache-hit != 'true' + run: | + mkdir -p ~/cache/toolchain/gnurx + wget --progress=dot:mega $TOOLCHAIN_URL -O toolchain.run + chmod +x toolchain.run + ./toolchain.run -p ~/cache/toolchain/gnurx -y + + - name: Set Toolchain Path + run: echo >> $GITHUB_PATH `echo ~/cache/toolchain/*/bin` + + - name: Build + run: python3 tools/build_family.py ${{ matrix.family }} + + - uses: actions/upload-artifact@v2 + with: + name: ${{ matrix.family }}-tinyusb-examples + path: _bin/ + + - name: Create Release Asset + if: ${{ github.event_name == 'release' }} + run: | + cd _bin/ + zip -r ../${{ matrix.family }}-tinyusb-${{ github.event.release.tag_name }}-examples.zip * + + - name: Upload Release Asset + uses: actions/upload-release-asset@v1 + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + if: ${{ github.event_name == 'release' }} + with: + upload_url: ${{ github.event.release.upload_url }} + asset_path: ${{ matrix.family }}-tinyusb-${{ github.event.release.tag_name }}-examples.zip + asset_name: ${{ matrix.family }}-tinyusb-${{ github.event.release.tag_name }}-examples.zip + asset_content_type: application/zip + # --------------------------------------- # Build all no-family (opharned) boards # --------------------------------------- From 74c8887c8eb22c7bc457dc7e4381061241d2fa84 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Wed, 31 Mar 2021 21:50:53 +0900 Subject: [PATCH 17/20] removed a submodule for Renesas --- .gitmodules | 3 --- hw/mcu/renesas | 1 - 2 files changed, 4 deletions(-) delete mode 160000 hw/mcu/renesas diff --git a/.gitmodules b/.gitmodules index e075e0c6..1a5ae2c5 100644 --- a/.gitmodules +++ b/.gitmodules @@ -116,6 +116,3 @@ [submodule "hw/mcu/silabs/cmsis-dfp-efm32gg12b"] path = hw/mcu/silabs/cmsis-dfp-efm32gg12b url = https://github.com/cmsis-packs/cmsis-dfp-efm32gg12b -[submodule "hw/mcu/renesas"] - path = hw/mcu/renesas - url = https://github.com/kkitayam/rx_device.git diff --git a/hw/mcu/renesas b/hw/mcu/renesas deleted file mode 160000 index 4a51dfe6..00000000 --- a/hw/mcu/renesas +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 4a51dfe6ecdf936d2d89f223f069e24a2d109207 From 25057022e3bb74097849e86c90f0eb4b35b90394 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Wed, 31 Mar 2021 21:53:15 +0900 Subject: [PATCH 18/20] add a submodule of Renesas RX family to `hw/mcu/renesas/rx` --- .gitmodules | 3 +++ hw/bsp/rx63n/boards/gr_citrus/board.mk | 4 ++-- hw/mcu/renesas/rx | 1 + 3 files changed, 6 insertions(+), 2 deletions(-) create mode 160000 hw/mcu/renesas/rx diff --git a/.gitmodules b/.gitmodules index 1a5ae2c5..c0dd871f 100644 --- a/.gitmodules +++ b/.gitmodules @@ -116,3 +116,6 @@ [submodule "hw/mcu/silabs/cmsis-dfp-efm32gg12b"] path = hw/mcu/silabs/cmsis-dfp-efm32gg12b url = https://github.com/cmsis-packs/cmsis-dfp-efm32gg12b +[submodule "hw/mcu/renesas/rx"] + path = hw/mcu/renesas/rx + url = https://github.com/kkitayam/rx_device.git diff --git a/hw/bsp/rx63n/boards/gr_citrus/board.mk b/hw/bsp/rx63n/boards/gr_citrus/board.mk index e33f3b50..feab5b5e 100644 --- a/hw/bsp/rx63n/boards/gr_citrus/board.mk +++ b/hw/bsp/rx63n/boards/gr_citrus/board.mk @@ -1,4 +1,4 @@ -DEPS_SUBMODULES += hw/mcu/renesas +DEPS_SUBMODULES += hw/mcu/renesas/rx CFLAGS += \ -nostartfiles \ @@ -32,7 +32,7 @@ CFLAGS += -nostdinc \ LIBS += -loptc -loptm endif -MCU_DIR = hw/mcu/renesas/rx63n +MCU_DIR = hw/mcu/renesas/rx/rx63n # All source paths should be relative to the top level. LD_FILE = $(BOARD_PATH)/r5f5631fd.ld diff --git a/hw/mcu/renesas/rx b/hw/mcu/renesas/rx new file mode 160000 index 00000000..4a51dfe6 --- /dev/null +++ b/hw/mcu/renesas/rx @@ -0,0 +1 @@ +Subproject commit 4a51dfe6ecdf936d2d89f223f069e24a2d109207 From ff2978d95fe80ec7abcabbc6c5a451f6b998dae2 Mon Sep 17 00:00:00 2001 From: kkitayam <45088311+kkitayam@users.noreply.github.com> Date: Wed, 31 Mar 2021 22:15:03 +0900 Subject: [PATCH 19/20] added comments for JLink connection work. --- hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c | 32 +++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c b/hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c index aadd4139..6697012a 100644 --- a/hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c +++ b/hw/bsp/rx63n/boards/gr_citrus/gr_citrus.c @@ -24,6 +24,38 @@ * This file is part of the TinyUSB stack. */ +/* How to connect JLink and GR-CITRUS + * + * GR-CITRUS needs to solder some pads to enable JTAG interface. + * - Short the following pads individually with solder. + * - J4 + * - J5 + * - Short EMLE pad and 3.3V(GR-CITRUS pin name) with a wire. + * + * The pads are [the back side of GR-CITRUS](https://www.slideshare.net/MinaoYamamoto/grcitrusrx631/2). + * + * Connet the pins between GR-CITRUS and JLink as follows. + * + * | JTAG Function | GR-CITRUS pin name| JLink pin No.| note | + * |:-------------:|:-----------------:|:------------:|:--------:| + * | VTref | 3.3V | 1 | | + * | TRST | 5 | 3 | | + * | GND | GND | 4 | | + * | TDI | 3 | 5 | | + * | TMS | 2 | 7 | | + * | TCK | 14 | 9 | short J4 | + * | TDO | 9 | 13 | short J5 | + * | nRES | RST | 15 | | + * + * JLink firmware needs to update to V6.96 or newer version to avoid + * [a bug](https://forum.segger.com/index.php/Thread/7758-SOLVED-Bug-in-JLink-from-V6-88b-regarding-RX65N) + * regarding downloading. + * + * When using SEGGER RTT, `RX_NEWLIB=0` should be added to make command arguments. + * The option is used to change the C runtime library to `optlib` from `newlib`. + * RTT may not work with `newlib`. + */ + #include "../board.h" #include "iodefine.h" #include "interrupt_handlers.h" From 1d8a79ef4f4f6603ea8102b08613e97e18ed7eb6 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 31 Mar 2021 20:50:08 +0700 Subject: [PATCH 20/20] remove NVIC_SystemReset() in freertos examples --- examples/device/cdc_msc_freertos/src/main.c | 4 +--- examples/device/hid_composite_freertos/src/main.c | 4 +--- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/examples/device/cdc_msc_freertos/src/main.c b/examples/device/cdc_msc_freertos/src/main.c index abb95f4f..ccff2e0f 100644 --- a/examples/device/cdc_msc_freertos/src/main.c +++ b/examples/device/cdc_msc_freertos/src/main.c @@ -97,10 +97,8 @@ int main(void) // skip starting scheduler (and return) for ESP32-S2 #if CFG_TUSB_MCU != OPT_MCU_ESP32S2 vTaskStartScheduler(); -#if CFG_TUSB_MCU != OPT_MCU_RX63X - NVIC_SystemReset(); -#endif #endif + return 0; } diff --git a/examples/device/hid_composite_freertos/src/main.c b/examples/device/hid_composite_freertos/src/main.c index 1b42cee4..37b4a0cf 100644 --- a/examples/device/hid_composite_freertos/src/main.c +++ b/examples/device/hid_composite_freertos/src/main.c @@ -98,10 +98,8 @@ int main(void) // skip starting scheduler (and return) for ESP32-S2 #if CFG_TUSB_MCU != OPT_MCU_ESP32S2 vTaskStartScheduler(); -#if CFG_TUSB_MCU != OPT_MCU_RX63X - NVIC_SystemReset(); -#endif #endif + return 0; }