From 463e978134c7ee1d4abae4937f9c0c3e603ac6bc Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 1 Jul 2020 12:47:14 +0700 Subject: [PATCH] added DA14695 DK USB bsp --- README.md | 1 + docs/boards.md | 5 + hw/bsp/da14695_dk_usb/board.mk | 59 ++++ hw/bsp/da14695_dk_usb/da14695_dk_usb.c | 127 +++++++++ hw/bsp/da14695_dk_usb/da1469x.ld | 245 ++++++++++++++++ hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S | 301 ++++++++++++++++++++ hw/bsp/da14695_dk_usb/product_header.dump | Bin 0 -> 8192 bytes hw/bsp/da14695_dk_usb/syscfg/syscfg.h | 34 +++ hw/bsp/da1469x_dk_pro/board.mk | 7 +- 9 files changed, 773 insertions(+), 6 deletions(-) create mode 100644 hw/bsp/da14695_dk_usb/board.mk create mode 100644 hw/bsp/da14695_dk_usb/da14695_dk_usb.c create mode 100644 hw/bsp/da14695_dk_usb/da1469x.ld create mode 100644 hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S create mode 100644 hw/bsp/da14695_dk_usb/product_header.dump create mode 100644 hw/bsp/da14695_dk_usb/syscfg/syscfg.h diff --git a/README.md b/README.md index 31e40b399..f9a7d0b73 100644 --- a/README.md +++ b/README.md @@ -31,6 +31,7 @@ Special thanks to all the people who spent their precious time and effort to hel The stack supports the following MCUs: - **Espressif:** ESP32-S2 +- **Dialog:** DA1469x - **MicroChip:** SAMD21, SAMD51, SAME5x (device only) - **NordicSemi:** nRF52833, nRF52840 - **Nuvoton:** NUC120, NUC121/NUC125, NUC126, NUC505 diff --git a/docs/boards.md b/docs/boards.md index 46d071853..57b1410bc 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -14,6 +14,11 @@ This code base already had supported for a handful of following boards (sorted a - [ESP32-S2-Kaluga-1](https://docs.espressif.com/projects/esp-idf/en/latest/esp32s2/hw-reference/esp32s2/user-guide-esp32-s2-kaluga-1-kit.html) - [ESP32-S2-Saola-1](https://docs.espressif.com/projects/esp-idf/en/latest/esp32s2/hw-reference/esp32s2/user-guide-saola-1-v1.2.html) +### Dialog DA146xx + +- [DA14695 Development Kit – USB](https://www.dialog-semiconductor.com/products/da14695-development-kit-usb) +- [DA1469x Development Kit – Pro](https://www.dialog-semiconductor.com/products/da14695-development-kit-pro) + ### MicroChip SAMD - [Adafruit Circuit Playground Express](https://www.adafruit.com/product/3333) diff --git a/hw/bsp/da14695_dk_usb/board.mk b/hw/bsp/da14695_dk_usb/board.mk new file mode 100644 index 000000000..f5b8873f9 --- /dev/null +++ b/hw/bsp/da14695_dk_usb/board.mk @@ -0,0 +1,59 @@ + 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\ + +MCU_FAMILY_DIR = hw/mcu/dialog/da1469x + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/da1469x.ld + +SRC_C += \ + $(MCU_FAMILY_DIR)/src/system_da1469x.c \ + $(MCU_FAMILY_DIR)/src/da1469x_clock.c \ + $(MCU_FAMILY_DIR)/src/hal_gpio.c \ + +SRC_S += $(TOP)/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 TinyUSB port source +VENDOR = dialog +# While this is for da1469x chip, there is chance that da1468x chip family will also work +CHIP_FAMILY = da146xx + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM33_NTZ/non_secure + +# For flash-jlink target +JLINK_DEVICE = DA14695 +JLINK_IF = swd + +# flash using jlink but with some twists +flash: flash-dialog + +flash-dialog: $(BUILD)/$(BOARD)-firmware.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)/$(BOARD)-firmware.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/da14695_dk_usb/da14695_dk_usb.c b/hw/bsp/da14695_dk_usb/da14695_dk_usb.c new file mode 100644 index 000000000..e7c7ae364 --- /dev/null +++ b/hw/bsp/da14695_dk_usb/da14695_dk_usb.c @@ -0,0 +1,127 @@ +/* + * 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.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); +} + +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_NONE); + + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + + NVIC_SetPriority(USB_IRQn, 2); + + /* 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); +} + +//--------------------------------------------------------------------+ +// 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 LOW + return hal_gpio_read(BUTTON_PIN) ^ 1; +} + +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/da14695_dk_usb/da1469x.ld b/hw/bsp/da14695_dk_usb/da1469x.ld new file mode 100644 index 000000000..96507d6e7 --- /dev/null +++ b/hw/bsp/da14695_dk_usb/da1469x.ld @@ -0,0 +1,245 @@ +/* + * 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/da14695_dk_usb/gcc_startup_da1469x.S b/hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S new file mode 100644 index 000000000..d47fbcd97 --- /dev/null +++ b/hw/bsp/da14695_dk_usb/gcc_startup_da1469x.S @@ -0,0 +1,301 @@ +/* + * 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/da14695_dk_usb/product_header.dump b/hw/bsp/da14695_dk_usb/product_header.dump new file mode 100644 index 0000000000000000000000000000000000000000..ea4842242654f6f52e34ed4737c9fc1692869f2d GIT binary patch literal 8192 zcmeIuO$mTN0EE#I51zMyQA{AF@Vuo2G0Ao@gg-GB-oOWQep}6){M|Xu{kvBgGb~eE qA0t43009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0Rja25O@K4jm)P2 literal 0 HcmV?d00001 diff --git a/hw/bsp/da14695_dk_usb/syscfg/syscfg.h b/hw/bsp/da14695_dk_usb/syscfg/syscfg.h new file mode 100644 index 000000000..6cbb4319e --- /dev/null +++ b/hw/bsp/da14695_dk_usb/syscfg/syscfg.h @@ -0,0 +1,34 @@ +/** + * This file was generated by Apache newt version: 1.9.0-dev + */ + +#ifndef H_MYNEWT_SYSCFG_ +#define H_MYNEWT_SYSCFG_ + +/** + * This macro exists to ensure code includes this header when needed. If code + * checks the existence of a setting directly via ifdef without including this + * header, the setting macro will silently evaluate to 0. In contrast, an + * attempt to use these macros without including this header will result in a + * compiler error. + */ +#define MYNEWT_VAL(_name) MYNEWT_VAL_ ## _name +#define MYNEWT_VAL_CHOICE(_name, _val) MYNEWT_VAL_ ## _name ## __ ## _val + +#ifndef MYNEWT_VAL_RAM_RESIDENT +#define MYNEWT_VAL_RAM_RESIDENT (0) +#endif + +#ifndef MYNEWT_VAL_MCU_GPIO_MAX_IRQ +#define MYNEWT_VAL_MCU_GPIO_MAX_IRQ (4) +#endif + +#ifndef MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM +#define MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM (-1) +#endif + +#ifndef MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US +#define MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US (2000) +#endif + +#endif diff --git a/hw/bsp/da1469x_dk_pro/board.mk b/hw/bsp/da1469x_dk_pro/board.mk index c8a268aa5..6708955f2 100644 --- a/hw/bsp/da1469x_dk_pro/board.mk +++ b/hw/bsp/da1469x_dk_pro/board.mk @@ -11,11 +11,7 @@ -DCFG_TUSB_MCU=OPT_MCU_DA1469X \ -DCFG_TUD_ENDPOINT0_SIZE=8\ -# mcu driver cause following warnings -# CFLAGS += -Wno-error=strict-prototypes -Wno-error=unused-parameter - MCU_FAMILY_DIR = hw/mcu/dialog/da1469x -MCU_DIR = hw/mcu/dialog/da14699 # All source paths should be relative to the top level. LD_FILE = hw/bsp/$(BOARD)/da1469x.ld @@ -28,8 +24,7 @@ SRC_C += \ SRC_S += $(TOP)/hw/bsp/$(BOARD)/gcc_startup_da1469x.S INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/include \ + $(TOP)/hw/bsp/$(BOARD) \ $(TOP)/$(MCU_FAMILY_DIR)/include \ $(TOP)/$(MCU_FAMILY_DIR)/SDK_10.0.8.105/sdk/bsp/include \