diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 8ef19b0a0..1ef0bf5ea 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -44,6 +44,7 @@ jobs: - 'lpc18' - 'lpc54' - 'lpc55' + - 'mm32' - 'nrf' - 'rp2040' - 'samd11' diff --git a/.github/workflows/build_esp.yml b/.github/workflows/build_esp.yml index 25f4e68f8..93d582361 100644 --- a/.github/workflows/build_esp.yml +++ b/.github/workflows/build_esp.yml @@ -18,8 +18,7 @@ jobs: # ESP32-S2 - 'espressif_saola_1' # ESP32-S3 - # latest IDF does not define USB0 in linker - #- 'espressif_addax_1' + - 'espressif_addax_1' steps: - name: Setup Python diff --git a/.gitmodules b/.gitmodules index 4c86fd55c..5f5bee56c 100644 --- a/.gitmodules +++ b/.gitmodules @@ -121,9 +121,9 @@ [submodule "hw/mcu/nxp/nxp_sdk"] path = hw/mcu/nxp/nxp_sdk url = https://github.com/hathach/nxp_sdk.git -[submodule "hw/mcu/mindmotion/mm32sdk"] - path = hw/mcu/mindmotion/mm32sdk - url = https://github.com/zhangslice/mm32sdk.git [submodule "hw/mcu/gd/nuclei-sdk"] path = hw/mcu/gd/nuclei-sdk url = https://github.com/Nuclei-Software/nuclei-sdk.git +[submodule "hw/mcu/mindmotion/mm32sdk"] + path = hw/mcu/mindmotion/mm32sdk + url = https://github.com/hathach/mm32sdk.git diff --git a/examples/device/cdc_msc_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h b/examples/device/cdc_msc_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h index 85d86b329..ccb620720 100644 --- a/examples/device/cdc_msc_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h +++ b/examples/device/cdc_msc_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h @@ -46,10 +46,15 @@ #include "bsp/board_mcu.h" #if CFG_TUSB_MCU == OPT_MCU_ESP32S2 || CFG_TUSB_MCU == OPT_MCU_ESP32S3 -#error "ESP32-Sx should use IDF's FreeRTOSConfig.h" + #error "ESP32-Sx should use IDF's FreeRTOSConfig.h" #endif -extern uint32_t SystemCoreClock; +// TODO fix later +#if CFG_TUSB_MCU == OPT_MCU_MM32F327X + extern u32 SystemCoreClock; +#else + extern uint32_t SystemCoreClock; +#endif /* Cortex M23/M33 port configuration. */ #define configENABLE_MPU 0 diff --git a/examples/device/hid_composite_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h b/examples/device/hid_composite_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h index 85d86b329..bfdf1e926 100644 --- a/examples/device/hid_composite_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h +++ b/examples/device/hid_composite_freertos/src/FreeRTOSConfig/FreeRTOSConfig.h @@ -49,7 +49,12 @@ #error "ESP32-Sx should use IDF's FreeRTOSConfig.h" #endif -extern uint32_t SystemCoreClock; +#if CFG_TUSB_MCU == OPT_MCU_MM32F327X + // TODO fix/remove later + extern u32 SystemCoreClock; +#else + extern uint32_t SystemCoreClock; +#endif /* Cortex M23/M33 port configuration. */ #define configENABLE_MPU 0 diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index 8cc50c808..a4d57597c 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -134,6 +134,8 @@ #elif CFG_TUSB_MCU == OPT_MCU_GD32VF103 #include "gd32vf103.h" +#elif CFG_TUSB_MCU == OPT_MCU_MM32F327X + #include "mm32_device.h" #else #error "Missing MCU header" #endif diff --git a/hw/bsp/mm32/boards/mm32f327x_mb39/board.mk b/hw/bsp/mm32/boards/mm32f327x_mb39/board.mk new file mode 100644 index 000000000..b7663926f --- /dev/null +++ b/hw/bsp/mm32/boards/mm32f327x_mb39/board.mk @@ -0,0 +1,8 @@ +LD_FILE = $(BOARD_PATH)/flash.ld +SRC_S += $(SDK_DIR)/mm32f327x/MM32F327x/Source/GCC_StartAsm/startup_mm32m3ux_u_gcc.S + +# For flash-jlink target +#JLINK_DEVICE = stm32f411ve + +# flash target using on-board stlink +#flash: flash-jlink diff --git a/hw/bsp/mm32/boards/mm32f327x_mb39/flash.ld b/hw/bsp/mm32/boards/mm32f327x_mb39/flash.ld new file mode 100644 index 000000000..d96d6e43d --- /dev/null +++ b/hw/bsp/mm32/boards/mm32f327x_mb39/flash.ld @@ -0,0 +1,163 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 MM32 SE TEAM + * + * 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. + */ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x2001FFFF; /* end of RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/hw/bsp/mm32/boards/mm32f327x_mb39/mm32f327x_mb39.c b/hw/bsp/mm32/boards/mm32f327x_mb39/mm32f327x_mb39.c new file mode 100644 index 000000000..cff7bc15e --- /dev/null +++ b/hw/bsp/mm32/boards/mm32f327x_mb39/mm32f327x_mb39.c @@ -0,0 +1,172 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 MM32 SE TEAM + * + * 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 "mm32_device.h" +#include "hal_conf.h" +#include "tusb.h" +#include "../board.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler (void) +{ + tud_int_handler(0); + +} +void USB_DeviceClockInit (void) +{ + /* Select USBCLK source */ + // RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_Div1); + RCC->CFGR &= ~(0x3 << 22); + RCC->CFGR |= (0x1 << 22); + + /* Enable USB clock */ + RCC->AHB2ENR |= 0x1 << 7; +} +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ +// LED + +void board_led_write (bool state); +extern u32 SystemCoreClock; +const int baudrate = 115200; + +void board_init (void) +{ +// usb clock + USB_DeviceClockInit(); + + if ( SysTick_Config(SystemCoreClock / 1000) ) + { + while ( 1 ) + ; + } + NVIC_SetPriority(SysTick_IRQn, 0x0); + + // LED + GPIO_InitTypeDef GPIO_InitStruct; + RCC_AHBPeriphClockCmd(RCC_AHBENR_GPIOA, ENABLE); + GPIO_StructInit(&GPIO_InitStruct); + GPIO_PinAFConfig(GPIOA, GPIO_PinSource15, GPIO_AF_15); //Disable JTDI AF to AF15 + + GPIO_InitStruct.GPIO_Pin = GPIO_Pin_15; + GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStruct.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_Init(GPIOA, &GPIO_InitStruct); + + board_led_write(true); + + // UART + UART_InitTypeDef UART_InitStruct; + + RCC_APB2PeriphClockCmd(RCC_APB2ENR_UART1, ENABLE); //enableUART1,GPIOAclock + RCC_AHBPeriphClockCmd(RCC_AHBENR_GPIOA, ENABLE); // + //UART initialset + + GPIO_PinAFConfig(GPIOA, GPIO_PinSource9, GPIO_AF_7); + GPIO_PinAFConfig(GPIOA, GPIO_PinSource10, GPIO_AF_7); + + UART_StructInit(&UART_InitStruct); + UART_InitStruct.UART_BaudRate = baudrate; + UART_InitStruct.UART_WordLength = UART_WordLength_8b; + UART_InitStruct.UART_StopBits = UART_StopBits_1; //one stopbit + UART_InitStruct.UART_Parity = UART_Parity_No; //none odd-even verify bit + UART_InitStruct.UART_HardwareFlowControl = UART_HardwareFlowControl_None; //No hardware flow control + UART_InitStruct.UART_Mode = UART_Mode_Rx | UART_Mode_Tx; // receive and sent mode + + UART_Init(UART1, &UART_InitStruct); //initial uart 1 + UART_Cmd(UART1, ENABLE); //enable uart 1 + + //UART1_TX GPIOA.9 + GPIO_StructInit(&GPIO_InitStruct); + GPIO_InitStruct.GPIO_Pin = GPIO_Pin_9; + GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(GPIOA, &GPIO_InitStruct); + + //UART1_RX GPIOA.10 + GPIO_InitStruct.GPIO_Pin = GPIO_Pin_5; + GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IPU; + GPIO_Init(GPIOA, &GPIO_InitStruct); + +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write (bool state) +{ + state ? (GPIO_ResetBits(GPIOA, GPIO_Pin_15)) : (GPIO_SetBits(GPIOA, GPIO_Pin_15)); +} + +uint32_t board_button_read (void) +{ + return 0; +} + +int board_uart_read (uint8_t *buf, int len) +{ + (void) buf; + (void) len; + return 0; +} + +int board_uart_write (void const *buf, int len) +{ + const char *buff = buf; + while ( len ) + { + while ( (UART1->CSR & UART_IT_TXIEN) == 0 ) + ; //The loop is sent until it is finished + UART1->TDR = (*buff & 0xFF); + buff++; + len--; + } + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis (void) +{ + return system_ticks; +} +#endif + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/mm32/family.mk b/hw/bsp/mm32/family.mk new file mode 100644 index 000000000..3273ff870 --- /dev/null +++ b/hw/bsp/mm32/family.mk @@ -0,0 +1,36 @@ +UF2_FAMILY_ID = 0x0 +SDK_DIR = hw/mcu/mindmotion/mm32sdk +DEPS_SUBMODULES += lib/CMSIS_5 $(SDK_DIR) + +include $(TOP)/$(BOARD_PATH)/board.mk + +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m3 \ + -mfloat-abi=soft \ + -nostdlib -nostartfiles \ + -DCFG_TUSB_MCU=OPT_MCU_MM32F327X + +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=unused-parameter -Wno-error=maybe-uninitialized + +SRC_C += \ + src/portable/mindmotion/mm32/dcd_mm32f327x_otg.c \ + $(SDK_DIR)/mm32f327x/MM32F327x/Source/system_mm32f327x.c \ + $(SDK_DIR)/mm32f327x/MM32F327x/HAL_Lib/Src/hal_gpio.c \ + $(SDK_DIR)/mm32f327x/MM32F327x/HAL_Lib/Src/hal_rcc.c \ + $(SDK_DIR)/mm32f327x/MM32F327x/HAL_Lib/Src/hal_uart.c \ + +INC += \ + $(TOP)/$(BOARD_PATH) \ + $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ + $(TOP)/$(SDK_DIR)/mm32f327x/MM32F327x/Include \ + $(TOP)/$(SDK_DIR)/mm32f327x/MM32F327x/HAL_Lib/Inc + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM3 + +# flash target using on-board +flash: flash-jlink diff --git a/hw/mcu/mindmotion/mm32sdk b/hw/mcu/mindmotion/mm32sdk index b6b99de3a..708a71529 160000 --- a/hw/mcu/mindmotion/mm32sdk +++ b/hw/mcu/mindmotion/mm32sdk @@ -1 +1 @@ -Subproject commit b6b99de3ab26218784ec158488bdd91377288f94 +Subproject commit 708a7152952ac595d24837069dcc0f7f59a4c30b diff --git a/src/class/cdc/cdc_device.h b/src/class/cdc/cdc_device.h index 7ff757add..fbc7162a3 100644 --- a/src/class/cdc/cdc_device.h +++ b/src/class/cdc/cdc_device.h @@ -82,7 +82,7 @@ int32_t tud_cdc_n_read_char (uint8_t itf); void tud_cdc_n_read_flush (uint8_t itf); // Get a byte from FIFO at the specified position without removing it -bool tud_cdc_n_peek (uint8_t itf, uint8_t* u8); +bool tud_cdc_n_peek (uint8_t itf, uint8_t* ui8); // Write bytes to TX FIFO, data may remain in the FIFO for a while uint32_t tud_cdc_n_write (uint8_t itf, void const* buffer, uint32_t bufsize); @@ -116,7 +116,7 @@ static inline uint32_t tud_cdc_available (void); static inline int32_t tud_cdc_read_char (void); static inline uint32_t tud_cdc_read (void* buffer, uint32_t bufsize); static inline void tud_cdc_read_flush (void); -static inline bool tud_cdc_peek (uint8_t* u8); +static inline bool tud_cdc_peek (uint8_t* ui8); static inline uint32_t tud_cdc_write_char (char ch); static inline uint32_t tud_cdc_write (void const* buffer, uint32_t bufsize); @@ -206,9 +206,9 @@ static inline void tud_cdc_read_flush (void) tud_cdc_n_read_flush(0); } -static inline bool tud_cdc_peek (uint8_t* u8) +static inline bool tud_cdc_peek (uint8_t* ui8) { - return tud_cdc_n_peek(0, u8); + return tud_cdc_n_peek(0, ui8); } static inline uint32_t tud_cdc_write_char (char ch) diff --git a/src/class/vendor/vendor_device.h b/src/class/vendor/vendor_device.h index 844693c68..d71c2a3e9 100644 --- a/src/class/vendor/vendor_device.h +++ b/src/class/vendor/vendor_device.h @@ -44,7 +44,7 @@ bool tud_vendor_n_mounted (uint8_t itf); uint32_t tud_vendor_n_available (uint8_t itf); uint32_t tud_vendor_n_read (uint8_t itf, void* buffer, uint32_t bufsize); -bool tud_vendor_n_peek (uint8_t itf, uint8_t* u8); +bool tud_vendor_n_peek (uint8_t itf, uint8_t* ui8); void tud_vendor_n_read_flush (uint8_t itf); uint32_t tud_vendor_n_write (uint8_t itf, void const* buffer, uint32_t bufsize); @@ -59,7 +59,7 @@ uint32_t tud_vendor_n_write_str (uint8_t itf, char const* str); static inline bool tud_vendor_mounted (void); static inline uint32_t tud_vendor_available (void); static inline uint32_t tud_vendor_read (void* buffer, uint32_t bufsize); -static inline bool tud_vendor_peek (uint8_t* u8); +static inline bool tud_vendor_peek (uint8_t* ui8); static inline void tud_vendor_read_flush (void); static inline uint32_t tud_vendor_write (void const* buffer, uint32_t bufsize); static inline uint32_t tud_vendor_write_str (char const* str); @@ -96,9 +96,9 @@ static inline uint32_t tud_vendor_read (void* buffer, uint32_t bufsize) return tud_vendor_n_read(0, buffer, bufsize); } -static inline bool tud_vendor_peek (uint8_t* u8) +static inline bool tud_vendor_peek (uint8_t* ui8) { - return tud_vendor_n_peek(0, u8); + return tud_vendor_n_peek(0, ui8); } static inline void tud_vendor_read_flush(void) diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index 1899b35cc..fc4d3bc62 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -38,18 +38,18 @@ #define TU_MIN(_x, _y) ( ( (_x) < (_y) ) ? (_x) : (_y) ) #define TU_MAX(_x, _y) ( ( (_x) > (_y) ) ? (_x) : (_y) ) -#define TU_U16_HIGH(u16) ((uint8_t) (((u16) >> 8) & 0x00ff)) -#define TU_U16_LOW(u16) ((uint8_t) ((u16) & 0x00ff)) -#define U16_TO_U8S_BE(u16) TU_U16_HIGH(u16), TU_U16_LOW(u16) -#define U16_TO_U8S_LE(u16) TU_U16_LOW(u16), TU_U16_HIGH(u16) +#define TU_U16_HIGH(_u16) ((uint8_t) (((_u16) >> 8) & 0x00ff)) +#define TU_U16_LOW(_u16) ((uint8_t) ((_u16) & 0x00ff)) +#define U16_TO_U8S_BE(_u16) TU_U16_HIGH(_u16), TU_U16_LOW(_u16) +#define U16_TO_U8S_LE(_u16) TU_U16_LOW(_u16), TU_U16_HIGH(_u16) -#define TU_U32_BYTE3(u32) ((uint8_t) ((((uint32_t) u32) >> 24) & 0x000000ff)) // MSB -#define TU_U32_BYTE2(u32) ((uint8_t) ((((uint32_t) u32) >> 16) & 0x000000ff)) -#define TU_U32_BYTE1(u32) ((uint8_t) ((((uint32_t) u32) >> 8) & 0x000000ff)) -#define TU_U32_BYTE0(u32) ((uint8_t) (((uint32_t) u32) & 0x000000ff)) // LSB +#define TU_U32_BYTE3(_u32) ((uint8_t) ((((uint32_t) _u32) >> 24) & 0x000000ff)) // MSB +#define TU_U32_BYTE2(_u32) ((uint8_t) ((((uint32_t) _u32) >> 16) & 0x000000ff)) +#define TU_U32_BYTE1(_u32) ((uint8_t) ((((uint32_t) _u32) >> 8) & 0x000000ff)) +#define TU_U32_BYTE0(_u32) ((uint8_t) (((uint32_t) _u32) & 0x000000ff)) // LSB -#define U32_TO_U8S_BE(u32) TU_U32_BYTE3(u32), TU_U32_BYTE2(u32), TU_U32_BYTE1(u32), TU_U32_BYTE0(u32) -#define U32_TO_U8S_LE(u32) TU_U32_BYTE0(u32), TU_U32_BYTE1(u32), TU_U32_BYTE2(u32), TU_U32_BYTE3(u32) +#define U32_TO_U8S_BE(_u32) TU_U32_BYTE3(_u32), TU_U32_BYTE2(_u32), TU_U32_BYTE1(_u32), TU_U32_BYTE0(_u32) +#define U32_TO_U8S_LE(_u32) TU_U32_BYTE0(_u32), TU_U32_BYTE1(_u32), TU_U32_BYTE2(_u32), TU_U32_BYTE3(_u32) #define TU_BIT(n) (1UL << (n)) @@ -105,16 +105,13 @@ TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u16(uint8_t high, uint8_t low) return (uint16_t) ((((uint16_t) high) << 8) | low); } -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte3(uint32_t u32) { return TU_U32_BYTE3(u32); } -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte2(uint32_t u32) { return TU_U32_BYTE2(u32); } -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte1(uint32_t u32) { return TU_U32_BYTE1(u32); } -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte0(uint32_t u32) { return TU_U32_BYTE0(u32); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte3(uint32_t ui32) { return TU_U32_BYTE3(ui32); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte2(uint32_t ui32) { return TU_U32_BYTE2(ui32); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte1(uint32_t ui32) { return TU_U32_BYTE1(ui32); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte0(uint32_t ui32) { return TU_U32_BYTE0(ui32); } -TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u32_high16(uint32_t u32) { return (uint16_t) (u32 >> 16); } -TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u32_low16 (uint32_t u32) { return (uint16_t) (u32 & 0x0000ffffu); } - -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_high(uint16_t u16) { return TU_U16_HIGH(u16); } -TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_low (uint16_t u16) { return TU_U16_LOW(u16); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_high(uint16_t ui16) { return TU_U16_HIGH(ui16); } +TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_low (uint16_t ui16) { return TU_U16_LOW(ui16); } //------------- Bits -------------// TU_ATTR_ALWAYS_INLINE static inline uint32_t tu_bit_set (uint32_t value, uint8_t pos) { return value | TU_BIT(pos); } diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index a35fc0ac5..44f2cc1d6 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -63,6 +63,9 @@ #elif TU_CHECK_MCU(MKL25ZXX) || TU_CHECK_MCU(K32L2BXX) #define DCD_ATTR_ENDPOINT_MAX 16 +#elif TU_CHECK_MCU(MM32F327X) + #define DCD_ATTR_ENDPOINT_MAX 16 + //------------- Nordic -------------// #elif TU_CHECK_MCU(NRF5X) // 8 CBI + 1 ISO diff --git a/src/portable/mindmotion/mm32/dcd_mm32f327x_otg.c b/src/portable/mindmotion/mm32/dcd_mm32f327x_otg.c index c472f2175..6cc0fcac3 100644 --- a/src/portable/mindmotion/mm32/dcd_mm32f327x_otg.c +++ b/src/portable/mindmotion/mm32/dcd_mm32f327x_otg.c @@ -283,7 +283,7 @@ void dcd_set_address(uint8_t rhport, uint8_t dev_addr) /* Response with status first before changing device address */ dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); } -extern u32 SystemCoreClock ; +extern u32 SystemCoreClock; void dcd_remote_wakeup(uint8_t rhport) { (void) rhport;