From 8e143fc962cb927dea6232d171aad85c7f4d44e4 Mon Sep 17 00:00:00 2001 From: Jerzy Kasenberg Date: Fri, 19 Jun 2020 14:02:09 +0200 Subject: [PATCH] Add board support for Dialog DA1469x-dk-pro This adds source files that allow to run TinyUSB stack on DA1469x-dk-pro board. Source files .c .S and .ld are taken from Apache Mynewt repository. Those files were stripped to allow starting board without Mynewt os. --- hw/bsp/board_mcu.h | 3 + hw/bsp/da1469x_dk_pro/board.mk | 64 +++ hw/bsp/da1469x_dk_pro/da1469x.ld | 245 +++++++++ hw/bsp/da1469x_dk_pro/dialog_da1469x-dk-pro.c | 127 +++++ hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S | 301 +++++++++++ hw/bsp/da1469x_dk_pro/product_header.dump | Bin 0 -> 8192 bytes hw/bsp/da1469x_dk_pro/syscfg/syscfg.h | 34 ++ hw/mcu/dialog/da1469x/da1469x.ld | 228 +++++++++ hw/mcu/dialog/da1469x/include/hal/hal_gpio.h | 184 +++++++ .../da1469x/include/mcu/da1469x_clock.h | 138 +++++ .../dialog/da1469x/include/mcu/da1469x_hal.h | 53 ++ hw/mcu/dialog/da1469x/include/mcu/mcu.h | 165 ++++++ hw/mcu/dialog/da1469x/src/da1469x_clock.c | 159 ++++++ hw/mcu/dialog/da1469x/src/hal_gpio.c | 478 ++++++++++++++++++ hw/mcu/dialog/da1469x/src/hal_system.c | 136 +++++ hw/mcu/dialog/da1469x/src/hal_system_start.c | 177 +++++++ hw/mcu/dialog/da1469x/src/system_da1469x.c | 61 +++ 17 files changed, 2553 insertions(+) create mode 100644 hw/bsp/da1469x_dk_pro/board.mk create mode 100644 hw/bsp/da1469x_dk_pro/da1469x.ld create mode 100644 hw/bsp/da1469x_dk_pro/dialog_da1469x-dk-pro.c create mode 100644 hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S create mode 100644 hw/bsp/da1469x_dk_pro/product_header.dump create mode 100644 hw/bsp/da1469x_dk_pro/syscfg/syscfg.h create mode 100644 hw/mcu/dialog/da1469x/da1469x.ld create mode 100644 hw/mcu/dialog/da1469x/include/hal/hal_gpio.h create mode 100644 hw/mcu/dialog/da1469x/include/mcu/da1469x_clock.h create mode 100644 hw/mcu/dialog/da1469x/include/mcu/da1469x_hal.h create mode 100644 hw/mcu/dialog/da1469x/include/mcu/mcu.h create mode 100644 hw/mcu/dialog/da1469x/src/da1469x_clock.c create mode 100644 hw/mcu/dialog/da1469x/src/hal_gpio.c create mode 100644 hw/mcu/dialog/da1469x/src/hal_system.c create mode 100644 hw/mcu/dialog/da1469x/src/hal_system_start.c create mode 100644 hw/mcu/dialog/da1469x/src/system_da1469x.c diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index 825a67be3..15b31edfd 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -113,6 +113,9 @@ #elif CFG_TUSB_MCU == OPT_MCU_ESP32S2 // no header needed +#elif CFG_TUSB_MCU == OPT_MCU_DA1469X + #include "DA1469xAB.h" + #else #error "Missing MCU header" #endif diff --git a/hw/bsp/da1469x_dk_pro/board.mk b/hw/bsp/da1469x_dk_pro/board.mk new file mode 100644 index 000000000..c8a268aa5 --- /dev/null +++ b/hw/bsp/da1469x_dk_pro/board.mk @@ -0,0 +1,64 @@ + 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 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 + +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_DIR)/include \ + $(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 = DA14699 +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/da1469x_dk_pro/da1469x.ld b/hw/bsp/da1469x_dk_pro/da1469x.ld new file mode 100644 index 000000000..96507d6e7 --- /dev/null +++ b/hw/bsp/da1469x_dk_pro/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/da1469x_dk_pro/dialog_da1469x-dk-pro.c b/hw/bsp/da1469x_dk_pro/dialog_da1469x-dk-pro.c new file mode 100644 index 000000000..85fa17152 --- /dev/null +++ b/hw/bsp/da1469x_dk_pro/dialog_da1469x-dk-pro.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 +#define LED_STATE_ON 1 +#define LED_STATE_OFF 0 + +#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/da1469x_dk_pro/gcc_startup_da1469x.S b/hw/bsp/da1469x_dk_pro/gcc_startup_da1469x.S new file mode 100644 index 000000000..d47fbcd97 --- /dev/null +++ b/hw/bsp/da1469x_dk_pro/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/da1469x_dk_pro/product_header.dump b/hw/bsp/da1469x_dk_pro/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/da1469x_dk_pro/syscfg/syscfg.h b/hw/bsp/da1469x_dk_pro/syscfg/syscfg.h new file mode 100644 index 000000000..6cbb4319e --- /dev/null +++ b/hw/bsp/da1469x_dk_pro/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/mcu/dialog/da1469x/da1469x.ld b/hw/mcu/dialog/da1469x/da1469x.ld new file mode 100644 index 000000000..c91dea841 --- /dev/null +++ b/hw/mcu/dialog/da1469x/da1469x.ld @@ -0,0 +1,228 @@ +/* Linker script for Dialog DA1469x devices + * + * Version: Sourcery G++ 4.5-1 + * Support: https://support.codesourcery.com/GNUToolchain/ + * + * Copyright (c) 2007, 2008, 2009, 2010 CodeSourcery, Inc. + * + * The authors hereby grant permission to use, copy, modify, distribute, + * and license this software and its documentation for any purpose, provided + * that existing copyright notices are retained in all copies and that this + * notice is included verbatim in any distributions. No written agreement, + * license, or royalty fee is required for any of the authorized uses. + * Modifications to this software may be copyrighted by their authors + * and need not follow the licensing terms described here, provided that + * the new terms are clearly indicated on the first page of each file where + * they apply. + */ +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 +{ + .imghdr (NOLOAD): + { + . = . + _imghdr_size; + } > FLASH + + __text = .; + + .text : + { + __isr_vector_start = .; + KEEP(*(.isr_vector)) + /* ISR vector shall have exactly 512 bytes */ + . = __isr_vector_start + 0x200; + __isr_vector_end = .; + + *(.text) + *(.text.*) + + 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.exidx : + { + *(.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; + + /* 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/mcu/dialog/da1469x/include/hal/hal_gpio.h b/hw/mcu/dialog/da1469x/include/hal/hal_gpio.h new file mode 100644 index 000000000..67fc3c144 --- /dev/null +++ b/hw/mcu/dialog/da1469x/include/hal/hal_gpio.h @@ -0,0 +1,184 @@ +/* + * 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. + */ + + +/** + * @addtogroup HAL + * @{ + * @defgroup HALGpio HAL GPIO + * @{ + */ + +#ifndef H_HAL_GPIO_ +#define H_HAL_GPIO_ + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * The "mode" of the gpio. The gpio is either an input, output, or it is + * "not connected" (the pin specified is not functioning as a gpio) + */ +enum hal_gpio_mode_e { + /** Not connected */ + HAL_GPIO_MODE_NC = -1, + /** Input */ + HAL_GPIO_MODE_IN = 0, + /** Output */ + HAL_GPIO_MODE_OUT = 1 +}; +typedef enum hal_gpio_mode_e hal_gpio_mode_t; + +/* + * The "pull" of the gpio. This is either an input or an output. + */ +enum hal_gpio_pull { + /** Pull-up/down not enabled */ + HAL_GPIO_PULL_NONE = 0, + /** Pull-up enabled */ + HAL_GPIO_PULL_UP = 1, + /** Pull-down enabled */ + HAL_GPIO_PULL_DOWN = 2 +}; +typedef enum hal_gpio_pull hal_gpio_pull_t; + +/* + * IRQ trigger type. + */ +enum hal_gpio_irq_trigger { + HAL_GPIO_TRIG_NONE = 0, + /** IRQ occurs on rising edge */ + HAL_GPIO_TRIG_RISING = 1, + /** IRQ occurs on falling edge */ + HAL_GPIO_TRIG_FALLING = 2, + /** IRQ occurs on either edge */ + HAL_GPIO_TRIG_BOTH = 3, + /** IRQ occurs when line is low */ + HAL_GPIO_TRIG_LOW = 4, + /** IRQ occurs when line is high */ + HAL_GPIO_TRIG_HIGH = 5 +}; +typedef enum hal_gpio_irq_trigger hal_gpio_irq_trig_t; + +/* Function proto for GPIO irq handler functions */ +typedef void (*hal_gpio_irq_handler_t)(void *arg); + +/** + * Initializes the specified pin as an input + * + * @param pin Pin number to set as input + * @param pull pull type + * + * @return int 0: no error; -1 otherwise. + */ +int hal_gpio_init_in(int pin, hal_gpio_pull_t pull); + +/** + * Initialize the specified pin as an output, setting the pin to the specified + * value. + * + * @param pin Pin number to set as output + * @param val Value to set pin + * + * @return int 0: no error; -1 otherwise. + */ +int hal_gpio_init_out(int pin, int val); + +/** + * Deinitialize the specified pin to revert the previous initialization + * + * @param pin Pin number to unset + * + * @return int 0: no error; -1 otherwise. + */ +int hal_gpio_deinit(int pin); + +/** + * Write a value (either high or low) to the specified pin. + * + * @param pin Pin to set + * @param val Value to set pin (0:low 1:high) + */ +void hal_gpio_write(int pin, int val); + +/** + * Reads the specified pin. + * + * @param pin Pin number to read + * + * @return int 0: low, 1: high + */ +int hal_gpio_read(int pin); + +/** + * Toggles the specified pin + * + * @param pin Pin number to toggle + * + * @return current gpio state int 0: low, 1: high + */ +int hal_gpio_toggle(int pin); + +/** + * Initialize a given pin to trigger a GPIO IRQ callback. + * + * @param pin The pin to trigger GPIO interrupt on + * @param handler The handler function to call + * @param arg The argument to provide to the IRQ handler + * @param trig The trigger mode (e.g. rising, falling) + * @param pull The mode of the pin (e.g. pullup, pulldown) + * + * @return 0 on success, non-zero error code on failure. + */ +int hal_gpio_irq_init(int pin, hal_gpio_irq_handler_t handler, void *arg, + hal_gpio_irq_trig_t trig, hal_gpio_pull_t pull); + +/** + * Release a pin from being configured to trigger IRQ on state change. + * + * @param pin The pin to release + */ +void hal_gpio_irq_release(int pin); + +/** + * Enable IRQs on the passed pin + * + * @param pin The pin to enable IRQs on + */ +void hal_gpio_irq_enable(int pin); + +/** + * Disable IRQs on the passed pin + * + * @param pin The pin to disable IRQs on + */ +void hal_gpio_irq_disable(int pin); + + +#ifdef __cplusplus +} +#endif + +#endif /* H_HAL_GPIO_ */ + +/** + * @} HALGpio + * @} HAL + */ diff --git a/hw/mcu/dialog/da1469x/include/mcu/da1469x_clock.h b/hw/mcu/dialog/da1469x/include/mcu/da1469x_clock.h new file mode 100644 index 000000000..3c697747d --- /dev/null +++ b/hw/mcu/dialog/da1469x/include/mcu/da1469x_clock.h @@ -0,0 +1,138 @@ +/* + * Licensed to the Apache Software Foundation (ASF) under one + * or more contributor license agreements. See the NOTICE file + * distributed with this work for additional information + * regarding copyright ownership. The ASF licenses this file + * to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance + * with the License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, + * software distributed under the License is distributed on an + * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY + * KIND, either express or implied. See the License for the + * specific language governing permissions and limitations + * under the License. + */ + +#ifndef __MCU_DA1469X_CLOCK_H_ +#define __MCU_DA1469X_CLOCK_H_ + +#include +#include "mcu/da1469x_hal.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Initialize XTAL32M + */ +void da1469x_clock_sys_xtal32m_init(void); + +/** + * Enable XTAL32M + */ +void da1469x_clock_sys_xtal32m_enable(void); + +/** + * Wait for XTAL32M to settle + */ +void da1469x_clock_sys_xtal32m_wait_to_settle(void); + +/** + * Switch sys_clk to XTAL32M + * + * Caller shall ensure that XTAL32M is already settled. + */ +void da1469x_clock_sys_xtal32m_switch(void); + +/** + * Switch sys_clk to XTAL32M + * + * Waits for XTAL32M to settle before switching. + */ +void da1469x_clock_sys_xtal32m_switch_safe(void); + +/** + * Disable RC32M + */ +void da1469x_clock_sys_rc32m_disable(void); + +/** + * Enable AMBA clock(s) + * + * @param mask + */ +static inline void +da1469x_clock_amba_enable(uint32_t mask) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + CRG_TOP->CLK_AMBA_REG |= mask; + __HAL_ENABLE_INTERRUPTS(primask); +} + +/** + * Disable AMBA clock(s) + * + * @param uint32_t mask + */ +static inline void +da1469x_clock_amba_disable(uint32_t mask) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + CRG_TOP->CLK_AMBA_REG &= ~mask; + __HAL_ENABLE_INTERRUPTS(primask); +} + +/** + * Enable PLL96 + */ +static inline void +da1469x_clock_sys_pll_enable(void) +{ + CRG_XTAL->PLL_SYS_CTRL1_REG |= CRG_XTAL_PLL_SYS_CTRL1_REG_PLL_EN_Msk | + CRG_XTAL_PLL_SYS_CTRL1_REG_LDO_PLL_ENABLE_Msk; +} + +/** + * Disable PLL96 + * + * If PLL was used as SYS_CLOCK switches to XTAL32M. + */ +void da1469x_clock_sys_pll_disable(void); + +/** + * Checks whether PLL96 is locked and can be use as system clock or USB clock + * + * @return 0 if PLL is off, non-0 it its running + */ +static inline int +da1469x_clock_is_pll_locked(void) +{ + return 0 != (CRG_XTAL->PLL_SYS_STATUS_REG & CRG_XTAL_PLL_SYS_STATUS_REG_PLL_LOCK_FINE_Msk); +} + +/** + * Waits for PLL96 to lock. + */ +void da1469x_clock_pll_wait_to_lock(void); + +/** + * Switches system clock to PLL96 + * + * Caller shall ensure that PLL is already locked. + */ +void da1469x_clock_sys_pll_switch(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __MCU_DA1469X_CLOCK_H_ */ diff --git a/hw/mcu/dialog/da1469x/include/mcu/da1469x_hal.h b/hw/mcu/dialog/da1469x/include/mcu/da1469x_hal.h new file mode 100644 index 000000000..28fa1aa88 --- /dev/null +++ b/hw/mcu/dialog/da1469x/include/mcu/da1469x_hal.h @@ -0,0 +1,53 @@ +/* + * Licensed to the Apache Software Foundation (ASF) under one + * or more contributor license agreements. See the NOTICE file + * distributed with this work for additional information + * regarding copyright ownership. The ASF licenses this file + * to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance + * with the License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, + * software distributed under the License is distributed on an + * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY + * KIND, either express or implied. See the License for the + * specific language governing permissions and limitations + * under the License. + */ + +#ifndef __MCU_DA1469X_HAL_H_ +#define __MCU_DA1469X_HAL_H_ + +#include +#include "mcu/mcu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Helper functions to enable/disable interrupts. */ +#define __HAL_DISABLE_INTERRUPTS(x) \ + do { \ + x = __get_PRIMASK(); \ + __disable_irq(); \ + } while (0) + +#define __HAL_ENABLE_INTERRUPTS(x) \ + do { \ + if (!x) { \ + __enable_irq(); \ + } \ + } while (0) + +#define __HAL_ASSERT_CRITICAL() \ + do { \ + assert(__get_PRIMASK() & 1); \ + } while (0) + +#ifdef __cplusplus +} +#endif + +#endif /* __MCU_DA1469X_HAL_H_ */ diff --git a/hw/mcu/dialog/da1469x/include/mcu/mcu.h b/hw/mcu/dialog/da1469x/include/mcu/mcu.h new file mode 100644 index 000000000..1e6736785 --- /dev/null +++ b/hw/mcu/dialog/da1469x/include/mcu/mcu.h @@ -0,0 +1,165 @@ +/* + * Licensed to the Apache Software Foundation (ASF) under one + * or more contributor license agreements. See the NOTICE file + * distributed with this work for additional information + * regarding copyright ownership. The ASF licenses this file + * to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance + * with the License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, + * software distributed under the License is distributed on an + * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY + * KIND, either express or implied. See the License for the + * specific language governing permissions and limitations + * under the License. + */ + +#ifndef __MCU_MCU_H_ +#define __MCU_MCU_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "DA1469xAB.h" + +#define sec_text_ram_core __attribute__((section(".text_ram"))) __attribute__((noinline)) + +#define MCU_SYSVIEW_INTERRUPTS \ + "I#1=Reset,I#2=MNI,I#3=HardFault,I#4=MemoryMgmt,I#5=BusFault,I#6=UsageFault," \ + "I#7=SecureFault,I#11=SVCall,I#12=DebugMonitor,I#14=PendSV,I#15=SysTick," \ + "I#16=SENSOR_NODE,I#17=DMA,I#18=CHARGER_STATE,I#19=CHARGER_ERROR," \ + "I#20=CMAC2SYS,I#21=UART,I#22=UART2,I#23=UART3,I#24=I2C,I#25=I2C2,I#26=SPI," \ + "I#27=SPI2,I#28=PCM,I#29=SRC_IN,I#30=SRC_OUT,I#31=USB,I#32=TIMER," \ + "I#33=TIMER2,I#34=RTC,I#35=KEY_WKUP_GPIO,I#36=PDC,I#37=VBUS,I#38=MRM," \ + "I#39=MOTOR_CONTROLLER,I#40=TRNG,I#41=DCDC,I#42=XTAL32M_RDY,I#43=ADC," \ + "I#44=ADC2,I#45=CRYPTO,I#46=CAPTIMER1,I#47=RFDIAG,I#48=LCD_CONTROLLER," \ + "I#49=PLL_LOCK,I#50=TIMER3,I#51=TIMER4,I#52=LRA,I#53=RTC_EVENT," \ + "I#54=GPIO_P0,I#55=GPIO_P1" + +/** +* \brief GPIO function +* +*/ +typedef enum { + MCU_GPIO_FUNC_GPIO = 0, /**< GPIO */ + MCU_GPIO_FUNC_UART_RX = 1, /**< GPIO as UART RX */ + MCU_GPIO_FUNC_UART_TX = 2, /**< GPIO as UART TX */ + MCU_GPIO_FUNC_UART2_RX = 3, /**< GPIO as UART2 RX */ + MCU_GPIO_FUNC_UART2_TX = 4, /**< GPIO as UART2 TX */ + MCU_GPIO_FUNC_UART2_CTSN = 5, /**< GPIO as UART2 CTSN */ + MCU_GPIO_FUNC_UART2_RTSN = 6, /**< GPIO as UART2 RTSN */ + MCU_GPIO_FUNC_UART3_RX = 7, /**< GPIO as UART3 RX */ + MCU_GPIO_FUNC_UART3_TX = 8, /**< GPIO as UART3 TX */ + MCU_GPIO_FUNC_UART3_CTSN = 9, /**< GPIO as UART3 CTSN */ + MCU_GPIO_FUNC_UART3_RTSN = 10, /**< GPIO as UART3 RTSN */ + MCU_GPIO_FUNC_ISO_CLK = 11, /**< GPIO as ISO CLK */ + MCU_GPIO_FUNC_ISO_DATA = 12, /**< GPIO as ISO DATA */ + MCU_GPIO_FUNC_SPI_DI = 13, /**< GPIO as SPI DI */ + MCU_GPIO_FUNC_SPI_DO = 14, /**< GPIO as SPI DO */ + MCU_GPIO_FUNC_SPI_CLK = 15, /**< GPIO as SPI CLK */ + MCU_GPIO_FUNC_SPI_EN = 16, /**< GPIO as SPI EN */ + MCU_GPIO_FUNC_SPI2_DI = 17, /**< GPIO as SPI2 DI */ + MCU_GPIO_FUNC_SPI2_DO = 18, /**< GPIO as SPI2 DO */ + MCU_GPIO_FUNC_SPI2_CLK = 19, /**< GPIO as SPI2 CLK */ + MCU_GPIO_FUNC_SPI2_EN = 20, /**< GPIO as SPI2 EN */ + MCU_GPIO_FUNC_I2C_SCL = 21, /**< GPIO as I2C SCL */ + MCU_GPIO_FUNC_I2C_SDA = 22, /**< GPIO as I2C SDA */ + MCU_GPIO_FUNC_I2C2_SCL = 23, /**< GPIO as I2C2 SCL */ + MCU_GPIO_FUNC_I2C2_SDA = 24, /**< GPIO as I2C2 SDA */ + MCU_GPIO_FUNC_USB_SOF = 25, /**< GPIO as USB SOF */ + MCU_GPIO_FUNC_ADC = 26, /**< GPIO as ADC (dedicated pin) */ + MCU_GPIO_FUNC_USB = 27, /**< GPIO as USB */ + MCU_GPIO_FUNC_PCM_DI = 28, /**< GPIO as PCM DI */ + MCU_GPIO_FUNC_PCM_DO = 29, /**< GPIO as PCM DO */ + MCU_GPIO_FUNC_PCM_FSC = 30, /**< GPIO as PCM FSC */ + MCU_GPIO_FUNC_PCM_CLK = 31, /**< GPIO as PCM CLK */ + MCU_GPIO_FUNC_PDM_DATA = 32, /**< GPIO as PDM DATA */ + MCU_GPIO_FUNC_PDM_CLK = 33, /**< GPIO as PDM CLK */ + MCU_GPIO_FUNC_COEX_EXT_ACT = 34, /**< GPIO as COEX EXT ACT0 */ + MCU_GPIO_FUNC_COEX_SMART_ACT = 35, /**< GPIO as COEX SMART ACT */ + MCU_GPIO_FUNC_COEX_SMART_PRI = 36, /**< GPIO as COEX SMART PRI */ + MCU_GPIO_FUNC_PORT0_DCF = 37, /**< GPIO as PORT0 DCF */ + MCU_GPIO_FUNC_PORT1_DCF = 38, /**< GPIO as PORT1 DCF */ + MCU_GPIO_FUNC_PORT2_DCF = 39, /**< GPIO as PORT2 DCF */ + MCU_GPIO_FUNC_PORT3_DCF = 40, /**< GPIO as PORT3 DCF */ + MCU_GPIO_FUNC_PORT4_DCF = 41, /**< GPIO as PORT4 DCF */ + MCU_GPIO_FUNC_CLOCK = 42, /**< GPIO as CLOCK */ + MCU_GPIO_FUNC_PG = 43, /**< GPIO as PG */ + MCU_GPIO_FUNC_LCD = 44, /**< GPIO as LCD */ + MCU_GPIO_FUNC_LCD_SPI_DC = 45, /**< GPIO as LCD SPI DC */ + MCU_GPIO_FUNC_LCD_SPI_DO = 46, /**< GPIO as LCD SPI DO */ + MCU_GPIO_FUNC_LCD_SPI_CLK = 47, /**< GPIO as LCD SPI CLK */ + MCU_GPIO_FUNC_LCD_SPI_EN = 48, /**< GPIO as LCD SPI EN */ + MCU_GPIO_FUNC_TIM_PWM = 49, /**< GPIO as TIM PWM */ + MCU_GPIO_FUNC_TIM2_PWM = 50, /**< GPIO as TIM2 PWM */ + MCU_GPIO_FUNC_TIM_1SHOT = 51, /**< GPIO as TIM 1SHOT */ + MCU_GPIO_FUNC_TIM2_1SHOT = 52, /**< GPIO as TIM2 1SHOT */ + MCU_GPIO_FUNC_TIM3_PWM = 53, /**< GPIO as TIM3 PWM */ + MCU_GPIO_FUNC_TIM4_PWM = 54, /**< GPIO as TIM4 PWM */ + MCU_GPIO_FUNC_AGC_EXT = 55, /**< GPIO as AGC EXT */ + MCU_GPIO_FUNC_CMAC_DIAG0 = 56, /**< GPIO as CMAC DIAG0 */ + MCU_GPIO_FUNC_CMAC_DIAG1 = 57, /**< GPIO as CMAC DIAG1 */ + MCU_GPIO_FUNC_CMAC_DIAG2 = 58, /**< GPIO as CMAC DIAG2 */ + MCU_GPIO_FUNC_CMAC_DIAGX = 59, /**< GPIO as CMAC DIAGX */ + MCU_GPIO_FUNC_LAST, +} mcu_gpio_func; + +#define MCU_GPIO_MODE_INPUT 0x000 /**< GPIO as an input */ +#define MCU_GPIO_MODE_INPUT_PULLUP 0x100 /**< GPIO as an input with pull-up */ +#define MCU_GPIO_MODE_INPUT_PULLDOWN 0x200 /**< GPIO as an input with pull-down */ +#define MCU_GPIO_MODE_OUTPUT 0x300 /**< GPIO as an output */ +#define MCU_GPIO_MODE_OUTPUT_OPEN_DRAIN 0x700 /**< GPIO as an open-drain output */ + +#define MCU_GPIO_PORT0_PIN_COUNT 32 +#define MCU_GPIO_PORT0(pin) ((0 * 32) + (pin)) +#define MCU_GPIO_PORT1(pin) ((1 * 32) + (pin)) +#define MCU_DMA_CHAN_MAX 8 + +#define MCU_PIN_GPADC_SEL0 MCU_GPIO_PORT1(9) +#define MCU_PIN_GPADC_SEL1 MCU_GPIO_PORT0(25) +#define MCU_PIN_GPADC_SEL2 MCU_GPIO_PORT0(8) +#define MCU_PIN_GPADC_SEL3 MCU_GPIO_PORT0(9) +#define MCU_PIN_GPADC_SEL16 MCU_GPIO_PORT1(13) +#define MCU_PIN_GPADC_SEL17 MCU_GPIO_PORT1(12) +#define MCU_PIN_GPADC_SEL18 MCU_GPIO_PORT1(18) +#define MCU_PIN_GPADC_SEL19 MCU_GPIO_PORT1(19) +#define MCU_PIN_GPADC_DIFF0_P0 MCU_GPIO_PORT1(9) +#define MCU_PIN_GPADC_DIFF0_P1 MCU_GPIO_PORT0(25) +#define MCU_PIN_GPADC_DIFF1_P0 MCU_GPIO_PORT0(8) +#define MCU_PIN_GPADC_DIFF1_P1 MCU_GPIO_PORT0(9) + +#define MCU_PIN_SDADC0 MCU_GPIO_PORT1(9) +#define MCU_PIN_SDADC1 MCU_GPIO_PORT0(25) +#define MCU_PIN_SDADC2 MCU_GPIO_PORT0(8) +#define MCU_PIN_SDADC3 MCU_GPIO_PORT0(9) +#define MCU_PIN_SDADC4 MCU_GPIO_PORT1(14) +#define MCU_PIN_SDADC5 MCU_GPIO_PORT1(20) +#define MCU_PIN_SDADC6 MCU_GPIO_PORT1(21) +#define MCU_PIN_SDADC7 MCU_GPIO_PORT1(22) + +void mcu_gpio_set_pin_function(int pin, int mode, mcu_gpio_func func); +void mcu_gpio_enter_sleep(void); +void mcu_gpio_exit_sleep(void); + +#define MCU_MEM_QSPIF_M_END_REMAP_ADDRESS (0x800000) +#define MCU_MEM_QSPIF_M_START_ADDRESS (0x16000000) +#define MCU_MEM_QSPIF_M_END_ADDRESS (0x18000000) +#define MCU_MEM_SYSRAM_START_ADDRESS (0x20000000) +#define MCU_MEM_SYSRAM_END_ADDRESS (0x20080000) + +#define MCU_OTPM_BASE 0x30080000UL +#define MCU_OTPM_SIZE 4096 + +/* Largest group id seen on a DA14699 was 18 so far */ +#define MCU_TRIMV_GROUP_ID_MAX (18) + +#ifdef __cplusplus +} +#endif + +#endif /* __MCU_MCU_H_ */ + diff --git a/hw/mcu/dialog/da1469x/src/da1469x_clock.c b/hw/mcu/dialog/da1469x/src/da1469x_clock.c new file mode 100644 index 000000000..6b4f0e6cf --- /dev/null +++ b/hw/mcu/dialog/da1469x/src/da1469x_clock.c @@ -0,0 +1,159 @@ +/* + * 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 +#include +#include +#include "syscfg/syscfg.h" +#include "mcu/da1469x_hal.h" +#include "mcu/da1469x_clock.h" + +static inline bool +da1469x_clock_is_xtal32m_settled(void) +{ + return ((*(uint32_t *)0x5001001c & 0xff00) == 0) && + ((*(uint32_t *)0x50010054 & 0x000f) != 0xb); +} + +void +da1469x_clock_sys_xtal32m_init(void) +{ + uint32_t reg; + int xtalrdy_cnt; + + /* Number of lp_clk cycles (~30.5us) */ + xtalrdy_cnt = MYNEWT_VAL(MCU_CLOCK_XTAL32M_SETTLE_TIME_US) * 10 / 305; + + reg = CRG_XTAL->XTALRDY_CTRL_REG; + reg &= ~(CRG_XTAL_XTALRDY_CTRL_REG_XTALRDY_CLK_SEL_Msk | + CRG_XTAL_XTALRDY_CTRL_REG_XTALRDY_CNT_Msk); + reg |= xtalrdy_cnt; + CRG_XTAL->XTALRDY_CTRL_REG = reg; +} + +void +da1469x_clock_sys_xtal32m_enable(void) +{ + PDC->PDC_CTRL0_REG = (2 << PDC_PDC_CTRL0_REG_TRIG_SELECT_Pos) | + (15 << PDC_PDC_CTRL0_REG_TRIG_ID_Pos) | + (1 << PDC_PDC_CTRL0_REG_PDC_MASTER_Pos) | + (1 << PDC_PDC_CTRL0_REG_EN_XTAL_Pos); + + PDC->PDC_SET_PENDING_REG = 0; + PDC->PDC_ACKNOWLEDGE_REG = 0; +} + +void +da1469x_clock_sys_xtal32m_switch(void) +{ + if (CRG_TOP->CLK_CTRL_REG & CRG_TOP_CLK_CTRL_REG_RUNNING_AT_RC32M_Msk) { + CRG_TOP->CLK_SWITCH2XTAL_REG = CRG_TOP_CLK_SWITCH2XTAL_REG_SWITCH2XTAL_Msk; + } else { + CRG_TOP->CLK_CTRL_REG &= ~CRG_TOP_CLK_CTRL_REG_SYS_CLK_SEL_Msk; + } + + while (!(CRG_TOP->CLK_CTRL_REG & CRG_TOP_CLK_CTRL_REG_RUNNING_AT_XTAL32M_Msk)); +} + +void +da1469x_clock_sys_xtal32m_wait_to_settle(void) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + + NVIC_ClearPendingIRQ(XTAL32M_RDY_IRQn); + + if (!da1469x_clock_is_xtal32m_settled()) { + NVIC_EnableIRQ(XTAL32M_RDY_IRQn); + while (!NVIC_GetPendingIRQ(XTAL32M_RDY_IRQn)) { + __WFI(); + } + NVIC_DisableIRQ(XTAL32M_RDY_IRQn); + } + + __HAL_ENABLE_INTERRUPTS(primask); +} + +void +da1469x_clock_sys_xtal32m_switch_safe(void) +{ + da1469x_clock_sys_xtal32m_wait_to_settle(); + + da1469x_clock_sys_xtal32m_switch(); +} + +void +da1469x_clock_sys_rc32m_disable(void) +{ + CRG_TOP->CLK_RC32M_REG &= ~CRG_TOP_CLK_RC32M_REG_RC32M_ENABLE_Msk; +} + +void +da1469x_clock_lp_xtal32k_enable(void) +{ + CRG_TOP->CLK_XTAL32K_REG |= CRG_TOP_CLK_XTAL32K_REG_XTAL32K_ENABLE_Msk; +} + +void +da1469x_clock_lp_xtal32k_switch(void) +{ + CRG_TOP->CLK_CTRL_REG = (CRG_TOP->CLK_CTRL_REG & + ~CRG_TOP_CLK_CTRL_REG_LP_CLK_SEL_Msk) | + (2 << CRG_TOP_CLK_CTRL_REG_LP_CLK_SEL_Pos); +} + +void +da1469x_clock_pll_disable(void) +{ + while (CRG_TOP->CLK_CTRL_REG & CRG_TOP_CLK_CTRL_REG_RUNNING_AT_PLL96M_Msk) { + CRG_TOP->CLK_SWITCH2XTAL_REG = CRG_TOP_CLK_SWITCH2XTAL_REG_SWITCH2XTAL_Msk; + } + + CRG_XTAL->PLL_SYS_CTRL1_REG &= ~CRG_XTAL_PLL_SYS_CTRL1_REG_PLL_EN_Msk; +} + +void +da1469x_clock_pll_wait_to_lock(void) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + + NVIC_ClearPendingIRQ(PLL_LOCK_IRQn); + + if (!da1469x_clock_is_pll_locked()) { + NVIC_EnableIRQ(PLL_LOCK_IRQn); + while (!NVIC_GetPendingIRQ(PLL_LOCK_IRQn)) { + __WFI(); + } + NVIC_DisableIRQ(PLL_LOCK_IRQn); + } + + __HAL_ENABLE_INTERRUPTS(primask); +} + +void +da1469x_clock_sys_pll_switch(void) +{ + /* CLK_SEL_Msk == 3 means PLL */ + CRG_TOP->CLK_CTRL_REG |= CRG_TOP_CLK_CTRL_REG_SYS_CLK_SEL_Msk; + + while (!(CRG_TOP->CLK_CTRL_REG & CRG_TOP_CLK_CTRL_REG_RUNNING_AT_PLL96M_Msk)); +} diff --git a/hw/mcu/dialog/da1469x/src/hal_gpio.c b/hw/mcu/dialog/da1469x/src/hal_gpio.c new file mode 100644 index 000000000..e105cf2b0 --- /dev/null +++ b/hw/mcu/dialog/da1469x/src/hal_gpio.c @@ -0,0 +1,478 @@ + +/* + * 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 +#include +#include "syscfg/syscfg.h" +#include "mcu/da1469x_hal.h" +#include +#include "hal/hal_gpio.h" + +/* GPIO interrupts */ +#define HAL_GPIO_MAX_IRQ MYNEWT_VAL(MCU_GPIO_MAX_IRQ) + +#define GPIO_REG(name) ((__IO uint32_t *)(GPIO_BASE + offsetof(GPIO_Type, name))) +#define WAKEUP_REG(name) ((__IO uint32_t *)(WAKEUP_BASE + offsetof(WAKEUP_Type, name))) +#define CRG_TOP_REG(name) ((__IO uint32_t *)(CRG_TOP_BASE + offsetof(CRG_TOP_Type, name))) + +#ifndef MCU_GPIO_PORT0_PIN_COUNT +#define MCU_GPIO_PORT0_PIN_COUNT 32 +#endif + +#if (MCU_GPIO_PORT0_PIN_COUNT) == 32 +#define GPIO_PORT(pin) (((unsigned)(pin)) >> 5U) +#define GPIO_PORT_PIN(pin) (((unsigned)(pin)) & 31U) +#else +#define GPIO_PORT(pin) (((unsigned)(pin)) < MCU_GPIO_PORT0_PIN_COUNT ? 0 : 1) +#define GPIO_PORT_PIN(pin) ((unsigned)(pin) < MCU_GPIO_PORT0_PIN_COUNT ? \ + (pin) : (pin) - MCU_GPIO_PORT0_PIN_COUNT) +#endif + +#define GPIO_PIN_BIT(pin) (1 << GPIO_PORT_PIN(pin)) + +#define GPIO_PIN_DATA_REG_ADDR(pin) (GPIO_REG(P0_DATA_REG) + GPIO_PORT(pin)) +#define GPIO_PIN_DATA_REG(pin) *GPIO_PIN_DATA_REG_ADDR(pin) +#define GPIO_PIN_SET_DATA_REG_ADDR(pin) (GPIO_REG(P0_SET_DATA_REG) + GPIO_PORT(pin)) +#define GPIO_PIN_SET_DATA_REG(pin) *GPIO_PIN_SET_DATA_REG_ADDR(pin) +#define GPIO_PIN_RESET_DATA_REG_ADDR(pin) (GPIO_REG(P0_RESET_DATA_REG) + GPIO_PORT(pin)) +#define GPIO_PIN_RESET_DATA_REG(pin) *GPIO_PIN_RESET_DATA_REG_ADDR(pin) +#define GPIO_PIN_MODE_REG_ADDR(pin) (GPIO_REG(P0_00_MODE_REG) + (pin)) +#define GPIO_PIN_MODE_REG(pin) *GPIO_PIN_MODE_REG_ADDR(pin) +#define GPIO_PIN_PADPWR_CTRL_REG_ADDR(pin) (GPIO_REG(P0_PADPWR_CTRL_REG) + GPIO_PORT(pin)) +#define GPIO_PIN_PADPWR_CTRL_REG(pin) *GPIO_PIN_PADPWR_CTRL_REG_ADDR(pin) +#define GPIO_PIN_UNLATCH_ADDR(pin) (CRG_TOP_REG(P0_SET_PAD_LATCH_REG) + GPIO_PORT(pin) * 3) +#define GPIO_PIN_LATCH_ADDR(pin) (CRG_TOP_REG(P0_RESET_PAD_LATCH_REG) + GPIO_PORT(pin) * 3) + +#define WKUP_CTRL_REG_ADDR (WAKEUP_REG(WKUP_CTRL_REG)) +#define WKUP_RESET_IRQ_REG_ADDR (WAKEUP_REG(WKUP_RESET_IRQ_REG)) +#define WKUP_SELECT_PX_REG_ADDR(pin) (WAKEUP_REG(WKUP_SELECT_P0_REG) + GPIO_PORT(pin)) +#define WKUP_SELECT_PX_REG(pin) *(WKUP_SELECT_PX_REG_ADDR(pin)) +#define WKUP_POL_PX_REG_ADDR(pin) (WAKEUP_REG(WKUP_POL_P0_REG) + GPIO_PORT(pin)) +#define WKUP_POL_PX_SET_FALLING(pin) do { *(WKUP_POL_PX_REG_ADDR(pin)) |= GPIO_PIN_BIT(pin); } while (0) +#define WKUP_POL_PX_SET_RISING(pin) do { *(WKUP_POL_PX_REG_ADDR(pin)) &= ~GPIO_PIN_BIT(pin); } while (0) +#define WKUP_STAT_PX_REG_ADDR(pin) (WAKEUP_REG(WKUP_STATUS_P0_REG) + GPIO_PORT(pin)) +#define WKUP_STAT(pin) ((*(WKUP_STAT_PX_REG_ADDR(pin)) >> GPIO_PORT_PIN(pin)) & 1) +#define WKUP_CLEAR_PX_REG_ADDR(pin) (WAKEUP_REG(WKUP_CLEAR_P0_REG) + GPIO_PORT(pin)) +#define WKUP_CLEAR_PX(pin) do { (*(WKUP_CLEAR_PX_REG_ADDR(pin)) = GPIO_PIN_BIT(pin)); } while (0) +#define WKUP_SEL_GPIO_PX_REG_ADDR(pin) (WAKEUP_REG(WKUP_SEL_GPIO_P0_REG) + GPIO_PORT(pin)) +#define WKUP_SEL_GPIO_PX_REG(pin) *(WKUP_SEL_GPIO_PX_REG_ADDR(pin)) + +/* Storage for GPIO callbacks. */ +struct hal_gpio_irq { + int pin; + hal_gpio_irq_handler_t func; + void *arg; +}; + +static struct hal_gpio_irq hal_gpio_irqs[HAL_GPIO_MAX_IRQ]; + +#if MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM) >= 0 +static uint32_t g_mcu_gpio_latch_state[2]; +static uint8_t g_mcu_gpio_retained_num; +static struct da1469x_retreg g_mcu_gpio_retained[MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM)]; +#endif + +/* + * We assume that any latched pin has default configuration, i.e. was either + * not configured or was deinited. Any unlatched pin is considered to be used + * by someone. + * + * By default, all pins are assumed to have default configuration and are + * latched. This allows PD_COM to be disabled (if no other peripheral needs + * it) since we do not need GPIO mux to be active. + * + * Configuration of any pin shall be done as follows, with interrupts disabled: + * 1. call mcu_gpio_unlatch_prepare() to enable PD_COM if needed + * 2. configure pin + * 3. call mcu_gpio_unlatch() to actually unlatch pin + * + * Once pin is restored to default configuration it shall be latched again by + * calling mcu_gpio_latch(). + */ + +#if MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM) >= 0 +static void +mcu_gpio_retained_add_port(uint32_t latch_val, volatile uint32_t *base_reg) +{ + struct da1469x_retreg *retreg; + int pin; + + retreg = &g_mcu_gpio_retained[g_mcu_gpio_retained_num]; + + while (latch_val) { + assert(g_mcu_gpio_retained_num < MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM)); + + pin = __builtin_ctz(latch_val); + latch_val &= ~(1 << pin); + + da1469x_retreg_assign(retreg, &base_reg[pin]); + + g_mcu_gpio_retained_num++; + retreg++; + } +} +#endif + +static void +mcu_gpio_retained_refresh(void) +{ +#if MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM) >= 0 + g_mcu_gpio_retained_num = 0; + + mcu_gpio_retained_add_port(CRG_TOP->P0_PAD_LATCH_REG, &GPIO->P0_00_MODE_REG); + mcu_gpio_retained_add_port(CRG_TOP->P1_PAD_LATCH_REG, &GPIO->P1_00_MODE_REG); +#endif +} + +static inline void +mcu_gpio_unlatch_prepare(int pin) +{ + __HAL_ASSERT_CRITICAL(); + (void)pin; + + /* Acquire PD_COM if first pin will be unlatched */ +// if ((CRG_TOP->P0_PAD_LATCH_REG | CRG_TOP->P1_PAD_LATCH_REG) == 0) { +// da1469x_pd_acquire(MCU_PD_DOMAIN_COM); +// } +} + +static inline void +mcu_gpio_unlatch(int pin) +{ + __HAL_ASSERT_CRITICAL(); + + *GPIO_PIN_UNLATCH_ADDR(pin) = GPIO_PIN_BIT(pin); + mcu_gpio_retained_refresh(); +} + +static inline void +mcu_gpio_latch(int pin) +{ + (void)pin; +// uint32_t primask; +// uint32_t latch_pre; +// uint32_t latch_post; +// +// __HAL_DISABLE_INTERRUPTS(primask); +// +// latch_pre = CRG_TOP->P0_PAD_LATCH_REG | CRG_TOP->P1_PAD_LATCH_REG; +// +// *GPIO_PIN_LATCH_ADDR(pin) = GPIO_PIN_BIT(pin); +// mcu_gpio_retained_refresh(); +// +// latch_post = CRG_TOP->P0_PAD_LATCH_REG | CRG_TOP->P1_PAD_LATCH_REG; +// +// /* Release PD_COM if last pin was latched */ +// if (latch_pre && !latch_post) { +// da1469x_pd_release(MCU_PD_DOMAIN_COM); +// } +// +// __HAL_ENABLE_INTERRUPTS(primask); +} + +int +hal_gpio_init_in(int pin, hal_gpio_pull_t pull) +{ + volatile uint32_t *px_xx_mod_reg = GPIO_PIN_MODE_REG_ADDR(pin); + uint32_t regval; + uint32_t primask; + + switch (pull) { + case HAL_GPIO_PULL_UP: + regval = MCU_GPIO_FUNC_GPIO | MCU_GPIO_MODE_INPUT_PULLUP; + break; + case HAL_GPIO_PULL_DOWN: + regval = MCU_GPIO_FUNC_GPIO | MCU_GPIO_MODE_INPUT_PULLDOWN; + break; + case HAL_GPIO_PULL_NONE: + regval = MCU_GPIO_FUNC_GPIO | MCU_GPIO_MODE_INPUT; + break; + default: + return -1; + } + + __HAL_DISABLE_INTERRUPTS(primask); + + mcu_gpio_unlatch_prepare(pin); + + *px_xx_mod_reg = regval; + + mcu_gpio_unlatch(pin); + + __HAL_ENABLE_INTERRUPTS(primask); + + return 0; +} + +int +hal_gpio_init_out(int pin, int val) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + + mcu_gpio_unlatch_prepare(pin); + + GPIO_PIN_MODE_REG(pin) = MCU_GPIO_MODE_OUTPUT; + + if (val) { + GPIO_PIN_SET_DATA_REG(pin) = GPIO_PIN_BIT(pin); + } else { + GPIO_PIN_RESET_DATA_REG(pin) = GPIO_PIN_BIT(pin); + } + + mcu_gpio_unlatch(pin); + + __HAL_ENABLE_INTERRUPTS(primask); + + return 0; +} + +int +hal_gpio_deinit(int pin) +{ + /* Reset mode to default value and latch pin */ + GPIO_PIN_MODE_REG(pin) = 0x200; + GPIO_PIN_RESET_DATA_REG(pin) = GPIO_PIN_BIT(pin); + + mcu_gpio_latch(pin); + + return 0; +} + +void +hal_gpio_write(int pin, int val) +{ + if (val) { + GPIO_PIN_SET_DATA_REG(pin) = GPIO_PIN_BIT(pin); + } else { + GPIO_PIN_RESET_DATA_REG(pin) = GPIO_PIN_BIT(pin); + } +} + +int +hal_gpio_read(int pin) +{ + return (GPIO_PIN_DATA_REG(pin) >> GPIO_PORT_PIN(pin)) & 1; +} + +int +hal_gpio_toggle(int pin) +{ + int new_value = hal_gpio_read(pin) == 0; + + hal_gpio_write(pin, new_value); + + return new_value; +} + +static void +hal_gpio_irq_handler(void) +{ + struct hal_gpio_irq *irq; + uint32_t stat; + int i; + + *WKUP_RESET_IRQ_REG_ADDR = 1; + NVIC_ClearPendingIRQ(KEY_WKUP_GPIO_IRQn); + + for (i = 0; i < HAL_GPIO_MAX_IRQ; i++) { + irq = &hal_gpio_irqs[i]; + + /* Read latched status value from relevant GPIO port */ + stat = WKUP_STAT(irq->pin); + + if (irq->func && stat) { + irq->func(irq->arg); + } + + WKUP_CLEAR_PX(irq->pin); + } +} + +static void +hal_gpio_irq_setup(void) +{ + static uint8_t irq_setup; + int sr; + + if (!irq_setup) { + __HAL_DISABLE_INTERRUPTS(sr); + + irq_setup = 1; + + NVIC_ClearPendingIRQ(GPIO_P0_IRQn); + NVIC_ClearPendingIRQ(GPIO_P1_IRQn); + NVIC_SetVector(GPIO_P0_IRQn, (uint32_t)hal_gpio_irq_handler); + NVIC_SetVector(GPIO_P1_IRQn, (uint32_t)hal_gpio_irq_handler); + WAKEUP->WKUP_CTRL_REG = 0; + WAKEUP->WKUP_CLEAR_P0_REG = 0xFFFFFFFF; + WAKEUP->WKUP_CLEAR_P1_REG = 0x007FFFFF; + WAKEUP->WKUP_SELECT_P0_REG = 0; + WAKEUP->WKUP_SELECT_P1_REG = 0; + WAKEUP->WKUP_SEL_GPIO_P0_REG = 0; + WAKEUP->WKUP_SEL_GPIO_P1_REG = 0; + WAKEUP->WKUP_RESET_IRQ_REG = 0; + + CRG_TOP->CLK_TMR_REG |= CRG_TOP_CLK_TMR_REG_WAKEUPCT_ENABLE_Msk; + + __HAL_ENABLE_INTERRUPTS(sr); + NVIC_EnableIRQ(GPIO_P0_IRQn); + NVIC_EnableIRQ(GPIO_P1_IRQn); + } +} + +static int +hal_gpio_find_empty_slot(void) +{ + int i; + + for (i = 0; i < HAL_GPIO_MAX_IRQ; i++) { + if (hal_gpio_irqs[i].func == NULL) { + return i; + } + } + + return -1; +} + +int +hal_gpio_irq_init(int pin, hal_gpio_irq_handler_t handler, void *arg, + hal_gpio_irq_trig_t trig, hal_gpio_pull_t pull) +{ + int i; + + hal_gpio_irq_setup(); + + i = hal_gpio_find_empty_slot(); + /* If assert failed increase syscfg value MCU_GPIO_MAX_IRQ */ + assert(i >= 0); + if (i < 0) { + return -1; + } + + hal_gpio_init_in(pin, pull); + + switch (trig) { + case HAL_GPIO_TRIG_RISING: + WKUP_POL_PX_SET_RISING(pin); + break; + case HAL_GPIO_TRIG_FALLING: + WKUP_POL_PX_SET_FALLING(pin); + break; + case HAL_GPIO_TRIG_BOTH: + /* Not supported */ + default: + return -1; + } + + hal_gpio_irqs[i].pin = pin; + hal_gpio_irqs[i].func = handler; + hal_gpio_irqs[i].arg = arg; + + return 0; +} + +void +hal_gpio_irq_release(int pin) +{ + int i; + + hal_gpio_irq_disable(pin); + + for (i = 0; i < HAL_GPIO_MAX_IRQ; i++) { + if (hal_gpio_irqs[i].pin == pin && hal_gpio_irqs[i].func) { + hal_gpio_irqs[i].pin = -1; + hal_gpio_irqs[i].arg = NULL; + hal_gpio_irqs[i].func = NULL; + } + } +} + +void +hal_gpio_irq_enable(int pin) +{ + WKUP_SEL_GPIO_PX_REG(pin) |= GPIO_PIN_BIT(pin); +} + +void +hal_gpio_irq_disable(int pin) +{ + WKUP_SEL_GPIO_PX_REG(pin) &= ~GPIO_PIN_BIT(pin); + WKUP_CLEAR_PX(pin); +} + +void +mcu_gpio_set_pin_function(int pin, int mode, mcu_gpio_func func) +{ + uint32_t primask; + + __HAL_DISABLE_INTERRUPTS(primask); + + mcu_gpio_unlatch_prepare(pin); + + GPIO_PIN_MODE_REG(pin) = (func & GPIO_P0_00_MODE_REG_PID_Msk) | + (mode & (GPIO_P0_00_MODE_REG_PUPD_Msk | GPIO_P0_00_MODE_REG_PPOD_Msk)); + + mcu_gpio_unlatch(pin); + + __HAL_ENABLE_INTERRUPTS(primask); +} + +void +mcu_gpio_enter_sleep(void) +{ +#if MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM) >= 0 + if (g_mcu_gpio_retained_num == 0) { + return; + } + + g_mcu_gpio_latch_state[0] = CRG_TOP->P0_PAD_LATCH_REG; + g_mcu_gpio_latch_state[1] = CRG_TOP->P1_PAD_LATCH_REG; + + da1469x_retreg_update(g_mcu_gpio_retained, g_mcu_gpio_retained_num); + + CRG_TOP->P0_RESET_PAD_LATCH_REG = CRG_TOP_P0_PAD_LATCH_REG_P0_LATCH_EN_Msk; + CRG_TOP->P1_RESET_PAD_LATCH_REG = CRG_TOP_P1_PAD_LATCH_REG_P1_LATCH_EN_Msk; + + da1469x_pd_release(MCU_PD_DOMAIN_COM); +#endif +} + +void +mcu_gpio_exit_sleep(void) +{ +#if MYNEWT_VAL(MCU_GPIO_RETAINABLE_NUM) >= 0 + if (g_mcu_gpio_retained_num == 0) { + return; + } + + da1469x_pd_acquire(MCU_PD_DOMAIN_COM); + + da1469x_retreg_restore(g_mcu_gpio_retained, g_mcu_gpio_retained_num); + + /* Set pins states to their latched values */ + GPIO->P0_DATA_REG = GPIO->P0_DATA_REG; + GPIO->P1_DATA_REG = GPIO->P1_DATA_REG; + + CRG_TOP->P0_PAD_LATCH_REG = g_mcu_gpio_latch_state[0]; + CRG_TOP->P1_PAD_LATCH_REG = g_mcu_gpio_latch_state[1]; +#endif +} diff --git a/hw/mcu/dialog/da1469x/src/hal_system.c b/hw/mcu/dialog/da1469x/src/hal_system.c new file mode 100644 index 000000000..2841979f8 --- /dev/null +++ b/hw/mcu/dialog/da1469x/src/hal_system.c @@ -0,0 +1,136 @@ +/* + * 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 +#include "syscfg/syscfg.h" +#include "mcu/da1469x_clock.h" +#include "mcu/da1469x_lpclk.h" +#include "mcu/da1469x_pd.h" +#include "mcu/da1469x_pdc.h" +#include "mcu/da1469x_prail.h" +#include "hal/hal_system.h" +#include "os/os_cputime.h" + +#if !MYNEWT_VAL(BOOT_LOADER) +static enum hal_reset_reason g_hal_reset_reason; +#endif + +void +hal_system_init(void) +{ +#if MYNEWT_VAL(MCU_DCDC_ENABLE) + da1469x_prail_dcdc_enable(); +#endif + + /* + * RESET_STAT_REG has to be cleared to allow HW set bits during next reset + * so we should read it now and keep result for application to check at any + * time. This does not happen for bootloader since reading reset reason in + * bootloader would prevent application from reading it. + */ + +#if !MYNEWT_VAL(BOOT_LOADER) + uint32_t reg; + + reg = CRG_TOP->RESET_STAT_REG; + CRG_TOP->RESET_STAT_REG = 0; + + if (reg & CRG_TOP_RESET_STAT_REG_PORESET_STAT_Msk) { + g_hal_reset_reason = HAL_RESET_POR; + } else if (reg & CRG_TOP_RESET_STAT_REG_WDOGRESET_STAT_Msk) { + g_hal_reset_reason = HAL_RESET_WATCHDOG; + } else if (reg & CRG_TOP_RESET_STAT_REG_SWRESET_STAT_Msk) { + g_hal_reset_reason = HAL_RESET_SOFT; + } else if (reg & CRG_TOP_RESET_STAT_REG_HWRESET_STAT_Msk) { + g_hal_reset_reason = HAL_RESET_PIN; + } else { + g_hal_reset_reason = 0; + } +#endif +} + +void +hal_system_reset(void) +{ + +#if MYNEWT_VAL(HAL_SYSTEM_RESET_CB) + hal_system_reset_cb(); +#endif + + while (1) { + HAL_DEBUG_BREAK(); + CRG_TOP->SYS_CTRL_REG = 0x20; + NVIC_SystemReset(); + } +} + +int +hal_debugger_connected(void) +{ + return CRG_TOP->SYS_STAT_REG & CRG_TOP_SYS_STAT_REG_DBG_IS_ACTIVE_Msk; +} + +void +hal_system_clock_start(void) +{ + /* Reset clock dividers to 0 */ + CRG_TOP->CLK_AMBA_REG &= ~(CRG_TOP_CLK_AMBA_REG_HCLK_DIV_Msk | CRG_TOP_CLK_AMBA_REG_PCLK_DIV_Msk); + + /* PD_TIM is already started in SystemInit */ + + da1469x_clock_sys_xtal32m_init(); + da1469x_clock_sys_xtal32m_enable(); +#if MYNEWT_VAL(MCU_PLL_ENABLE) + da1469x_clock_sys_pll_enable(); +#endif +#if MYNEWT_VAL_CHOICE(MCU_SYSCLK_SOURCE, PLL96) + da1469x_clock_pll_wait_to_lock(); + da1469x_clock_sys_pll_switch(); +#endif +#if MYNEWT_VAL_CHOICE(MCU_SYSCLK_SOURCE, XTAL32M) + /* Switch to XTAL32M and disable RC32M */ + da1469x_clock_sys_xtal32m_switch_safe(); +#endif + da1469x_clock_sys_rc32m_disable(); + +#if MYNEWT_VAL_CHOICE(MCU_LPCLK_SOURCE, RCX) + /* Switch to RCX and calibrate it */ + da1469x_clock_lp_rcx_enable(); + da1469x_clock_lp_rcx_switch(); + da1469x_clock_lp_rcx_calibrate(); + da1469x_lpclk_enabled(); +#else + /* + * We cannot switch lp_clk to XTAL32K here since it needs some time to + * settle, so we just disable RCX (we don't need it) and then we'll handle + * switch to XTAL32K from sysinit since we need os_cputime for this. + */ + da1469x_clock_lp_rcx_disable(); +#endif +} + +enum hal_reset_reason +hal_reset_cause(void) +{ +#if MYNEWT_VAL(BOOT_LOADER) + return 0; +#else + return g_hal_reset_reason; +#endif +} diff --git a/hw/mcu/dialog/da1469x/src/hal_system_start.c b/hw/mcu/dialog/da1469x/src/hal_system_start.c new file mode 100644 index 000000000..bd2465042 --- /dev/null +++ b/hw/mcu/dialog/da1469x/src/hal_system_start.c @@ -0,0 +1,177 @@ +/* + * 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 +#include +#include "mcu/mcu.h" +#include "mcu/da1469x_hal.h" +#include +#include +#if MCUBOOT_MYNEWT +#include "bootutil/bootutil.h" +#include "bootutil/image.h" +#include "bootutil/bootutil_log.h" +#include "mcu/da1469x_dma.h" +#include "mcu/da1469x_otp.h" +#endif + +#if MYNEWT_VAL(BOOT_CUSTOM_START) && MCUBOOT_MYNEWT +sec_text_ram_core +#endif +void __attribute__((naked)) +hal_system_start(void *img_start) +{ + uint32_t img_data_addr; + uint32_t *img_data; + + img_data_addr = MCU_MEM_QSPIF_M_START_ADDRESS + (uint32_t)img_start; + + assert(img_data_addr < MCU_MEM_QSPIF_M_END_ADDRESS); + + img_data = (uint32_t *)img_data_addr; + + asm volatile (".syntax unified \n" + /* 1st word is stack pointer */ + " msr msp, %0 \n" + /* 2nd word is a reset handler (image entry) */ + " bx %1 \n" + : /* no output */ + : "r" (img_data[0]), "r" (img_data[1])); +} + +void +hal_system_restart(void *img_start) +{ + uint32_t primask __attribute__((unused)); + int i; + + /* + * Disable interrupts, and leave them disabled. + * They get re-enabled when system starts coming back again. + */ + __HAL_DISABLE_INTERRUPTS(primask); + + for (i = 0; i < sizeof(NVIC->ICER) / sizeof(NVIC->ICER[0]); i++) { + NVIC->ICER[i] = 0xffffffff; + } + + hal_system_start(img_start); +} + +#if MYNEWT_VAL(BOOT_CUSTOM_START) && MCUBOOT_MYNEWT +#define IMAGE_TLV_AES_NONCE 0x50 +#define IMAGE_TLV_SECRET_ID 0x60 + +sec_text_ram_core void +boot_custom_start(uintptr_t flash_base, struct boot_rsp *rsp) +{ + int rc; + struct image_tlv_iter it; + const struct flash_area *fap; + uint32_t off; + uint16_t len; + uint16_t type; + uint8_t buf[8]; + uint8_t key; + uint32_t nonce[2]; + bool has_aes_nonce; + bool has_secret_id; + DMA_Type *dma_regs = DMA; + uint32_t jump_offset = rsp->br_image_off + rsp->br_hdr->ih_hdr_size; + + BOOT_LOG_INF("Custom initialization"); + + /* skip to booting if we are running nonsecure mode */ + if (!(CRG_TOP->SECURE_BOOT_REG & 0x1)) { + hal_system_start((void *)(flash_base + jump_offset)); + } + + rc = flash_area_open(flash_area_id_from_image_slot(0), &fap); + assert(rc == 0); + + rc = bootutil_tlv_iter_begin(&it, rsp->br_hdr, fap, IMAGE_TLV_ANY, true); + assert(rc == 0); + + has_aes_nonce = has_secret_id = false; + while (true) { + rc = bootutil_tlv_iter_next(&it, &off, &len, &type); + assert(rc >= 0); + + if (rc > 0) { + break; + } + + if (type == IMAGE_TLV_AES_NONCE) { + assert(len == 8); + + rc = flash_area_read(fap, off, buf, len); + assert(rc == 0); + + nonce[0] = __builtin_bswap32(*(uint32_t *)buf); + nonce[1] = __builtin_bswap32(*(uint32_t *)(buf + 4)); + has_aes_nonce = true; + } else if (type == IMAGE_TLV_SECRET_ID) { + assert(len == 4); + + rc = flash_area_read(fap, off, buf, len); + assert(rc == 0); + + key = buf[0]; + has_secret_id = true; + } + } + + assert(has_aes_nonce && has_secret_id && key <= 7); + + /* enable OTP clock and set in read mode */ + da1469x_clock_amba_enable(CRG_TOP_CLK_AMBA_REG_OTP_ENABLE_Msk); + da1469x_otp_set_mode(OTPC_MODE_READ); + + /* disable decrypt on the fly and program start and end addresses */ + QSPIC->QSPIC_CTR_CTRL_REG = 0; + QSPIC->QSPIC_CTR_SADDR_REG = jump_offset; + QSPIC->QSPIC_CTR_EADDR_REG = QSPIC->QSPIC_CTR_SADDR_REG + + rsp->br_hdr->ih_img_size - 1; + + /* securely DMA hardware key from secret storage to QSPI decrypt engine */ + dma_regs->DMA_REQ_MUX_REG |= 0xf000; + dma_regs->DMA7_LEN_REG = 8; + dma_regs->DMA7_A_START_REG = MCU_OTPM_BASE + OTP_SEGMENT_QSPI_FW_KEYS + + (32 * key); + dma_regs->DMA7_B_START_REG = (uint32_t)&QSPIC->QSPIC_CTR_KEY_0_3_REG; + dma_regs->DMA7_CTRL_REG = DMA_DMA7_CTRL_REG_AINC_Msk | + DMA_DMA7_CTRL_REG_BINC_Msk | + (MCU_DMA_BUS_WIDTH_4B << DMA_DMA7_CTRL_REG_BW_Pos) | + DMA_DMA7_CTRL_REG_DMA_ON_Msk; + while (dma_regs->DMA7_IDX_REG != 8); + + /* program NONCE */ + QSPIC->QSPIC_CTR_NONCE_0_3_REG = nonce[0]; + QSPIC->QSPIC_CTR_NONCE_4_7_REG = nonce[1]; + + /* turn back on decrypt on the fly */ + QSPIC->QSPIC_CTR_CTRL_REG = 1; + + /* set OTP to standby and turn off clock */ + da1469x_otp_set_mode(OTPC_MODE_STBY); + da1469x_clock_amba_disable(CRG_TOP_CLK_AMBA_REG_OTP_ENABLE_Msk); + + hal_system_start((void *)(flash_base + jump_offset)); +} +#endif diff --git a/hw/mcu/dialog/da1469x/src/system_da1469x.c b/hw/mcu/dialog/da1469x/src/system_da1469x.c new file mode 100644 index 000000000..538bac79f --- /dev/null +++ b/hw/mcu/dialog/da1469x/src/system_da1469x.c @@ -0,0 +1,61 @@ +/* + * 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 "mcu/mcu.h" +#include + +extern uint8_t __StackLimit; + +uint32_t SystemCoreClock = 32000000; + +void +SystemInit(void) +{ + /* Enable FPU when using hard-float */ +#if (__FPU_USED == 1) + SCB->CPACR |= (3UL << 20) | (3UL << 22); + __DSB(); + __ISB(); +#endif + + /* Freez watchdog */ + GPREG->SET_FREEZE_REG |= GPREG_SET_FREEZE_REG_FRZ_SYS_WDOG_Msk; + /* Initialize power domains (disable radio only) */ + CRG_TOP->PMU_CTRL_REG = CRG_TOP_PMU_CTRL_REG_RADIO_SLEEP_Msk; + + CRG_TOP->P0_SET_PAD_LATCH_REG = CRG_TOP_P0_PAD_LATCH_REG_P0_LATCH_EN_Msk; + CRG_TOP->P1_SET_PAD_LATCH_REG = CRG_TOP_P1_PAD_LATCH_REG_P1_LATCH_EN_Msk; + + /* Reset clock dividers to 0 */ + CRG_TOP->CLK_AMBA_REG &= ~(CRG_TOP_CLK_AMBA_REG_HCLK_DIV_Msk | CRG_TOP_CLK_AMBA_REG_PCLK_DIV_Msk); + + /* PD_TIM is already started in SystemInit */ + + da1469x_clock_sys_xtal32m_init(); + da1469x_clock_sys_xtal32m_enable(); + da1469x_clock_sys_pll_enable(); + da1469x_clock_pll_wait_to_lock(); + /* Switch to XTAL32M and disable RC32M */ + da1469x_clock_sys_xtal32m_switch_safe(); + da1469x_clock_sys_rc32m_disable(); +} + +void _init(void) +{ +}