diff --git a/.github/workflows/ci_set_matrix.py b/.github/workflows/ci_set_matrix.py
index 5584b8312..2a00e5413 100644
--- a/.github/workflows/ci_set_matrix.py
+++ b/.github/workflows/ci_set_matrix.py
@@ -16,6 +16,7 @@ family_list = {
"broadcom_32bit": ["arm-gcc"],
"broadcom_64bit": ["aarch64-gcc"],
"ch32v10x ch32v20x ch32v307 fomu gd32vf103": ["riscv-gcc"],
+ "da1469x": ["arm-gcc"],
"imxrt": ["arm-gcc", "arm-clang"],
"kinetis_k kinetis_kl kinetis_k32l2": ["arm-gcc", "arm-clang"],
"lpc11 lpc13 lpc15": ["arm-gcc", "arm-clang"],
@@ -36,7 +37,7 @@ family_list = {
"stm32f7": ["arm-gcc", "arm-clang", "arm-iar"],
"stm32g0 stm32g4 stm32h5": ["arm-gcc", "arm-clang", "arm-iar"],
"stm32h7": ["arm-gcc", "arm-clang", "arm-iar"],
- "stm32l4 stm32u5 stm32wb": ["arm-gcc", "arm-clang", "arm-iar"],
+ "stm32l0 stm32l4 stm32u5 stm32wb": ["arm-gcc", "arm-clang", "arm-iar"],
"xmc4000": ["arm-gcc"],
}
diff --git a/.idea/cmake.xml b/.idea/cmake.xml
index 1055e31d3..ec900b4a6 100644
--- a/.idea/cmake.xml
+++ b/.idea/cmake.xml
@@ -3,7 +3,7 @@
-
+
@@ -67,7 +67,7 @@
-
+
@@ -134,9 +134,10 @@
-
+
+
\ No newline at end of file
diff --git a/examples/build_system/cmake/cpu/cortex-m33-nodsp.cmake b/examples/build_system/cmake/cpu/cortex-m33-nodsp.cmake
new file mode 100644
index 000000000..b3cd743fd
--- /dev/null
+++ b/examples/build_system/cmake/cpu/cortex-m33-nodsp.cmake
@@ -0,0 +1,25 @@
+if (TOOLCHAIN STREQUAL "gcc")
+ set(TOOLCHAIN_COMMON_FLAGS
+ -mthumb
+ -mcpu=cortex-m33+nodsp
+ -mfloat-abi=hard
+ -mfpu=fpv5-sp-d16
+ )
+ set(FREERTOS_PORT GCC_ARM_CM33_NTZ_NONSECURE CACHE INTERNAL "")
+
+elseif (TOOLCHAIN STREQUAL "clang")
+ set(TOOLCHAIN_COMMON_FLAGS
+ --target=arm-none-eabi
+ -mcpu=cortex-m33+nodsp
+ -mfpu=fpv5-sp-d16
+ )
+ set(FREERTOS_PORT GCC_ARM_CM33_NTZ_NONSECURE CACHE INTERNAL "")
+
+elseif (TOOLCHAIN STREQUAL "iar")
+ set(TOOLCHAIN_COMMON_FLAGS
+ --cpu cortex-m33+nodsp
+ --fpu VFPv5-SP
+ )
+ set(FREERTOS_PORT IAR_ARM_CM33_NTZ_NONSECURE CACHE INTERNAL "")
+
+endif ()
diff --git a/hw/bsp/da14695_dk_usb/da14695_dk_usb.c b/hw/bsp/da14695_dk_usb/da14695_dk_usb.c
deleted file mode 100644
index 667b83de3..000000000
--- a/hw/bsp/da14695_dk_usb/da14695_dk_usb.c
+++ /dev/null
@@ -1,134 +0,0 @@
-/*
- * The MIT License (MIT)
- *
- * Copyright (c) 2020 Jerzy Kasenberg
- *
- * 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 "bsp/board_api.h"
-#include
-#include
-
-//--------------------------------------------------------------------+
-// Forward USB interrupt events to TinyUSB IRQ Handler
-//--------------------------------------------------------------------+
-void USB_IRQHandler(void)
-{
- tud_int_handler(0);
-}
-
-//--------------------------------------------------------------------+
-// MACRO TYPEDEF CONSTANT ENUM
-//--------------------------------------------------------------------+
-
-#define LED_PIN 33 // P1.1
-#define LED_STATE_ON 1
-#define LED_STATE_OFF (1-LED_STATE_ON)
-
-#define BUTTON_PIN 6
-
-void UnhandledIRQ(void)
-{
- CRG_TOP->SYS_CTRL_REG = 0x80;
- __BKPT(1);
- while(1);
-}
-
-// DA146xx driver function that must be called whenever VBUS changes.
-extern void tusb_vbus_changed(bool present);
-
-void board_init(void)
-{
- // LED
- hal_gpio_init_out(LED_PIN, LED_STATE_ON);
-
- hal_gpio_init_out(1, 0);
- hal_gpio_init_out(2, 0);
- hal_gpio_init_out(3, 0);
- hal_gpio_init_out(4, 0);
- hal_gpio_init_out(5, 0);
-
- // Button
- hal_gpio_init_in(BUTTON_PIN, HAL_GPIO_PULL_DOWN);
-
- // 1ms tick timer
- SysTick_Config(SystemCoreClock / 1000);
-
-#if CFG_TUD_ENABLED
- // This board is USB powered there is no need to monitor
- // VBUS line. Notify driver that VBUS is present.
- tusb_vbus_changed(true);
-
- /* Setup USB IRQ */
- NVIC_SetPriority(USB_IRQn, 2);
- NVIC_EnableIRQ(USB_IRQn);
-
- /* Use PLL96 / 2 clock not HCLK */
- CRG_TOP->CLK_CTRL_REG &= ~CRG_TOP_CLK_CTRL_REG_USB_CLK_SRC_Msk;
-
- mcu_gpio_set_pin_function(14, MCU_GPIO_MODE_INPUT, MCU_GPIO_FUNC_USB);
- mcu_gpio_set_pin_function(15, MCU_GPIO_MODE_INPUT, MCU_GPIO_FUNC_USB);
-#endif
-}
-
-//--------------------------------------------------------------------+
-// Board porting API
-//--------------------------------------------------------------------+
-
-void board_led_write(bool state)
-{
- hal_gpio_write(LED_PIN, state ? LED_STATE_ON : LED_STATE_OFF);
-}
-
-uint32_t board_button_read(void)
-{
- // button is active HIGH
- return hal_gpio_read(BUTTON_PIN);
-}
-
-int board_uart_read(uint8_t* buf, int len)
-{
- (void)buf;
- (void)len;
- return 0;
-}
-
-int board_uart_write(void const * buf, int len)
-{
- (void)buf;
- (void)len;
-
- return 0;
-}
-
-#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
diff --git a/hw/bsp/da1469x/FreeRTOSConfig/FreeRTOSConfig.h b/hw/bsp/da1469x/FreeRTOSConfig/FreeRTOSConfig.h
new file mode 100644
index 000000000..4d4379a6f
--- /dev/null
+++ b/hw/bsp/da1469x/FreeRTOSConfig/FreeRTOSConfig.h
@@ -0,0 +1,150 @@
+/*
+ * FreeRTOS Kernel V10.0.0
+ * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * 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. If you wish to use our Amazon
+ * FreeRTOS name, please do so in a fair use way that does not cause confusion.
+ *
+ * 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.
+ *
+ * http://www.FreeRTOS.org
+ * http://aws.amazon.com/freertos
+ *
+ * 1 tab == 4 spaces!
+ */
+
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
+ *
+ * See http://www.freertos.org/a00110.html.
+ *----------------------------------------------------------*/
+
+// skip if included from IAR assembler
+#ifndef __IASMARM__
+ #include "DA1469xAB.h"
+#endif
+
+/* Cortex M23/M33 port configuration. */
+#define configENABLE_MPU 0
+#define configENABLE_FPU 1
+#define configENABLE_TRUSTZONE 0
+#define configMINIMAL_SECURE_STACK_SIZE (1024)
+#define configRUN_FREERTOS_SECURE_ONLY 1
+
+#define configUSE_PREEMPTION 1
+#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
+#define configCPU_CLOCK_HZ SystemCoreClock
+#define configTICK_RATE_HZ ( 1000 )
+#define configMAX_PRIORITIES ( 5 )
+#define configMINIMAL_STACK_SIZE ( 128 )
+#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 )
+#define configMAX_TASK_NAME_LEN 16
+#define configUSE_16_BIT_TICKS 0
+#define configIDLE_SHOULD_YIELD 1
+#define configUSE_MUTEXES 1
+#define configUSE_RECURSIVE_MUTEXES 1
+#define configUSE_COUNTING_SEMAPHORES 1
+#define configQUEUE_REGISTRY_SIZE 4
+#define configUSE_QUEUE_SETS 0
+#define configUSE_TIME_SLICING 0
+#define configUSE_NEWLIB_REENTRANT 0
+#define configENABLE_BACKWARD_COMPATIBILITY 1
+#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0
+
+#define configSUPPORT_STATIC_ALLOCATION 1
+#define configSUPPORT_DYNAMIC_ALLOCATION 0
+
+/* Hook function related definitions. */
+#define configUSE_IDLE_HOOK 0
+#define configUSE_TICK_HOOK 0
+#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning
+#define configCHECK_FOR_STACK_OVERFLOW 2
+#define configCHECK_HANDLER_INSTALLATION 0
+
+/* Run time and task stats gathering related definitions. */
+#define configGENERATE_RUN_TIME_STATS 0
+#define configRECORD_STACK_HIGH_ADDRESS 1
+#define configUSE_TRACE_FACILITY 1 // legacy trace
+#define configUSE_STATS_FORMATTING_FUNCTIONS 0
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 0
+#define configMAX_CO_ROUTINE_PRIORITIES 2
+
+/* Software timer related definitions. */
+#define configUSE_TIMERS 1
+#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2)
+#define configTIMER_QUEUE_LENGTH 32
+#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
+
+/* Optional functions - most linkers will remove unused functions anyway. */
+#define INCLUDE_vTaskPrioritySet 0
+#define INCLUDE_uxTaskPriorityGet 0
+#define INCLUDE_vTaskDelete 0
+#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY
+#define INCLUDE_xResumeFromISR 0
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+#define INCLUDE_xTaskGetSchedulerState 0
+#define INCLUDE_xTaskGetCurrentTaskHandle 1
+#define INCLUDE_uxTaskGetStackHighWaterMark 0
+#define INCLUDE_xTaskGetIdleTaskHandle 0
+#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
+#define INCLUDE_pcTaskGetTaskName 0
+#define INCLUDE_eTaskGetState 0
+#define INCLUDE_xEventGroupSetBitFromISR 0
+#define INCLUDE_xTimerPendFunctionCall 0
+
+/* FreeRTOS hooks to NVIC vectors */
+#define xPortPendSVHandler PendSV_Handler
+#define xPortSysTickHandler SysTick_Handler
+#define vPortSVCHandler SVC_Handler
+
+//--------------------------------------------------------------------+
+// Interrupt nesting behavior configuration.
+//--------------------------------------------------------------------+
+
+// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header
+#define configPRIO_BITS 4
+
+/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
+#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<
#include
+#define LED_STATE_OFF (1-LED_STATE_ON)
+
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
-void USB_IRQHandler(void)
-{
+void USB_IRQHandler(void) {
tud_int_handler(0);
}
-#if CFG_TUD_ENABLED
-// DA146xx driver function that must be called whenever VBUS changes
+// DA146xx driver function that must be called whenever VBUS changes.
extern void tusb_vbus_changed(bool present);
+#if defined(NEED_VBUS_MONITOR) && CFG_TUD_ENABLED
// VBUS change interrupt handler
-void VBUS_IRQHandler(void)
-{
+void VBUS_IRQHandler(void) {
bool present = (CRG_TOP->ANA_STATUS_REG & CRG_TOP_ANA_STATUS_REG_VBUS_AVAILABLE_Msk) != 0;
// Clear VBUS interrupt
CRG_TOP->VBUS_IRQ_CLEAR_REG = 1;
@@ -54,22 +55,13 @@ void VBUS_IRQHandler(void)
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
-
-#define LED_PIN 33
-#define LED_STATE_ON 1
-#define LED_STATE_OFF 0
-
-#define BUTTON_PIN 6
-
-void UnhandledIRQ(void)
-{
+void UnhandledIRQ(void) {
CRG_TOP->SYS_CTRL_REG = 0x80;
__BKPT(1);
- while(1);
+ while (1);
}
-void board_init(void)
-{
+void board_init(void) {
// LED
hal_gpio_init_out(LED_PIN, LED_STATE_ON);
@@ -80,12 +72,13 @@ void board_init(void)
hal_gpio_init_out(5, 0);
// Button
- hal_gpio_init_in(BUTTON_PIN, HAL_GPIO_PULL_UP);
+ hal_gpio_init_in(BUTTON_PIN, BUTTON_STATE_ACTIVE ? HAL_GPIO_PULL_DOWN : HAL_GPIO_PULL_UP);
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#if CFG_TUD_ENABLED
+ #ifdef NEED_VBUS_MONITOR
// Setup interrupt for both connect and disconnect
CRG_TOP->VBUS_IRQ_MASK_REG = CRG_TOP_VBUS_IRQ_MASK_REG_VBUS_IRQ_EN_FALL_Msk |
CRG_TOP_VBUS_IRQ_MASK_REG_VBUS_IRQ_EN_RISE_Msk;
@@ -94,6 +87,10 @@ void board_init(void)
// otherwise it could go unnoticed.
NVIC_SetPendingIRQ(VBUS_IRQn);
NVIC_EnableIRQ(VBUS_IRQn);
+ #else
+ // This board is USB powered there is no need to monitor VBUS line. Notify driver that VBUS is present.
+ tusb_vbus_changed(true);
+ #endif
/* Setup USB IRQ */
NVIC_SetPriority(USB_IRQn, 2);
@@ -111,41 +108,35 @@ void board_init(void)
// Board porting API
//--------------------------------------------------------------------+
-void board_led_write(bool state)
-{
+void board_led_write(bool state) {
hal_gpio_write(LED_PIN, state ? LED_STATE_ON : LED_STATE_OFF);
}
-uint32_t board_button_read(void)
-{
- // button is active LOW
- return hal_gpio_read(BUTTON_PIN) ^ 1;
+uint32_t board_button_read(void) {
+ return BUTTON_STATE_ACTIVE == hal_gpio_read(BUTTON_PIN);
}
-int board_uart_read(uint8_t* buf, int len)
-{
- (void)buf;
- (void)len;
+int board_uart_read(uint8_t* buf, int len) {
+ (void) buf;
+ (void) len;
return 0;
}
-int board_uart_write(void const * buf, int len)
-{
- (void)buf;
- (void)len;
+int board_uart_write(void const* buf, int len) {
+ (void) buf;
+ (void) len;
return 0;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
-void SysTick_Handler(void)
-{
+
+void SysTick_Handler(void) {
system_ticks++;
}
-uint32_t board_millis(void)
-{
+uint32_t board_millis(void) {
return system_ticks;
}
#endif
diff --git a/hw/bsp/da1469x/family.cmake b/hw/bsp/da1469x/family.cmake
new file mode 100644
index 000000000..8c89141fe
--- /dev/null
+++ b/hw/bsp/da1469x/family.cmake
@@ -0,0 +1,141 @@
+include_guard()
+
+set(MCU_DIR ${TOP}/hw/mcu/dialog/da1469x)
+
+# include board specific
+include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
+
+set(CMAKE_SYSTEM_PROCESSOR cortex-m33-nodsp CACHE INTERNAL "System Processor")
+set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
+set(FAMILY_MCUS DA1469X CACHE INTERNAL "")
+
+#------------------------------------
+# BOARD_TARGET
+#------------------------------------
+# only need to be built ONCE for all examples
+function(add_board_target BOARD_TARGET)
+ if (TARGET ${BOARD_TARGET})
+ return()
+ endif ()
+
+ if (NOT DEFINED LD_FILE_GNU)
+ set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/da1469x.ld)
+ endif ()
+
+ if (NOT DEFINED STARTUP_FILE_${CMAKE_C_COMPILER_ID})
+ set(STARTUP_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/gcc_startup_da1469x.S)
+ set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
+ endif ()
+
+ add_library(${BOARD_TARGET} STATIC
+ ${MCU_DIR}/src/system_da1469x.c
+ ${MCU_DIR}/src/da1469x_clock.c
+ ${MCU_DIR}/src/hal_gpio.c
+ ${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
+ )
+ target_compile_options(${BOARD_TARGET} PUBLIC -mthumb-interwork)
+ target_compile_definitions(${BOARD_TARGET} PUBLIC
+ CORE_M33
+ CFG_TUD_ENDPOINT0_SIZE=8
+ )
+ target_include_directories(${BOARD_TARGET} PUBLIC
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
+ ${MCU_DIR}/include
+ ${MCU_DIR}/SDK_10.0.8.105/sdk/bsp/include
+ )
+
+ update_board(${BOARD_TARGET})
+
+ if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
+ target_link_options(${BOARD_TARGET} PUBLIC
+ "LINKER:--script=${LD_FILE_GNU}"
+ -L${NRFX_DIR}/mdk
+ --specs=nosys.specs --specs=nano.specs
+ -nostartfiles
+ )
+ elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
+ target_link_options(${BOARD_TARGET} PUBLIC
+ "LINKER:--script=${LD_FILE_GNU}"
+ -L${NRFX_DIR}/mdk
+ )
+ elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
+ target_link_options(${BOARD_TARGET} PUBLIC
+ "LINKER:--config=${LD_FILE_IAR}"
+ )
+ endif ()
+endfunction()
+
+
+#------------------------------------
+# Functions
+#------------------------------------
+
+function(family_flash_jlink_dialog TARGET)
+ set(JLINKEXE JLinkExe)
+ set(JLINK_IF swd)
+
+ # mkimage from sdk
+ set(MKIMAGE $ENV{HOME}/code/tinyusb-mcu-driver/dialog/SDK_10.0.8.105/binaries/mkimage)
+
+ file(GENERATE OUTPUT $/version.h
+ CONTENT "#define SW_VERSION \"v_1.0.0.1\"
+#define SW_VERSION_DATE \"2024-07-17 17:55\""
+ )
+
+ file(GENERATE OUTPUT $/${TARGET}.jlink
+ CONTENT "r
+halt
+loadfile $/${TARGET}-image.bin 0x16000000
+r
+go
+exit"
+ )
+
+ add_custom_target(${TARGET}-image
+ DEPENDS ${TARGET}
+ COMMAND ${MKIMAGE} da1469x $/${TARGET}.bin $/version.h $/${TARGET}.bin.img
+ COMMAND cp ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/product_header.dump $/${TARGET}-image.bin
+ COMMAND cat $/${TARGET}.bin.img >> $/${TARGET}-image.bin
+ )
+ add_custom_target(${TARGET}-jlink
+ DEPENDS ${TARGET}-image
+ COMMAND ${JLINKEXE} -device ${JLINK_DEVICE} -if ${JLINK_IF} -JTAGConf -1,-1 -speed auto -CommandFile $/${TARGET}.jlink
+ )
+endfunction()
+
+
+function(family_configure_example TARGET RTOS)
+ family_configure_common(${TARGET} ${RTOS})
+
+ # Board target
+ add_board_target(board_${BOARD})
+
+ #---------- Port Specific ----------
+ # These files are built for each example since it depends on example's tusb_config.h
+ target_sources(${TARGET} PUBLIC
+ # BSP
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
+ )
+ target_include_directories(${TARGET} PUBLIC
+ # family, hw, board
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
+ ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
+ )
+
+ # Add TinyUSB target and port source
+ family_add_tinyusb(${TARGET} OPT_MCU_DA1469X ${RTOS})
+ target_sources(${TARGET}-tinyusb PUBLIC
+ ${TOP}/src/portable/dialog/da146xx/dcd_da146xx.c
+ )
+ target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
+
+ # Link dependencies
+ target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
+
+ # Flashing
+ family_add_bin_hex(${TARGET})
+ family_flash_jlink_dialog(${TARGET})
+endfunction()
diff --git a/hw/bsp/da14695_dk_usb/board.mk b/hw/bsp/da1469x/family.mk
similarity index 52%
rename from hw/bsp/da14695_dk_usb/board.mk
rename to hw/bsp/da1469x/family.mk
index 980b1a361..f35fe2cb5 100644
--- a/hw/bsp/da14695_dk_usb/board.mk
+++ b/hw/bsp/da1469x/family.mk
@@ -1,4 +1,6 @@
-MCU_FAMILY_DIR = hw/mcu/dialog/da1469x
+MCU_DIR = hw/mcu/dialog/da1469x
+
+include $(TOP)/$(BOARD_PATH)/board.mk
CFLAGS += \
-flto \
@@ -8,48 +10,52 @@ CFLAGS += \
-mcpu=cortex-m33+nodsp \
-mfloat-abi=hard \
-mfpu=fpv5-sp-d16 \
- -nostdlib \
-DCORE_M33 \
-DCFG_TUSB_MCU=OPT_MCU_DA1469X \
-DCFG_TUD_ENDPOINT0_SIZE=8\
-LDFLAGS_GCC += -specs=nosys.specs -specs=nano.specs
+LDFLAGS_GCC += \
+ -nostdlib \
+ --specs=nosys.specs --specs=nano.specs
# All source paths should be relative to the top level.
-LD_FILE = hw/bsp/$(BOARD)/da1469x.ld
+LD_FILE = $(FAMILY_PATH)/linker/da1469x.ld
# While this is for da1469x chip, there is chance that da1468x chip family will also work
SRC_C += \
src/portable/dialog/da146xx/dcd_da146xx.c \
- $(MCU_FAMILY_DIR)/src/system_da1469x.c \
- $(MCU_FAMILY_DIR)/src/da1469x_clock.c \
- $(MCU_FAMILY_DIR)/src/hal_gpio.c \
+ ${MCU_DIR}/src/system_da1469x.c \
+ ${MCU_DIR}/src/da1469x_clock.c \
+ ${MCU_DIR}/src/hal_gpio.c \
-SRC_S += hw/bsp/$(BOARD)/gcc_startup_da1469x.S
+SRC_S += $(FAMILY_PATH)/gcc_startup_da1469x.S
INC += \
- $(TOP)/hw/bsp/$(BOARD) \
- $(TOP)/$(MCU_FAMILY_DIR)/include \
- $(TOP)/$(MCU_FAMILY_DIR)/SDK_10.0.8.105/sdk/bsp/include
+ $(TOP)/$(BOARD_PATH) \
+ $(TOP)/${MCU_DIR}/include \
+ $(TOP)/${MCU_DIR}/SDK_10.0.8.105/sdk/bsp/include
# For freeRTOS port source
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM33_NTZ/non_secure
-# For flash-jlink target
-JLINK_DEVICE = DA14695
-
# flash using jlink but with some twists
flash: flash-dialog
-flash-dialog: $(BUILD)/$(PROJECT).bin
+# SDK_BINARY_PATH is the path to the SDK binary files
+SDK_BINARY_PATH = $(HOME)/code/tinyusb-mcu-driver/dialog/SDK_10.0.8.105/binaries
+MKIMAGE = $(SDK_BINARY_PATH)/mkimage
+
+$(BUILD)/$(PROJECT)-image.bin: $(BUILD)/$(PROJECT).bin
@echo '#define SW_VERSION "v_1.0.0.1"' >$(BUILD)/version.h
- @echo '#define SW_VERSION_DATE "'`date +"%Y-%m-%d %H:%M"`'"' >>$(BUILD)/version.h
- mkimage da1469x $(BUILD)/$(PROJECT).bin $(BUILD)/version.h $^.img
- cp $(TOP)/hw/bsp/$(BOARD)/product_header.dump $(BUILD)/$(BOARD)-image.bin
- cat $^.img >> $(BUILD)/$(BOARD)-image.bin
+ @echo '#define SW_VERSION_DATE "'`date +"%Y-%m-%d %H:%M"`'"' >> $(BUILD)/version.h
+ $(MKIMAGE) da1469x $^ $(BUILD)/version.h $^.img
+ cp $(TOP)/$(FAMILY_PATH)/product_header.dump $(BUILD)/$(PROJECT)-image.bin
+ cat $^.img >> $(BUILD)/$(PROJECT)-image.bin
+
+flash-dialog: $(BUILD)/$(PROJECT)-image.bin
@echo r > $(BUILD)/$(BOARD).jlink
@echo halt >> $(BUILD)/$(BOARD).jlink
- @echo loadfile $(BUILD)/$(BOARD)-image.bin 0x16000000 >> $(BUILD)/$(BOARD).jlink
+ @echo loadfile $^ 0x16000000 >> $(BUILD)/$(BOARD).jlink
@echo r >> $(BUILD)/$(BOARD).jlink
@echo go >> $(BUILD)/$(BOARD).jlink
@echo exit >> $(BUILD)/$(BOARD).jlink
diff --git a/hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S b/hw/bsp/da1469x/gcc_startup_da1469x.S
similarity index 100%
rename from hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S
rename to hw/bsp/da1469x/gcc_startup_da1469x.S
diff --git a/hw/bsp/da14695_dk_usb/da1469x.ld b/hw/bsp/da1469x/linker/da1469x.ld
similarity index 100%
rename from hw/bsp/da14695_dk_usb/da1469x.ld
rename to hw/bsp/da1469x/linker/da1469x.ld
diff --git a/hw/bsp/da14695_dk_usb/product_header.dump b/hw/bsp/da1469x/product_header.dump
similarity index 100%
rename from hw/bsp/da14695_dk_usb/product_header.dump
rename to hw/bsp/da1469x/product_header.dump
diff --git a/hw/bsp/da1469x_dk_pro/board.mk b/hw/bsp/da1469x_dk_pro/board.mk
deleted file mode 100644
index 5282f93a3..000000000
--- a/hw/bsp/da1469x_dk_pro/board.mk
+++ /dev/null
@@ -1,56 +0,0 @@
-MCU_FAMILY_DIR = hw/mcu/dialog/da1469x
-
-CFLAGS += \
- -flto \
- -mthumb \
- -mthumb-interwork \
- -mabi=aapcs \
- -mcpu=cortex-m33+nodsp \
- -mfloat-abi=hard \
- -mfpu=fpv5-sp-d16 \
- -nostdlib \
- -DCORE_M33 \
- -DCFG_TUSB_MCU=OPT_MCU_DA1469X \
- -DCFG_TUD_ENDPOINT0_SIZE=8\
-
-LDFLAGS_GCC += -specs=nosys.specs -specs=nano.specs
-
-# All source paths should be relative to the top level.
-LD_FILE = hw/bsp/$(BOARD)/da1469x.ld
-
-# While this is for da1469x chip, there is chance that da1468x chip family will also work
-SRC_C += \
- src/portable/dialog/da146xx/dcd_da146xx.c \
- $(MCU_FAMILY_DIR)/src/system_da1469x.c \
- $(MCU_FAMILY_DIR)/src/da1469x_clock.c \
- $(MCU_FAMILY_DIR)/src/hal_gpio.c \
-
-SRC_S += hw/bsp/$(BOARD)/gcc_startup_da1469x.S
-
-INC += \
- $(TOP)/hw/bsp/$(BOARD) \
- $(TOP)/$(MCU_FAMILY_DIR)/include \
- $(TOP)/$(MCU_FAMILY_DIR)/SDK_10.0.8.105/sdk/bsp/include
-
-# For freeRTOS port source
-FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM33_NTZ/non_secure
-
-# For flash-jlink target
-JLINK_DEVICE = DA14699
-
-# flash using jlink but with some twists
-flash: flash-dialog
-
-flash-dialog: $(BUILD)/$(PROJECT).bin
- @echo '#define SW_VERSION "v_1.0.0.1"' >$(BUILD)/version.h
- @echo '#define SW_VERSION_DATE "'`date +"%Y-%m-%d %H:%M"`'"' >>$(BUILD)/version.h
- mkimage da1469x $(BUILD)/$(PROJECT).bin $(BUILD)/version.h $^.img
- cp $(TOP)/hw/bsp/$(BOARD)/product_header.dump $(BUILD)/$(BOARD)-image.bin
- cat $^.img >> $(BUILD)/$(BOARD)-image.bin
- @echo r > $(BUILD)/$(BOARD).jlink
- @echo halt >> $(BUILD)/$(BOARD).jlink
- @echo loadfile $(BUILD)/$(BOARD)-image.bin 0x16000000 >> $(BUILD)/$(BOARD).jlink
- @echo r >> $(BUILD)/$(BOARD).jlink
- @echo go >> $(BUILD)/$(BOARD).jlink
- @echo exit >> $(BUILD)/$(BOARD).jlink
- $(JLINKEXE) -device $(JLINK_DEVICE) -if $(JLINK_IF) -JTAGConf -1,-1 -speed auto -CommandFile $(BUILD)/$(BOARD).jlink
diff --git a/hw/bsp/da1469x_dk_pro/da1469x.ld b/hw/bsp/da1469x_dk_pro/da1469x.ld
deleted file mode 100644
index 8cc1d9d99..000000000
--- a/hw/bsp/da1469x_dk_pro/da1469x.ld
+++ /dev/null
@@ -1,244 +0,0 @@
-/*
- * Licensed to the Apache Software Foundation (ASF) under one
- * or more contributor license agreements. See the NOTICE file
- * distributed with this work for additional information
- * regarding copyright ownership. The ASF licenses this file
- * to you under the Apache License, Version 2.0 (the
- * "License"); you may not use this file except in compliance
- * with the License. You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
- * KIND, either express or implied. See the License for the
- * specific language governing permissions and limitations
- * under the License.
- */
-
-MEMORY
-{
- /*
- * Flash is remapped at 0x0 by 1st stage bootloader, but this is done with
- * an offset derived from image header thus it is safer to use remapped
- * address space at 0x0 instead of QSPI_M address space at 0x16000000.
- * Bootloader partition is 32K, but 9K is currently reserved for product
- * header (8K) and image header (1K).
- * First 512 bytes of SYSRAM are remapped at 0x0 and used as ISR vector
- * (there's no need to reallocate ISR vector) and thus cannot be used by
- * application.
- */
-
- FLASH (r) : ORIGIN = (0x00000000), LENGTH = (1024 * 1024)
- RAM (rw) : ORIGIN = (0x20000000), LENGTH = (512 * 1024)
-}
-
-OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
-
-/* Linker script to place sections and symbol values. Should be used together
- * with other linker script that defines memory regions FLASH and RAM.
- * It references following symbols, which must be defined in code:
- * Reset_Handler : Entry of reset handler
- *
- * It defines following symbols, which code can use without definition:
- * __exidx_start
- * __exidx_end
- * __etext
- * __data_start__
- * __preinit_array_start
- * __preinit_array_end
- * __init_array_start
- * __init_array_end
- * __fini_array_start
- * __fini_array_end
- * __data_end__
- * __bss_start__
- * __bss_end__
- * __HeapBase
- * __HeapLimit
- * __StackLimit
- * __StackTop
- * __stack
- * __bssnz_start__
- * __bssnz_end__
- */
-ENTRY(Reset_Handler)
-
-SECTIONS
-{
- __text = .;
-
- .text :
- {
- __isr_vector_start = .;
- KEEP(*(.isr_vector))
- /* ISR vector shall have exactly 512 bytes */
- . = __isr_vector_start + 0x200;
- __isr_vector_end = .;
-
- *(.text)
- *(.text.*)
-
- *(.libcmac.rom)
-
- KEEP(*(.init))
- KEEP(*(.fini))
-
- /* .ctors */
- *crtbegin.o(.ctors)
- *crtbegin?.o(.ctors)
- *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
- *(SORT(.ctors.*))
- *(.ctors)
-
- /* .dtors */
- *crtbegin.o(.dtors)
- *crtbegin?.o(.dtors)
- *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
- *(SORT(.dtors.*))
- *(.dtors)
-
- *(.rodata*)
-
- *(.eh_frame*)
- . = ALIGN(4);
- } > FLASH
-
- .ARM.extab :
- {
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- . = ALIGN(4);
- } > FLASH
-
- __exidx_start = .;
- .ARM :
- {
- *(.ARM.exidx* .gnu.linkonce.armexidx.*)
- . = ALIGN(4);
- } > FLASH
- __exidx_end = .;
-
- .intvect :
- {
- . = ALIGN(4);
- __intvect_start__ = .;
- . = . + (__isr_vector_end - __isr_vector_start);
- . = ALIGN(4);
- } > RAM
-
- .sleep_state (NOLOAD) :
- {
- . = ALIGN(4);
- *(sleep_state)
- } > RAM
-
- /* This section will be zeroed by RTT package init */
- .rtt (NOLOAD):
- {
- . = ALIGN(4);
- *(.rtt)
- . = ALIGN(4);
- } > RAM
-
- __text_ram_addr = LOADADDR(.text_ram);
-
- .text_ram :
- {
- . = ALIGN(4);
- __text_ram_start__ = .;
- *(.text_ram*)
- . = ALIGN(4);
- __text_ram_end__ = .;
- } > RAM AT > FLASH
-
- __etext = LOADADDR(.data);
-
- .data :
- {
- __data_start__ = .;
- *(vtable)
- *(.data*)
-
- . = ALIGN(4);
- /* preinit data */
- PROVIDE_HIDDEN (__preinit_array_start = .);
- *(.preinit_array)
- PROVIDE_HIDDEN (__preinit_array_end = .);
-
- . = ALIGN(4);
- /* init data */
- PROVIDE_HIDDEN (__init_array_start = .);
- *(SORT(.init_array.*))
- *(.init_array)
- PROVIDE_HIDDEN (__init_array_end = .);
-
-
- . = ALIGN(4);
- /* finit data */
- PROVIDE_HIDDEN (__fini_array_start = .);
- *(SORT(.fini_array.*))
- *(.fini_array)
- PROVIDE_HIDDEN (__fini_array_end = .);
-
- *(.jcr)
- . = ALIGN(4);
- /* All data end */
- __data_end__ = .;
- } > RAM AT > FLASH
-
- .bssnz :
- {
- . = ALIGN(4);
- __bssnz_start__ = .;
- *(.bss.core.nz*)
- . = ALIGN(4);
- __bssnz_end__ = .;
- } > RAM
-
- .bss :
- {
- . = ALIGN(4);
- __bss_start__ = .;
- *(.bss*)
- *(COMMON)
- . = ALIGN(4);
- __bss_end__ = .;
- } > RAM
-
- .cmac (NOLOAD) :
- {
- . = ALIGN(0x400);
- *(.libcmac.ram)
- } > RAM
-
- /* Heap starts after BSS */
- . = ALIGN(8);
- __HeapBase = .;
-
- /* .stack_dummy section doesn't contains any symbols. It is only
- * used for linker to calculate size of stack sections, and assign
- * values to stack symbols later */
- .stack_dummy (COPY):
- {
- *(.stack*)
- } > RAM
-
- _ram_start = ORIGIN(RAM);
-
- /* Set stack top to end of RAM, and stack limit move down by
- * size of stack_dummy section */
- __StackTop = ORIGIN(RAM) + LENGTH(RAM);
- __StackLimit = __StackTop - SIZEOF(.stack_dummy);
- PROVIDE(__stack = __StackTop);
-
- /* Top of head is the bottom of the stack */
- __HeapLimit = __StackLimit;
- end = __HeapLimit;
-
- /* Check if data + heap + stack exceeds RAM limit */
- ASSERT(__HeapBase <= __HeapLimit, "region RAM overflowed with stack")
-
- /* Check that intvect is at the beginning of RAM */
- ASSERT(__intvect_start__ == ORIGIN(RAM), "intvect is not at beginning of RAM")
-}
diff --git a/hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S b/hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S
deleted file mode 100644
index d47fbcd97..000000000
--- a/hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S
+++ /dev/null
@@ -1,301 +0,0 @@
-/*
- * Licensed to the Apache Software Foundation (ASF) under one
- * or more contributor license agreements. See the NOTICE file
- * distributed with this work for additional information
- * regarding copyright ownership. The ASF licenses this file
- * to you under the Apache License, Version 2.0 (the
- * "License"); you may not use this file except in compliance
- * with the License. You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
- * KIND, either express or implied. See the License for the
- * specific language governing permissions and limitations
- * under the License.
- */
-
- #include "syscfg/syscfg.h"
-
- .syntax unified
- .arch armv7-m
-
- .section .stack
- .align 3
-#ifdef __STACK_SIZE
- .equ Stack_Size, __STACK_SIZE
-#else
- .equ Stack_Size, 0xC00
-#endif
- .equ SYS_CTRL_REG, 0x50000024
- .equ CACHE_FLASH_REG, 0x100C0040
- .equ RESET_STAT_REG, 0x500000BC
-
- .globl __StackTop
- .globl __StackLimit
-__StackLimit:
- .space Stack_Size
- .size __StackLimit, . - __StackLimit
-__StackTop:
- .size __StackTop, . - __StackTop
-
- .section .heap
- .align 3
-#ifdef __HEAP_SIZE
- .equ Heap_Size, __HEAP_SIZE
-#else
- .equ Heap_Size, 0
-#endif
- .globl __HeapBase
- .globl __HeapLimit
-__HeapBase:
- .if Heap_Size
- .space Heap_Size
- .endif
- .size __HeapBase, . - __HeapBase
-__HeapLimit:
- .size __HeapLimit, . - __HeapLimit
-
- .section .isr_vector
- .align 2
- .globl __isr_vector
-__isr_vector:
- .long __StackTop
- .long Reset_Handler
- /* Cortex-M33 interrupts */
- .long NMI_Handler
- .long HardFault_Handler
- .long MemoryManagement_Handler
- .long BusFault_Handler
- .long UsageFault_Handler
- .long SecureFault_Handler
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long SVC_Handler
- .long DebugMonitor_Handler
- .long 0 /* Reserved */
- .long PendSV_Handler
- .long SysTick_Handler
- /* DA1469x interrupts */
- .long SENSOR_NODE_IRQHandler
- .long DMA_IRQHandler
- .long CHARGER_STATE_IRQHandler
- .long CHARGER_ERROR_IRQHandler
- .long CMAC2SYS_IRQHandler
- .long UART_IRQHandler
- .long UART2_IRQHandler
- .long UART3_IRQHandler
- .long I2C_IRQHandler
- .long I2C2_IRQHandler
- .long SPI_IRQHandler
- .long SPI2_IRQHandler
- .long PCM_IRQHandler
- .long SRC_IN_IRQHandler
- .long SRC_OUT_IRQHandler
- .long USB_IRQHandler
- .long TIMER_IRQHandler
- .long TIMER2_IRQHandler
- .long RTC_IRQHandler
- .long KEY_WKUP_GPIO_IRQHandler
- .long PDC_IRQHandler
- .long VBUS_IRQHandler
- .long MRM_IRQHandler
- .long MOTOR_CONTROLLER_IRQHandler
- .long TRNG_IRQHandler
- .long DCDC_IRQHandler
- .long XTAL32M_RDY_IRQHandler
- .long ADC_IRQHandler
- .long ADC2_IRQHandler
- .long CRYPTO_IRQHandler
- .long CAPTIMER1_IRQHandler
- .long RFDIAG_IRQHandler
- .long LCD_CONTROLLER_IRQHandler
- .long PLL_LOCK_IRQHandler
- .long TIMER3_IRQHandler
- .long TIMER4_IRQHandler
- .long LRA_IRQHandler
- .long RTC_EVENT_IRQHandler
- .long GPIO_P0_IRQHandler
- .long GPIO_P1_IRQHandler
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .long 0 /* Reserved */
- .size __isr_vector, . - __isr_vector
-
- .text
- .thumb
- .thumb_func
- .align 2
- .globl Reset_Handler
- .type Reset_Handler, %function
-Reset_Handler:
- /* Make sure interrupt vector is remapped at 0x0 */
- ldr r1, =SYS_CTRL_REG
- ldrh r2, [r1, #0]
- orrs r2, r2, #8
- strh r2, [r1, #0]
-
-#if !MYNEWT_VAL(RAM_RESIDENT)
-/*
- * Flash is remapped at 0x0 with an offset, i.e. 0x0 does not correspond to
- * 0x16000000 but to start of an image on flash. This is calculated from product
- * header by 1st state bootloader and configured in CACHE_FLASH_REG. We need to
- * retrieve proper offset value for calculations later.
- */
- ldr r1, =CACHE_FLASH_REG
- ldr r4, [r1, #0]
- mov r2, r4
- mov r3, #0xFFFF
- bic r4, r4, r3 /* CACHE_FLASH_REG[FLASH_REGION_BASE] */
- mov r3, #0xFFF0
- and r2, r2, r3 /* CACHE_FLASH_REG[FLASH_REGION_OFFSET] */
- lsr r2, r2, #2
- orr r4, r4, r2
-
-/* Copy ISR vector from flash to RAM */
- ldr r1, =__isr_vector_start /* src ptr */
- ldr r2, =__isr_vector_end /* src end */
- ldr r3, =__intvect_start__ /* dst ptr */
-/* Make sure we copy from QSPIC address range, not from remapped range */
- cmp r1, r4
- itt lt
- addlt r1, r1, r4
- addlt r2, r2, r4
-.loop_isr_copy:
- cmp r1, r2
- ittt lt
- ldrlt r0, [r1], #4
- strlt r0, [r3], #4
- blt .loop_isr_copy
-
-/* Copy QSPI code from flash to RAM */
- ldr r1, =__text_ram_addr /* src ptr */
- ldr r2, =__text_ram_start__ /* ptr */
- ldr r3, =__text_ram_end__ /* dst end */
-.loop_code_text_ram_copy:
- cmp r2, r3
- ittt lt
- ldrlt r0, [r1], #4
- strlt r0, [r2], #4
- blt .loop_code_text_ram_copy
-
-/* Copy data from flash to RAM */
- ldr r1, =__etext /* src ptr */
- ldr r2, =__data_start__ /* dst ptr */
- ldr r3, =__data_end__ /* dst end */
-.loop_data_copy:
- cmp r2, r3
- ittt lt
- ldrlt r0, [r1], #4
- strlt r0, [r2], #4
- blt .loop_data_copy
-#endif
-
-/* Clear BSS */
- movs r0, 0
- ldr r1, =__bss_start__
- ldr r2, =__bss_end__
-.loop_bss_clear:
- cmp r1, r2
- itt lt
- strlt r0, [r1], #4
- blt .loop_bss_clear
-
- ldr r0, =__HeapBase
- ldr r1, =__HeapLimit
-/* Call static constructors */
- bl __libc_init_array
-
- bl SystemInit
- bl main
-
- .pool
- .size Reset_Handler, . - Reset_Handler
-
-/* Default interrupt handler */
- .type Default_Handler, %function
-Default_Handler:
- ldr r1, =SYS_CTRL_REG
- ldrh r2, [r1, #0]
- orrs r2, r2, #0x80 /* DEBUGGER_ENABLE */
- strh r2, [r1, #0]
- b .
-
- .size Default_Handler, . - Default_Handler
-
-/* Default handlers for all interrupts */
- .macro IRQ handler
- .weak \handler
- .set \handler, Default_Handler
- .endm
-
- /* Cortex-M33 interrupts */
- IRQ NMI_Handler
- IRQ HardFault_Handler
- IRQ MemoryManagement_Handler
- IRQ BusFault_Handler
- IRQ UsageFault_Handler
- IRQ SecureFault_Handler
- IRQ SVC_Handler
- IRQ DebugMonitor_Handler
- IRQ PendSV_Handler
- IRQ SysTick_Handler
- /* DA1469x interrupts */
- IRQ SENSOR_NODE_IRQHandler
- IRQ DMA_IRQHandler
- IRQ CHARGER_STATE_IRQHandler
- IRQ CHARGER_ERROR_IRQHandler
- IRQ CMAC2SYS_IRQHandler
- IRQ UART_IRQHandler
- IRQ UART2_IRQHandler
- IRQ UART3_IRQHandler
- IRQ I2C_IRQHandler
- IRQ I2C2_IRQHandler
- IRQ SPI_IRQHandler
- IRQ SPI2_IRQHandler
- IRQ PCM_IRQHandler
- IRQ SRC_IN_IRQHandler
- IRQ SRC_OUT_IRQHandler
- IRQ USB_IRQHandler
- IRQ TIMER_IRQHandler
- IRQ TIMER2_IRQHandler
- IRQ RTC_IRQHandler
- IRQ KEY_WKUP_GPIO_IRQHandler
- IRQ PDC_IRQHandler
- IRQ VBUS_IRQHandler
- IRQ MRM_IRQHandler
- IRQ MOTOR_CONTROLLER_IRQHandler
- IRQ TRNG_IRQHandler
- IRQ DCDC_IRQHandler
- IRQ XTAL32M_RDY_IRQHandler
- IRQ ADC_IRQHandler
- IRQ ADC2_IRQHandler
- IRQ CRYPTO_IRQHandler
- IRQ CAPTIMER1_IRQHandler
- IRQ RFDIAG_IRQHandler
- IRQ LCD_CONTROLLER_IRQHandler
- IRQ PLL_LOCK_IRQHandler
- IRQ TIMER3_IRQHandler
- IRQ TIMER4_IRQHandler
- IRQ LRA_IRQHandler
- IRQ RTC_EVENT_IRQHandler
- IRQ GPIO_P0_IRQHandler
- IRQ GPIO_P1_IRQHandler
- IRQ RESERVED40_IRQHandler
- IRQ RESERVED41_IRQHandler
- IRQ RESERVED42_IRQHandler
- IRQ RESERVED43_IRQHandler
- IRQ RESERVED44_IRQHandler
- IRQ RESERVED45_IRQHandler
- IRQ RESERVED46_IRQHandler
- IRQ RESERVED47_IRQHandler
-
-.end
diff --git a/hw/bsp/da1469x_dk_pro/product_header.dump b/hw/bsp/da1469x_dk_pro/product_header.dump
deleted file mode 100644
index ea4842242..000000000
Binary files a/hw/bsp/da1469x_dk_pro/product_header.dump and /dev/null differ
diff --git a/src/class/hid/hid_device.c b/src/class/hid/hid_device.c
index 7168ab3d5..00f6fc474 100644
--- a/src/class/hid/hid_device.c
+++ b/src/class/hid/hid_device.c
@@ -46,16 +46,16 @@ typedef struct {
uint8_t itf_protocol; // Boot mouse or keyboard
uint16_t report_desc_len;
- CFG_TUSB_MEM_ALIGN uint8_t protocol_mode; // Boot (0) or Report protocol (1)
- CFG_TUSB_MEM_ALIGN uint8_t idle_rate; // up to application to handle idle rate
-
- CFG_TUSB_MEM_ALIGN uint8_t epin_buf[CFG_TUD_HID_EP_BUFSIZE];
- CFG_TUSB_MEM_ALIGN uint8_t epout_buf[CFG_TUD_HID_EP_BUFSIZE];
- CFG_TUSB_MEM_ALIGN uint8_t ctrl_buf[CFG_TUD_HID_EP_BUFSIZE];
+ uint8_t protocol_mode; // Boot (0) or Report protocol (1)
+ uint8_t idle_rate; // up to application to handle idle rate
// TODO save hid descriptor since host can specifically request this after enumeration
// Note: HID descriptor may be not available from application after enumeration
tusb_hid_descriptor_hid_t const *hid_descriptor;
+
+ uint8_t ctrl_buf[CFG_TUD_HID_EP_BUFSIZE];
+ CFG_TUSB_MEM_ALIGN uint8_t epin_buf[CFG_TUD_HID_EP_BUFSIZE];
+ CFG_TUSB_MEM_ALIGN uint8_t epout_buf[CFG_TUD_HID_EP_BUFSIZE];
} hidd_interface_t;
CFG_TUD_MEM_SECTION tu_static hidd_interface_t _hidd_itf[CFG_TUD_HID];
diff --git a/tools/get_deps.py b/tools/get_deps.py
index 92bfb86a2..555e2d707 100644
--- a/tools/get_deps.py
+++ b/tools/get_deps.py
@@ -172,10 +172,10 @@ deps_optional = {
'7578cae0b21f86dd053a1f781b2fc6ab99d0ec17',
'ch32v10x'],
'hw/mcu/wch/ch32v20x': ['https://github.com/openwch/ch32v20x.git',
- 'de6d68c654340d7f27b00cebbfc9aa2740a1abc2',
+ 'c4c38f507e258a4e69b059ccc2dc27dde33cea1b',
'ch32v20x'],
'hw/mcu/wch/ch32v307': ['https://github.com/openwch/ch32v307.git',
- '17761f5cf9dbbf2dcf665b7c04934188add20082',
+ '184f21b852cb95eed58e86e901837bc9fff68775',
'ch32v307'],
'hw/mcu/wch/ch32f20x': ['https://github.com/openwch/ch32f20x.git',
'77c4095087e5ed2c548ec9058e655d0b8757663b',