Merge pull request #427 from kasjer/kasjer/add-da1469x-support

Support for DA1469x MCU from Dialog Semiconductor
This commit is contained in:
Ha Thach 2020-06-30 01:20:56 +07:00 committed by GitHub
commit 05996aee64
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
30 changed files with 18835 additions and 0 deletions

View File

@ -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

View File

@ -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

View File

@ -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")
}

View File

@ -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 <hal/hal_gpio.h>
#include <mcu/mcu.h>
//--------------------------------------------------------------------+
// 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

View File

@ -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

Binary file not shown.

View File

@ -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

9
hw/mcu/dialog/README.md Normal file
View File

@ -0,0 +1,9 @@
# Dialog DA1469x MCU
**Dialog Semiconductors** provides SDKs for DA146x MCU family.
Most of the files there can't be redistributed.
Registers definition file `DA1469xAB.h` and some **ARM** originated headers are have licenses that allow
for redistribution.
Whole SDK repository can be downloaded from Dialog Semiconductor web page `https://www.dialog.com`

View File

@ -0,0 +1,27 @@
/* Copyright (c) 2009 - 2013 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,271 @@
/**************************************************************************//**
* @file cmsis_compiler.h
* @brief CMSIS compiler generic header file
* @version V5.1.0
* @date 09. October 2018
******************************************************************************/
/*
* Copyright (c) 2009-2018 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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 __CMSIS_COMPILER_H
#define __CMSIS_COMPILER_H
#include <stdint.h>
/*
* Arm Compiler 4/5
*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*
* Arm Compiler 6.6 LTM (armclang)
*/
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100)
#include "cmsis_armclang_ltm.h"
/*
* Arm Compiler above 6.10.1 (armclang)
*/
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100)
#include "cmsis_armclang.h"
/*
* GNU Compiler
*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*
* IAR Compiler
*/
#elif defined ( __ICCARM__ )
#include <cmsis_iccarm.h>
/*
* TI Arm Compiler
*/
#elif defined ( __TI_ARM__ )
#include <cmsis_ccs.h>
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed))
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed))
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __attribute__((packed)) T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
#ifndef __RESTRICT
#define __RESTRICT __restrict
#endif
/*
* TASKING Compiler
*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __packed__
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __packed__
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __packed__
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __packed__ T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __align(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
/*
* COSMIC Compiler
*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#ifndef __ASM
#define __ASM _asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
// NO RETURN is automatically detected hence no warning here
#define __NO_RETURN
#endif
#ifndef __USED
#warning No compiler specific solution for __USED. __USED is ignored.
#define __USED
#endif
#ifndef __WEAK
#define __WEAK __weak
#endif
#ifndef __PACKED
#define __PACKED @packed
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT @packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION @packed union
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
@packed struct T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
#define __ALIGNED(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
#else
#error Unknown compiler.
#endif
#endif /* __CMSIS_COMPILER_H */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,39 @@
/**************************************************************************//**
* @file cmsis_version.h
* @brief CMSIS Core(M) Version definitions
* @version V5.0.2
* @date 19. April 2017
******************************************************************************/
/*
* Copyright (c) 2009-2017 ARM Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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.
*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined (__clang__)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CMSIS_VERSION_H
#define __CMSIS_VERSION_H
/* CMSIS Version definitions */
#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */
#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
__CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
#endif

View File

@ -0,0 +1,950 @@
/**************************************************************************//**
* @file core_cm0.h
* @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File
* @version V5.0.6
* @date 13. March 2019
******************************************************************************/
/*
* Copyright (c) 2009-2019 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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.
*/
/* Copyright (c) 2019 Modified by Dialog Semiconductor */
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined (__clang__)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CM0_H_GENERIC
#define __CORE_CM0_H_GENERIC
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
\page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
CMSIS violates the following MISRA-C:2004 rules:
\li Required Rule 8.5, object/function definition in header file.<br>
Function definitions in header files are used to allow 'inlining'.
\li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
Unions are used for effective representation of core registers.
\li Advisory Rule 19.7, Function-like macro defined.<br>
Function-like macros are used to allow more efficient code.
*/
/*******************************************************************************
* CMSIS definitions
******************************************************************************/
/**
\ingroup Cortex_M0
@{
*/
#include "cmsis_version.h"
/* CMSIS CM0 definitions */
#define __CM0_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */
#define __CM0_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */
#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16U) | \
__CM0_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */
#define __CORTEX_M (0U) /*!< Cortex-M Core */
/** __FPU_USED indicates whether an FPU is used or not.
This core does not support an FPU at all
*/
#define __FPU_USED 0U
#if defined ( __CC_ARM )
#if defined __TARGET_FPU_VFP
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#if defined __ARM_FP
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined ( __GNUC__ )
#if defined (__VFP_FP__) && !defined(__SOFTFP__)
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined ( __ICCARM__ )
#if defined __ARMVFP__
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined ( __TI_ARM__ )
#if defined __TI_VFP_SUPPORT__
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined ( __TASKING__ )
#if defined __FPU_VFP__
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#elif defined ( __CSMC__ )
#if ( __CSMC__ & 0x400U)
#error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
#endif
#endif
#include "cmsis_compiler.h" /* CMSIS compiler specific defines */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_CM0_H_GENERIC */
#ifndef __CMSIS_GENERIC
#ifndef __CORE_CM0_H_DEPENDANT
#define __CORE_CM0_H_DEPENDANT
#ifdef __cplusplus
extern "C" {
#endif
/* check device defines and use defaults */
#if defined __CHECK_DEVICE_DEFINES
#ifndef __CM0_REV
#define __CM0_REV 0x0000U
#warning "__CM0_REV not defined in device header file; using default!"
#endif
#ifndef __NVIC_PRIO_BITS
#define __NVIC_PRIO_BITS 2U
#warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
#endif
#ifndef __Vendor_SysTickConfig
#define __Vendor_SysTickConfig 0U
#warning "__Vendor_SysTickConfig not defined in device header file; using default!"
#endif
#endif
/* IO definitions (access restrictions to peripheral registers) */
/**
\defgroup CMSIS_glob_defs CMSIS Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
*/
#ifdef __cplusplus
#define __I volatile /*!< Defines 'read only' permissions */
#else
#define __I volatile const /*!< Defines 'read only' permissions */
#endif
#define __O volatile /*!< Defines 'write only' permissions */
#define __IO volatile /*!< Defines 'read / write' permissions */
/* following defines should be used for structure members */
#define __IM volatile const /*! Defines 'read only' structure member permissions */
#define __OM volatile /*! Defines 'write only' structure member permissions */
#define __IOM volatile /*! Defines 'read / write' structure member permissions */
/*@} end of group Cortex_M0 */
/*******************************************************************************
* Register Abstraction
Core Register contain:
- Core Register
- Core NVIC Register
- Core SCB Register
- Core SysTick Register
******************************************************************************/
/**
\defgroup CMSIS_core_register Defines and Type Definitions
\brief Type definitions and defines for Cortex-M processor based devices.
*/
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_CORE Status and Control Registers
\brief Core Register type definitions.
@{
*/
/**
\brief Union type to access the Application Program Status Register (APSR).
*/
typedef union
{
struct
{
uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */
uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
uint32_t C:1; /*!< bit: 29 Carry condition code flag */
uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
uint32_t N:1; /*!< bit: 31 Negative condition code flag */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} APSR_Type;
/* APSR Register Definitions */
#define APSR_N_Pos 31U /*!< APSR: N Position */
#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */
#define APSR_Z_Pos 30U /*!< APSR: Z Position */
#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */
#define APSR_C_Pos 29U /*!< APSR: C Position */
#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */
#define APSR_V_Pos 28U /*!< APSR: V Position */
#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */
/**
\brief Union type to access the Interrupt Program Status Register (IPSR).
*/
typedef union
{
struct
{
uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} IPSR_Type;
/* IPSR Register Definitions */
#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */
#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */
/**
\brief Union type to access the Special-Purpose Program Status Registers (xPSR).
*/
typedef union
{
struct
{
uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */
uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
uint32_t C:1; /*!< bit: 29 Carry condition code flag */
uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
uint32_t N:1; /*!< bit: 31 Negative condition code flag */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} xPSR_Type;
/* xPSR Register Definitions */
#define xPSR_N_Pos 31U /*!< xPSR: N Position */
#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */
#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */
#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */
#define xPSR_C_Pos 29U /*!< xPSR: C Position */
#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */
#define xPSR_V_Pos 28U /*!< xPSR: V Position */
#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */
#define xPSR_T_Pos 24U /*!< xPSR: T Position */
#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */
#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */
#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */
/**
\brief Union type to access the Control Registers (CONTROL).
*/
typedef union
{
struct
{
uint32_t _reserved0:1; /*!< bit: 0 Reserved */
uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} CONTROL_Type;
/* CONTROL Register Definitions */
#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */
#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */
/*@} end of group CMSIS_CORE */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
\brief Type definitions for the NVIC Registers
@{
*/
/**
\brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
*/
typedef struct
{
__IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
uint32_t RESERVED0[31U];
__IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
uint32_t RESERVED1[31U];
__IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
uint32_t RESERVED2[31U];
__IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
uint32_t RESERVED3[31U];
uint32_t RESERVED4[64U];
__IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */
} NVIC_Type;
/*@} end of group CMSIS_NVIC */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_SCB System Control Block (SCB)
\brief Type definitions for the System Control Block Registers
@{
*/
/**
\brief Structure type to access the System Control Block (SCB).
*/
typedef struct
{
__IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
__IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
uint32_t RESERVED0;
__IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
__IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
__IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
uint32_t RESERVED1;
__IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */
__IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
} SCB_Type;
/* SCB CPUID Register Definitions */
#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */
#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */
#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */
#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */
#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */
#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */
/* SCB Interrupt Control State Register Definitions */
#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */
#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */
#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */
#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */
#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */
#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */
#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */
#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */
#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */
#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */
/* SCB Application Interrupt and Reset Control Register Definitions */
#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */
#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */
#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */
#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */
#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */
#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
/* SCB System Control Register Definitions */
#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */
#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */
#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */
#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
/* SCB Configuration Control Register Definitions */
#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */
#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */
#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
/* SCB System Handler Control and State Register Definitions */
#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */
#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
/*@} end of group CMSIS_SCB */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_SysTick System Tick Timer (SysTick)
\brief Type definitions for the System Timer Registers.
@{
*/
/**
\brief Structure type to access the System Timer (SysTick).
*/
typedef struct
{
__IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
__IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
__IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
__IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
} SysTick_Type;
/* SysTick Control / Status Register Definitions */
#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */
#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */
#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */
#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */
#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */
/* SysTick Reload Register Definitions */
#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */
#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */
/* SysTick Current Register Definitions */
#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */
#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */
/* SysTick Calibration Register Definitions */
#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */
#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */
#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */
#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */
/*@} end of group CMSIS_SysTick */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
\brief Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor.
Therefore they are not covered by the Cortex-M0 header file.
@{
*/
/*@} end of group CMSIS_CoreDebug */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_core_bitfield Core register bit field macros
\brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk).
@{
*/
/**
\brief Mask and shift a bit field value for use in a register bit range.
\param[in] field Name of the register bit field.
\param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type.
\return Masked and shifted value.
*/
#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk)
/**
\brief Mask and shift a register value to extract a bit filed value.
\param[in] field Name of the register bit field.
\param[in] value Value of register. This parameter is interpreted as an uint32_t type.
\return Masked and shifted bit field value.
*/
#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos)
/*@} end of group CMSIS_core_bitfield */
/**
\ingroup CMSIS_core_register
\defgroup CMSIS_core_base Core Definitions
\brief Definitions for base addresses, unions, and structures.
@{
*/
/* Memory mapping of Core Hardware */
#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
/*@} */
/*******************************************************************************
* Hardware Abstraction Layer
Core Function Interface contains:
- Core NVIC Functions
- Core SysTick Functions
- Core Register Access Functions
******************************************************************************/
/**
\defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
*/
/* ########################## NVIC functions #################################### */
/**
\ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_NVICFunctions NVIC Functions
\brief Functions that manage interrupts and exceptions via the NVIC.
@{
*/
#ifdef CMSIS_NVIC_VIRTUAL
#ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE
#define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h"
#endif
#include CMSIS_NVIC_VIRTUAL_HEADER_FILE
#else
#define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping
#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping
#define NVIC_EnableIRQ __NVIC_EnableIRQ
#define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ
#define NVIC_DisableIRQ __NVIC_DisableIRQ
#define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ
#define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ
#define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ
/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0 */
#define NVIC_SetPriority __NVIC_SetPriority
#define NVIC_GetPriority __NVIC_GetPriority
#define NVIC_SystemReset __NVIC_SystemReset
#endif /* CMSIS_NVIC_VIRTUAL */
#ifdef CMSIS_VECTAB_VIRTUAL
#ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE
#define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h"
#endif
#include CMSIS_VECTAB_VIRTUAL_HEADER_FILE
#else
#define NVIC_SetVector __NVIC_SetVector
#define NVIC_GetVector __NVIC_GetVector
#endif /* (CMSIS_VECTAB_VIRTUAL) */
#define NVIC_USER_IRQ_OFFSET 16
/* The following EXC_RETURN values are saved the LR on exception entry */
#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */
#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */
#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */
/* Interrupt Priorities are WORD accessible only under Armv6-M */
/* The following MACROS handle generation of the register offset and byte masks */
#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL)
#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) )
#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) )
#define __NVIC_SetPriorityGrouping(X) (void)(X)
#define __NVIC_GetPriorityGrouping() (0U)
/**
\brief Enable Interrupt
\details Enables a device specific interrupt in the NVIC interrupt controller.
\param [in] IRQn Device specific interrupt number.
\note IRQn must not be negative.
*/
__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
}
}
/**
\brief Get Interrupt Enable status
\details Returns a device specific interrupt enable status from the NVIC interrupt controller.
\param [in] IRQn Device specific interrupt number.
\return 0 Interrupt is not enabled.
\return 1 Interrupt is enabled.
\note IRQn must not be negative.
*/
__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
}
else
{
return(0U);
}
}
/**
\brief Disable Interrupt
\details Disables a device specific interrupt in the NVIC interrupt controller.
\param [in] IRQn Device specific interrupt number.
\note IRQn must not be negative.
*/
__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
__DSB();
__ISB();
}
}
/**
\brief Get Pending Interrupt
\details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt.
\param [in] IRQn Device specific interrupt number.
\return 0 Interrupt status is not pending.
\return 1 Interrupt status is pending.
\note IRQn must not be negative.
*/
__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
}
else
{
return(0U);
}
}
/**
\brief Set Pending Interrupt
\details Sets the pending bit of a device specific interrupt in the NVIC pending register.
\param [in] IRQn Device specific interrupt number.
\note IRQn must not be negative.
*/
__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
}
}
/**
\brief Clear Pending Interrupt
\details Clears the pending bit of a device specific interrupt in the NVIC pending register.
\param [in] IRQn Device specific interrupt number.
\note IRQn must not be negative.
*/
__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
}
}
/**
\brief Set Interrupt Priority
\details Sets the priority of a device specific interrupt or a processor exception.
The interrupt number can be positive to specify a device specific interrupt,
or negative to specify a processor exception.
\param [in] IRQn Interrupt number.
\param [in] priority Priority to set.
\note The priority cannot be set for every processor exception.
*/
__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
{
if ((int32_t)(IRQn) >= 0)
{
NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
(((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
}
else
{
SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
(((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
}
}
/**
\brief Get Interrupt Priority
\details Reads the priority of a device specific interrupt or a processor exception.
The interrupt number can be positive to specify a device specific interrupt,
or negative to specify a processor exception.
\param [in] IRQn Interrupt number.
\return Interrupt Priority.
Value is aligned automatically to the implemented priority bits of the microcontroller.
*/
__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn)
{
if ((int32_t)(IRQn) >= 0)
{
return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
}
else
{
return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
}
}
/**
\brief Encode Priority
\details Encodes the priority for an interrupt with the given priority group,
preemptive priority value, and subpriority value.
In case of a conflict between priority grouping and available
priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
\param [in] PriorityGroup Used priority group.
\param [in] PreemptPriority Preemptive priority value (starting from 0).
\param [in] SubPriority Subpriority value (starting from 0).
\return Encoded priority. Value can be used in the function \ref __NVIC_SetPriority().
*/
__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
{
uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
uint32_t PreemptPriorityBits;
uint32_t SubPriorityBits;
PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp);
SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS));
return (
((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) |
((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL)))
);
}
/**
\brief Decode Priority
\details Decodes an interrupt priority value with a given priority group to
preemptive priority value and subpriority value.
In case of a conflict between priority grouping and available
priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set.
\param [in] Priority Priority value, which can be retrieved with the function \ref __NVIC_GetPriority().
\param [in] PriorityGroup Used priority group.
\param [out] pPreemptPriority Preemptive priority value (starting from 0).
\param [out] pSubPriority Subpriority value (starting from 0).
*/
__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority)
{
uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
uint32_t PreemptPriorityBits;
uint32_t SubPriorityBits;
PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp);
SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS));
*pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL);
*pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL);
}
/**
\brief Set Interrupt Vector
\details Sets an interrupt vector in SRAM based interrupt vector table.
The interrupt number can be positive to specify a device specific interrupt,
or negative to specify a processor exception.
Address 0 must be mapped to SRAM.
\param [in] IRQn Interrupt number
\param [in] vector Address of interrupt handler function
*/
__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector)
{
uint32_t vectors = 0x0U;
(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector;
}
/**
\brief Get Interrupt Vector
\details Reads an interrupt vector from interrupt vector table.
The interrupt number can be positive to specify a device specific interrupt,
or negative to specify a processor exception.
\param [in] IRQn Interrupt number.
\return Address of interrupt handler function
*/
__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn)
{
uint32_t vectors = 0x0U;
return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4));
}
/**
\brief System Reset
\details Initiates a system reset request to reset the MCU.
*/
__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void)
{
__DSB(); /* Ensure all outstanding memory accesses included
buffered write are completed before reset */
SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
SCB_AIRCR_SYSRESETREQ_Msk);
__DSB(); /* Ensure completion of memory access */
for(;;) /* wait until reset */
{
__NOP();
}
}
/*@} end of CMSIS_Core_NVICFunctions */
/* ########################## FPU functions #################################### */
/**
\ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_FpuFunctions FPU Functions
\brief Function that provides FPU type.
@{
*/
/**
\brief get FPU type
\details returns the FPU type
\returns
- \b 0: No FPU
- \b 1: Single precision FPU
- \b 2: Double + Single precision FPU
*/
__STATIC_INLINE uint32_t SCB_GetFPUType(void)
{
return 0U; /* No FPU */
}
/*@} end of CMSIS_Core_FpuFunctions */
/* ################################## SysTick function ############################################ */
/**
\ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_SysTickFunctions SysTick Functions
\brief Functions that configure the System.
@{
*/
#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U)
/**
\brief System Tick Configuration
\details Initializes the System Timer and its interrupt, and starts the System Tick Timer.
Counter is in free running mode to generate periodic interrupts.
\param [in] ticks Number of ticks between two interrupts.
\return 0 Function succeeded.
\return 1 Function failed.
\note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the
function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
must contain a vendor-specific implementation of this function.
*/
__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
{
if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk)
{
return (1UL); /* Reload value impossible */
}
SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */
NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */
SysTick->VAL = 0UL; /* Load the SysTick Counter Value */
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
SysTick_CTRL_TICKINT_Msk |
SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
return (0UL); /* Function successful */
}
#endif
/*@} end of CMSIS_Core_SysTickFunctions */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_CM0_H_DEPENDANT */
#endif /* __CMSIS_GENERIC */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,347 @@
/******************************************************************************
* @file mpu_armv8.h
* @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU
* @version V5.1.0
* @date 08. March 2019
******************************************************************************/
/*
* Copyright (c) 2017-2019 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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.
*/
/* Copyright (c) 2019 Modified by Dialog Semiconductor */
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined (__clang__)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef ARM_MPU_ARMV8_H
#define ARM_MPU_ARMV8_H
/** \brief Attribute for device memory (outer only) */
#define ARM_MPU_ATTR_DEVICE ( 0U )
/** \brief Attribute for non-cacheable, normal memory */
#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U )
/** \brief Attribute for normal memory (outer and inner)
* \param NT Non-Transient: Set to 1 for non-transient data.
* \param WB Write-Back: Set to 1 to use write-back update policy.
* \param RA Read Allocation: Set to 1 to use cache allocation on read miss.
* \param WA Write Allocation: Set to 1 to use cache allocation on write miss.
*/
#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \
(((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U))
/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */
#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U)
/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */
#define ARM_MPU_ATTR_DEVICE_nGnRE (1U)
/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */
#define ARM_MPU_ATTR_DEVICE_nGRE (2U)
/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */
#define ARM_MPU_ATTR_DEVICE_GRE (3U)
/** \brief Memory Attribute
* \param O Outer memory attributes
* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes
*/
#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U)))
/** \brief Normal memory non-shareable */
#define ARM_MPU_SH_NON (0U)
/** \brief Normal memory outer shareable */
#define ARM_MPU_SH_OUTER (2U)
/** \brief Normal memory inner shareable */
#define ARM_MPU_SH_INNER (3U)
/** \brief Memory access permissions
* \param RO Read-Only: Set to 1 for read-only memory.
* \param NP Non-Privileged: Set to 1 for non-privileged memory.
*/
#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U))
/** \brief Region Base Address Register value
* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned.
* \param SH Defines the Shareability domain for this memory region.
* \param RO Read-Only: Set to 1 for a read-only memory region.
* \param NP Non-Privileged: Set to 1 for a non-privileged memory region.
* \param XN eXecute Never: Set to 1 for a non-executable memory region.
*/
#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \
((BASE & MPU_RBAR_BASE_Msk) | \
((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \
((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \
((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk))
/** \brief Region Limit Address Register value
* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended.
* \param IDX The attribute index to be associated with this memory region.
*/
#define ARM_MPU_RLAR(LIMIT, IDX) \
((LIMIT & MPU_RLAR_LIMIT_Msk) | \
((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \
(MPU_RLAR_EN_Msk))
#if defined(MPU_RLAR_PXN_Pos)
/** \brief Region Limit Address Register with PXN value
* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended.
* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region.
* \param IDX The attribute index to be associated with this memory region.
*/
#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \
((LIMIT & MPU_RLAR_LIMIT_Msk) | \
((PXN << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \
((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \
(MPU_RLAR_EN_Msk))
#endif
/**
* Struct for a single MPU Region
*/
typedef struct {
uint32_t RBAR; /*!< Region Base Address Register value */
uint32_t RLAR; /*!< Region Limit Address Register value */
} ARM_MPU_Region_t;
/** Enable the MPU.
* \param MPU_Control Default access permissions for unconfigured regions.
*/
__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control)
{
MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
#endif
__DSB();
__ISB();
}
/** Disable the MPU.
*/
__STATIC_INLINE void ARM_MPU_Disable(void)
{
__DMB();
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
#endif
MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
}
#ifdef MPU_NS
/** Enable the Non-secure MPU.
* \param MPU_Control Default access permissions for unconfigured regions.
*/
__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control)
{
MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
#endif
__DSB();
__ISB();
}
/** Disable the Non-secure MPU.
*/
__STATIC_INLINE void ARM_MPU_Disable_NS(void)
{
__DMB();
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
#endif
MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk;
}
#endif
/** Set the memory attribute encoding to the given MPU.
* \param mpu Pointer to the MPU to be configured.
* \param idx The attribute index to be set [0-7]
* \param attr The attribute value to be set.
*/
__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr)
{
const uint8_t reg = idx / 4U;
const uint32_t pos = ((idx % 4U) * 8U);
const uint32_t mask = 0xFFU << pos;
if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) {
return; // invalid index
}
mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask));
}
/** Set the memory attribute encoding.
* \param idx The attribute index to be set [0-7]
* \param attr The attribute value to be set.
*/
__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr)
{
ARM_MPU_SetMemAttrEx(MPU, idx, attr);
}
#ifdef MPU_NS
/** Set the memory attribute encoding to the Non-secure MPU.
* \param idx The attribute index to be set [0-7]
* \param attr The attribute value to be set.
*/
__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr)
{
ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr);
}
#endif
/** Clear and disable the given MPU region of the given MPU.
* \param mpu Pointer to MPU to be used.
* \param rnr Region number to be cleared.
*/
__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr)
{
mpu->RNR = rnr;
mpu->RLAR = 0U;
}
/** Clear and disable the given MPU region.
* \param rnr Region number to be cleared.
*/
__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr)
{
ARM_MPU_ClrRegionEx(MPU, rnr);
}
#ifdef MPU_NS
/** Clear and disable the given Non-secure MPU region.
* \param rnr Region number to be cleared.
*/
__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr)
{
ARM_MPU_ClrRegionEx(MPU_NS, rnr);
}
#endif
/** Configure the given MPU region of the given MPU.
* \param mpu Pointer to MPU to be used.
* \param rnr Region number to be configured.
* \param rbar Value for RBAR register.
* \param rlar Value for RLAR register.
*/
__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar)
{
mpu->RNR = rnr;
mpu->RBAR = rbar;
mpu->RLAR = rlar;
}
/** Configure the given MPU region.
* \param rnr Region number to be configured.
* \param rbar Value for RBAR register.
* \param rlar Value for RLAR register.
*/
__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar)
{
ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar);
}
#ifdef MPU_NS
/** Configure the given Non-secure MPU region.
* \param rnr Region number to be configured.
* \param rbar Value for RBAR register.
* \param rlar Value for RLAR register.
*/
__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar)
{
ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar);
}
#endif
/** Memcopy with strictly ordered memory access, e.g. for register targets.
* \param dst Destination data is copied to.
* \param src Source data is copied from.
* \param len Amount of data words to be copied.
*/
__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len)
{
uint32_t i;
for (i = 0U; i < len; ++i)
{
dst[i] = src[i];
}
}
/** Load the given number of MPU regions from a table to the given MPU.
* \param mpu Pointer to the MPU registers to be used.
* \param rnr First region number to be configured.
* \param table Pointer to the MPU configuration table.
* \param cnt Amount of regions to be configured.
*/
__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
{
const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U;
if (cnt == 1U) {
mpu->RNR = rnr;
ARM_MPU_OrderedMemcpy(&(mpu->RBAR), &(table->RBAR), rowWordSize);
} else {
uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U);
uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES;
mpu->RNR = rnrBase;
while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) {
uint32_t c = MPU_TYPE_RALIASES - rnrOffset;
ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize);
table += c;
cnt -= c;
rnrOffset = 0U;
rnrBase += MPU_TYPE_RALIASES;
mpu->RNR = rnrBase;
}
ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize);
}
}
/** Load the given number of MPU regions from a table.
* \param rnr First region number to be configured.
* \param table Pointer to the MPU configuration table.
* \param cnt Amount of regions to be configured.
*/
__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
{
ARM_MPU_LoadEx(MPU, rnr, table, cnt);
}
#ifdef MPU_NS
/** Load the given number of MPU regions from a table to the Non-secure MPU.
* \param rnr First region number to be configured.
* \param table Pointer to the MPU configuration table.
* \param cnt Amount of regions to be configured.
*/
__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
{
ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt);
}
#endif
#endif

View File

@ -0,0 +1,55 @@
/**************************************************************************//**
* @file system_ARMCM0.h
* @brief CMSIS Device System Header File for
* ARMCM0 Device
* @version V5.3.1
* @date 09. July 2018
******************************************************************************/
/*
* Copyright (c) 2009-2018 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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 SYSTEM_ARMCM0_H
#define SYSTEM_ARMCM0_H
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
\brief Setup the microcontroller system.
Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
/**
\brief Update SystemCoreClock variable.
Updates the SystemCoreClock with current core Clock retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
#ifdef __cplusplus
}
#endif
#endif /* SYSTEM_ARMCM0_H */

View File

@ -0,0 +1,72 @@
/**************************************************************************//**
* @file system_DA1469x.h
* @brief CMSIS Device System Header File for DA1469x Device
* @version V5.3.1
* @date 17. May 2019
******************************************************************************/
/*
* Copyright (c) 2009-2018 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed 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
*
* 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.
*/
/* Copyright (c) 2017 Modified by Dialog Semiconductor */
#ifndef SYSTEM_DA1469x_H
#define SYSTEM_DA1469x_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
\brief Setup the microcontroller system.
Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
/**
\brief Update SystemCoreClock variable.
Updates the SystemCoreClock with current core Clock retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
/**
* \brief Convert a CPU address to a physical address
*
* To calculate the physical address, the current remapping (SYS_CTRL_REG.REMAP_ADR0)
* is used.
*
* \param [in] addr address seen by CPU
*
* \return physical address (for DMA, AES/HASH etc.) -- can be same or different as addr
*
*/
extern uint32_t black_orca_phy_addr(uint32_t addr);
#ifdef __cplusplus
}
#endif
#endif /* SYSTEM_DA1469x_H */

View File

@ -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")
}

View File

@ -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
*/

View File

@ -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 <stdint.h>
#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_ */

View File

@ -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 <assert.h>
#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_ */

View File

@ -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_ */

View File

@ -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 <assert.h>
#include <stdbool.h>
#include <stdint.h>
#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));
}

View File

@ -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 <assert.h>
#include <stddef.h>
#include "syscfg/syscfg.h"
#include "mcu/da1469x_hal.h"
#include <mcu/mcu.h>
#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
}

View File

@ -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 <assert.h>
#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
}

View File

@ -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 <assert.h>
#include <stdint.h>
#include "mcu/mcu.h"
#include "mcu/da1469x_hal.h"
#include <flash_map/flash_map.h>
#include <mcu/da1469x_clock.h>
#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

View File

@ -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 <mcu/da1469x_clock.h>
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)
{
}

View File

@ -0,0 +1,842 @@
/*
* 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 "tusb_option.h"
#if TUSB_OPT_DEVICE_ENABLED && CFG_TUSB_MCU == OPT_MCU_DA1469X
#include "DA1469xAB.h"
#include "device/dcd.h"
/*------------------------------------------------------------------*/
/* MACRO TYPEDEF CONSTANT ENUM
*------------------------------------------------------------------*/
// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval)
// We disable SOF for now until needed later on
#define USE_SOF 0
#define EP_MAX 4
#define NFSR_NODE_RESET 0
#define NFSR_NODE_RESUME 1
#define NFSR_NODE_OPERATIONAL 2
#define NFSR_NODE_SUSPEND 3
static TU_ATTR_ALIGNED(4) uint8_t _setup_packet[8];
typedef struct
{
union
{
__IOM uint32_t epc_in;
__IOM uint32_t USB_EPC0_REG; /*!< (@ 0x00000080) Endpoint Control 0 Register */
__IOM uint32_t USB_EPC1_REG; /*!< (@ 0x000000A0) Endpoint Control Register 1 */
__IOM uint32_t USB_EPC3_REG; /*!< (@ 0x000000C0) Endpoint Control Register 3 */
__IOM uint32_t USB_EPC5_REG; /*!< (@ 0x000000E0) Endpoint Control Register 5 */
};
union
{
__IOM uint32_t txd;
__IOM uint32_t USB_TXD0_REG; /*!< (@ 0x00000084) Transmit Data 0 Register */
__IOM uint32_t USB_TXD1_REG; /*!< (@ 0x000000A4) Transmit Data Register 1 */
__IOM uint32_t USB_TXD2_REG; /*!< (@ 0x000000C4) Transmit Data Register 2 */
__IOM uint32_t USB_TXD3_REG; /*!< (@ 0x000000E4) Transmit Data Register 3 */
};
union
{
__IOM uint32_t txs;
__IOM uint32_t USB_TXS0_REG; /*!< (@ 0x00000088) Transmit Status 0 Register */
__IOM uint32_t USB_TXS1_REG; /*!< (@ 0x000000A8) Transmit Status Register 1 */
__IOM uint32_t USB_TXS2_REG; /*!< (@ 0x000000C8) Transmit Status Register 2 */
__IOM uint32_t USB_TXS3_REG; /*!< (@ 0x000000E8) Transmit Status Register 3 */
};
union
{
__IOM uint32_t txc;
__IOM uint32_t USB_TXC0_REG; /*!< (@ 0x0000008C) Transmit command 0 Register */
__IOM uint32_t USB_TXC1_REG; /*!< (@ 0x000000AC) Transmit Command Register 1 */
__IOM uint32_t USB_TXC2_REG; /*!< (@ 0x000000CC) Transmit Command Register 2 */
__IOM uint32_t USB_TXC3_REG; /*!< (@ 0x000000EC) Transmit Command Register 3 */
};
union
{
__IOM uint32_t epc_out;
__IOM uint32_t USB_EP0_NAK_REG; /*!< (@ 0x00000090) EP0 INNAK and OUTNAK Register */
__IOM uint32_t USB_EPC2_REG; /*!< (@ 0x000000B0) Endpoint Control Register 2 */
__IOM uint32_t USB_EPC4_REG; /*!< (@ 0x000000D0) Endpoint Control Register 4 */
__IOM uint32_t USB_EPC6_REG; /*!< (@ 0x000000F0) Endpoint Control Register 6 */
};
union
{
__IOM uint32_t rxd;
__IOM uint32_t USB_RXD0_REG; /*!< (@ 0x00000094) Receive Data 0 Register */
__IOM uint32_t USB_RXD1_REG; /*!< (@ 0x000000B4) Receive Data Register,1 */
__IOM uint32_t USB_RXD2_REG; /*!< (@ 0x000000D4) Receive Data Register 2 */
__IOM uint32_t USB_RXD3_REG; /*!< (@ 0x000000F4) Receive Data Register 3 */
};
union
{
__IOM uint32_t rxs;
__IOM uint32_t USB_RXS0_REG; /*!< (@ 0x00000098) Receive Status 0 Register */
__IOM uint32_t USB_RXS1_REG; /*!< (@ 0x000000B8) Receive Status Register 1 */
__IOM uint32_t USB_RXS2_REG; /*!< (@ 0x000000D8) Receive Status Register 2 */
__IOM uint32_t USB_RXS3_REG; /*!< (@ 0x000000F8) Receive Status Register 3 */
};
union
{
__IOM uint32_t rxc;
__IOM uint32_t USB_RXC0_REG; /*!< (@ 0x0000009C) Receive Command 0 Register */
__IOM uint32_t USB_RXC1_REG; /*!< (@ 0x000000BC) Receive Command Register 1 */
__IOM uint32_t USB_RXC2_REG; /*!< (@ 0x000000DC) Receive Command Register 2 */
__IOM uint32_t USB_RXC3_REG; /*!< (@ 0x000000FC) Receive Command Register 3 */
};
} EPx_REGS;
#define EP_REGS(first_ep_reg) (EPx_REGS*)(&USB->first_ep_reg)
// Dialog register fields and bit mask are very long. Filed masks repeat register names.
// Those convenience macros are a way to reduce complexity of register modification lines.
#define GET_BIT(val, field) (val & field ## _Msk) >> field ## _Pos
#define REG_GET_BIT(reg, field) (USB->reg & USB_ ## reg ## _ ## field ## _Msk)
#define REG_SET_BIT(reg, field) USB->reg |= USB_ ## reg ## _ ## field ## _Msk
#define REG_CLR_BIT(reg, field) USB->reg &= ~USB_ ## reg ## _ ## field ## _Msk
#define REG_SET_VAL(reg, field, val) USB->reg = (USB->reg & ~USB_ ## reg ## _ ## field ## _Msk) | (val << USB_ ## reg ## _ ## field ## _Pos)
typedef struct {
EPx_REGS * regs;
uint8_t * buffer;
// Total length of current transfer
uint16_t total_len;
// Bytes transferred so far
uint16_t transferred;
uint16_t max_packet_size;
// Packet size sent or received so far. It is used to modify transferred field
// after ACK is received or when filling ISO endpoint with size larger then
// FIFO size.
uint16_t last_packet_size;
uint8_t ep_addr;
// DATA0/1 toggle bit 1 DATA1 is expected or transmitted
uint8_t data1 : 1;
// Endpoint is stalled
uint8_t stall : 1;
} xfer_ctl_t;
static struct
{
bool vbus_present;
bool in_reset;
xfer_ctl_t xfer_status[EP_MAX][2];
} _dcd =
{
.vbus_present = false,
.xfer_status =
{
{ { .regs = EP_REGS(USB_EPC0_REG) }, { .regs = EP_REGS(USB_EPC0_REG) } },
{ { .regs = EP_REGS(USB_EPC1_REG) }, { .regs = EP_REGS(USB_EPC1_REG) } },
{ { .regs = EP_REGS(USB_EPC3_REG) }, { .regs = EP_REGS(USB_EPC3_REG) } },
{ { .regs = EP_REGS(USB_EPC5_REG) }, { .regs = EP_REGS(USB_EPC5_REG) } },
}
};
// Two endpoint 0 descriptor definition for unified dcd_edpt_open()
static const tusb_desc_endpoint_t ep0OUT_desc =
{
.bLength = sizeof(tusb_desc_endpoint_t),
.bDescriptorType = TUSB_DESC_ENDPOINT,
.bEndpointAddress = 0x00,
.bmAttributes = { .xfer = TUSB_XFER_CONTROL },
.wMaxPacketSize = { .size = CFG_TUD_ENDPOINT0_SIZE },
.bInterval = 0
};
static const tusb_desc_endpoint_t ep0IN_desc =
{
.bLength = sizeof(tusb_desc_endpoint_t),
.bDescriptorType = TUSB_DESC_ENDPOINT,
.bEndpointAddress = 0x80,
.bmAttributes = { .xfer = TUSB_XFER_CONTROL },
.wMaxPacketSize = { .size = CFG_TUD_ENDPOINT0_SIZE },
.bInterval = 0
};
#define XFER_CTL_BASE(_ep, _dir) &_dcd.xfer_status[_ep][_dir]
// Function could be called when VBUS change was detected.
void tusb_vbus_changed(bool present)
{
if (present != _dcd.vbus_present)
{
_dcd.vbus_present = present;
if (present)
{
USB->USB_MCTRL_REG = USB_USB_MCTRL_REG_USBEN_Msk;
USB->USB_NFSR_REG = 0;
USB->USB_FAR_REG = 0x80;
USB->USB_NFSR_REG = NFSR_NODE_RESET;
USB->USB_TXMSK_REG = 0;
USB->USB_RXMSK_REG = 0;
USB->USB_MAMSK_REG = USB_USB_MAMSK_REG_USB_M_INTR_Msk |
USB_USB_MAMSK_REG_USB_M_ALT_Msk |
USB_USB_MAMSK_REG_USB_M_WARN_Msk;
USB->USB_ALTMSK_REG = USB_USB_ALTMSK_REG_USB_M_RESET_Msk;
}
else
{
USB->USB_MCTRL_REG = 0;
}
}
}
static void transmit_packet(xfer_ctl_t * xfer)
{
int left_to_send;
uint8_t const *src;
EPx_REGS *regs = xfer->regs;
uint32_t txc;
txc = USB_USB_TXC1_REG_USB_TX_EN_Msk;
if (xfer->data1) txc |= USB_USB_TXC1_REG_USB_TOGGLE_TX_Msk;
src = &xfer->buffer[xfer->transferred];
left_to_send = xfer->total_len - xfer->transferred;
if (left_to_send > xfer->max_packet_size - xfer->last_packet_size)
{
left_to_send = xfer->max_packet_size - xfer->last_packet_size;
}
// Loop checks TCOUNT all the time since this value is saturated to 31
// and can't be read just once before.
while ((regs->txs & USB_USB_TXS1_REG_USB_TCOUNT_Msk) > 0 && left_to_send > 0)
{
regs->txd = *src++;
xfer->last_packet_size++;
left_to_send--;
}
if (tu_edpt_number(xfer->ep_addr) != 0)
{
if (left_to_send > 0)
{
// Max packet size is set to value greater then FIFO. Enable fifo level warning
// to handle larger packets.
txc |= USB_USB_TXC1_REG_USB_TFWL_Msk;
}
else
{
// Whole packet already in fifo, no need to refill it later. Mark last.
txc |= USB_USB_TXC1_REG_USB_LAST_Msk;
}
}
// Enable transfer with correct interrupts enabled
regs->txc = txc;
}
static void receive_packet(xfer_ctl_t *xfer, uint16_t bytes_in_fifo)
{
EPx_REGS *regs = xfer->regs;
uint16_t remaining = xfer->total_len - xfer->transferred;
uint16_t receive_this_time = bytes_in_fifo;
if (remaining <= bytes_in_fifo) receive_this_time = remaining;
uint8_t *buf = xfer->buffer + xfer->transferred + xfer->last_packet_size;
for (int i = 0; i < receive_this_time; ++i) buf[i] = regs->rxd;
xfer->transferred += receive_this_time;
xfer->last_packet_size += receive_this_time;
}
static void handle_ep0_rx(void)
{
int packet_size;
uint32_t rxs0 = USB->USB_RXS0_REG;
xfer_ctl_t *xfer = XFER_CTL_BASE(0, TUSB_DIR_OUT);
packet_size = GET_BIT(rxs0, USB_USB_RXS0_REG_USB_RCOUNT);
if (rxs0 & USB_USB_RXS0_REG_USB_SETUP_Msk)
{
xfer_ctl_t *xfer_in = XFER_CTL_BASE(0, TUSB_DIR_IN);
// Setup packet is in
for (int i = 0; i < packet_size; ++i) _setup_packet[i] = USB->USB_RXD0_REG;
xfer->stall = 0;
xfer->data1 = 1;
xfer_in->stall = 0;
xfer_in->data1 = 1;
REG_SET_BIT(USB_TXC0_REG, USB_TOGGLE_TX0);
REG_CLR_BIT(USB_EPC0_REG, USB_STALL);
dcd_event_setup_received(0, _setup_packet,true);
}
else
{
if (GET_BIT(rxs0, USB_USB_RXS0_REG_USB_TOGGLE_RX0) != xfer->data1)
{
// Toggle bit does not match discard packet
REG_SET_BIT(USB_RXC0_REG, USB_FLUSH);
}
else
{
receive_packet(xfer, packet_size);
xfer->data1 ^= 1;
if (xfer->total_len == xfer->transferred || xfer->last_packet_size < xfer->max_packet_size)
{
dcd_event_xfer_complete(0, 0, xfer->transferred, XFER_RESULT_SUCCESS, true);
}
else
{
xfer->last_packet_size = 0;
// Re-enable reception
REG_SET_BIT(USB_RXC0_REG, USB_RX_EN);
}
}
}
}
static void handle_ep0_tx(void)
{
uint32_t txs0;
xfer_ctl_t *xfer = XFER_CTL_BASE(0, TUSB_DIR_IN);
EPx_REGS *regs = xfer->regs;
txs0 = regs->USB_TXS0_REG;
if (GET_BIT(txs0, USB_USB_TXS0_REG_USB_TX_DONE))
{
// ACK received
if (GET_BIT(txs0, USB_USB_TXS0_REG_USB_ACK_STAT))
{
xfer->transferred += xfer->last_packet_size;
xfer->last_packet_size = 0;
xfer->data1 ^= 1;
REG_SET_VAL(USB_TXC0_REG, USB_TOGGLE_TX0, xfer->data1);
if (xfer->transferred == xfer->total_len)
{
dcd_event_xfer_complete(0, 0 | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true);
return;
}
}
else
{
// Start from the beginning
xfer->last_packet_size = 0;
}
transmit_packet(xfer);
}
}
static void handle_epx_rx_ev(uint8_t ep)
{
uint32_t rxs;
int packet_size;
xfer_ctl_t *xfer = XFER_CTL_BASE(ep, TUSB_DIR_OUT);
EPx_REGS *regs = xfer->regs;
rxs = regs->rxs;
if (GET_BIT(rxs, USB_USB_RXS1_REG_USB_RX_ERR))
{
regs->rxc |= USB_USB_RXC1_REG_USB_FLUSH_Msk;
}
else
{
packet_size = GET_BIT(rxs, USB_USB_RXS1_REG_USB_RXCOUNT);
receive_packet(xfer, packet_size);
if (GET_BIT(rxs, USB_USB_RXS1_REG_USB_RX_LAST))
{
if (GET_BIT(rxs, USB_USB_RXS1_REG_USB_TOGGLE_RX) != xfer->data1)
{
// Toggle bit does not match discard packet
regs->rxc |= USB_USB_RXC1_REG_USB_FLUSH_Msk;
}
else
{
xfer->data1 ^= 1;
if (xfer->total_len == xfer->transferred || xfer->last_packet_size < xfer->max_packet_size)
{
dcd_event_xfer_complete(0, xfer->ep_addr, xfer->transferred, XFER_RESULT_SUCCESS, true);
}
else
{
xfer->last_packet_size = 0;
// Re-enable reception
regs->rxc |= USB_USB_RXC1_REG_USB_RX_EN_Msk;
}
}
}
}
}
static void handle_rx_ev(void)
{
if (USB->USB_RXEV_REG & 1)
handle_epx_rx_ev(1);
if (USB->USB_RXEV_REG & 2)
handle_epx_rx_ev(2);
if (USB->USB_RXEV_REG & 4)
handle_epx_rx_ev(3);
}
static void handle_epx_tx_ev(xfer_ctl_t *xfer)
{
uint32_t usb_txs1_reg;
EPx_REGS *regs = xfer->regs;
usb_txs1_reg = regs->USB_TXS1_REG;
if (GET_BIT(usb_txs1_reg, USB_USB_TXS1_REG_USB_TX_DONE))
{
if (GET_BIT(usb_txs1_reg, USB_USB_TXS1_REG_USB_ACK_STAT))
{
// ACK received, update transfer state and DATA0/1 bit
xfer->transferred += xfer->last_packet_size;
xfer->last_packet_size = 0;
xfer->data1 ^= 1;
if (xfer->transferred == xfer->total_len)
{
dcd_event_xfer_complete(0, xfer->ep_addr, xfer->total_len, XFER_RESULT_SUCCESS, true);
return;
}
}
else
{
xfer->last_packet_size = 0;
}
transmit_packet(xfer);
}
}
static void handle_tx_ev(void)
{
if (USB->USB_TXEV_REG & 1)
handle_epx_tx_ev(XFER_CTL_BASE(1, TUSB_DIR_IN));
if (USB->USB_TXEV_REG & 2)
handle_epx_tx_ev(XFER_CTL_BASE(2, TUSB_DIR_IN));
if (USB->USB_TXEV_REG & 4)
handle_epx_tx_ev(XFER_CTL_BASE(3, TUSB_DIR_IN));
}
static void handle_bus_reset(void)
{
USB->USB_NFSR_REG = 0;
USB->USB_FAR_REG = 0x80;
USB->USB_ALTMSK_REG = 0;
USB->USB_NFSR_REG = NFSR_NODE_RESET;
USB->USB_TXMSK_REG = 0;
USB->USB_RXMSK_REG = 0;
(void)USB->USB_ALTEV_REG;
_dcd.in_reset = true;
dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true);
USB->USB_MAMSK_REG = USB_USB_MAMSK_REG_USB_M_INTR_Msk |
#if USE_SOF
USB_USB_MAMSK_REG_USB_M_FRAME_Msk |
#endif
USB_USB_MAMSK_REG_USB_M_WARN_Msk |
USB_USB_MAMSK_REG_USB_M_ALT_Msk;
USB->USB_NFSR_REG = NFSR_NODE_OPERATIONAL;
USB->USB_ALTMSK_REG = USB_USB_ALTMSK_REG_USB_M_SD3_Msk |
USB_USB_ALTMSK_REG_USB_M_RESUME_Msk;
// There is no information about end of reset state
// USB_FRAME event will be used to enable reset detection again
REG_SET_BIT(USB_MAEV_REG, USB_FRAME);
dcd_edpt_open (0, &ep0OUT_desc);
dcd_edpt_open (0, &ep0IN_desc);
}
static void handle_alt_ev(void)
{
uint32_t alt_ev = USB->USB_ALTEV_REG;
if (GET_BIT(alt_ev, USB_USB_ALTEV_REG_USB_RESET))
{
handle_bus_reset();
}
else
{
if (GET_BIT(alt_ev, USB_USB_ALTEV_REG_USB_RESUME))
{
USB->USB_NFSR_REG = NFSR_NODE_OPERATIONAL;
USB->USB_ALTMSK_REG &= ~USB_USB_ALTMSK_REG_USB_M_RESUME_Msk;
USB->USB_ALTMSK_REG |= USB_USB_ALTMSK_REG_USB_M_SD3_Msk;
dcd_event_bus_signal(0, DCD_EVENT_RESUME, true);
}
if (GET_BIT(alt_ev, USB_USB_ALTEV_REG_USB_SD3))
{
USB->USB_NFSR_REG = NFSR_NODE_SUSPEND;
USB->USB_ALTMSK_REG |= USB_USB_ALTMSK_REG_USB_M_RESUME_Msk;
USB->USB_ALTMSK_REG &= ~USB_USB_ALTMSK_REG_USB_M_SD3_Msk | USB_USB_ALTMSK_REG_USB_M_SD5_Msk;
dcd_event_bus_signal(0, DCD_EVENT_SUSPEND, true);
}
}
}
static void handle_epx_tx_refill(uint8_t ep)
{
transmit_packet(XFER_CTL_BASE(ep, TUSB_DIR_IN));
}
static void handle_fifo_warning(void)
{
uint32_t fifo_warning = USB->USB_FWEV_REG;
if (fifo_warning & 0x01)
handle_epx_tx_refill(1);
if (fifo_warning & 0x02)
handle_epx_tx_refill(2);
if (fifo_warning & 0x04)
handle_epx_tx_refill(3);
if (fifo_warning & 0x10)
handle_epx_rx_ev(1);
if (fifo_warning & 0x20)
handle_epx_rx_ev(2);
if (fifo_warning & 0x40)
handle_epx_rx_ev(3);
}
static void handle_ep0_nak(void)
{
uint32_t ep0_nak = USB->USB_EP0_NAK_REG;
if (REG_GET_BIT(USB_EPC0_REG, USB_STALL))
{
if (GET_BIT(ep0_nak, USB_USB_EP0_NAK_REG_USB_EP0_INNAK))
{
// EP0 is stalled and NAK was sent, it means that RX is enabled
// Disable RX for now.
REG_CLR_BIT(USB_RXC0_REG, USB_RX_EN);
REG_SET_BIT(USB_TXC0_REG, USB_TX_EN);
}
if (GET_BIT(ep0_nak, USB_USB_EP0_NAK_REG_USB_EP0_OUTNAK))
{
REG_SET_BIT(USB_RXC0_REG, USB_RX_EN);
}
}
else
{
REG_CLR_BIT(USB_MAMSK_REG, USB_M_EP0_NAK);
}
}
/*------------------------------------------------------------------*/
/* Controller API
*------------------------------------------------------------------*/
void dcd_init(uint8_t rhport)
{
(void)rhport;
USB->USB_MCTRL_REG = USB_USB_MCTRL_REG_USBEN_Msk;
tusb_vbus_changed((CRG_TOP->ANA_STATUS_REG & CRG_TOP_ANA_STATUS_REG_VBUS_AVAILABLE_Msk) != 0);
}
void dcd_int_enable(uint8_t rhport)
{
(void)rhport;
NVIC_EnableIRQ(USB_IRQn);
}
void dcd_int_disable(uint8_t rhport)
{
(void)rhport;
NVIC_DisableIRQ(USB_IRQn);
}
void dcd_set_address(uint8_t rhport, uint8_t dev_addr)
{
(void)rhport;
// Set default address for one ZLP
USB->USB_EPC0_REG = USB_USB_EPC0_REG_USB_DEF_Msk;
USB->USB_FAR_REG = (dev_addr & USB_USB_FAR_REG_USB_AD_Msk) | USB_USB_FAR_REG_USB_AD_EN_Msk;
dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0);
}
void dcd_remote_wakeup(uint8_t rhport)
{
(void)rhport;
}
void dcd_connect(uint8_t rhport)
{
(void)rhport;
REG_SET_BIT(USB_MCTRL_REG, USB_NAT);
}
void dcd_disconnect(uint8_t rhport)
{
(void)rhport;
REG_CLR_BIT(USB_MCTRL_REG, USB_NAT);
}
/*------------------------------------------------------------------*/
/* DCD Endpoint port
*------------------------------------------------------------------*/
bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt)
{
uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress);
uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress);
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
uint8_t iso_mask = 0;
(void)rhport;
TU_ASSERT(desc_edpt->wMaxPacketSize.size <= 1023);
TU_ASSERT(epnum < EP_MAX);
xfer->max_packet_size = desc_edpt->wMaxPacketSize.size;
xfer->ep_addr = desc_edpt->bEndpointAddress;
xfer->data1 = 0;
if (epnum != 0 && desc_edpt->bmAttributes.xfer == 1) iso_mask = USB_USB_EPC1_REG_USB_ISO_Msk;
if (epnum == 0)
{
USB->USB_MAMSK_REG |= USB_USB_MAMSK_REG_USB_M_EP0_RX_Msk |
USB_USB_MAMSK_REG_USB_M_EP0_TX_Msk;
}
else
{
if (dir == TUSB_DIR_OUT)
{
xfer->regs->epc_out = epnum | USB_USB_EPC1_REG_USB_EP_EN_Msk | iso_mask;
USB->USB_RXMSK_REG |= 0x101 << (epnum - 1);
REG_SET_BIT(USB_MAMSK_REG, USB_M_RX_EV);
}
else
{
xfer->regs->epc_in = epnum | USB_USB_EPC1_REG_USB_EP_EN_Msk | iso_mask;
USB->USB_TXMSK_REG |= 0x101 << (epnum - 1);
REG_SET_BIT(USB_MAMSK_REG, USB_M_TX_EV);
}
}
return true;
}
bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes)
{
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
(void)rhport;
xfer->buffer = buffer;
xfer->total_len = total_bytes;
xfer->last_packet_size = 0;
xfer->transferred = 0;
if (dir == TUSB_DIR_OUT)
{
if (epnum != 0)
{
if (xfer->max_packet_size > 64)
{
// For endpoint size greater then FIFO size enable FIFO level warning interrupt
// when FIFO has less then 17 bytes free.
xfer->regs->rxc |= USB_USB_RXC1_REG_USB_RFWL_Msk;
}
else
{
// If max_packet_size would fit in FIFO no need for FIFO level warning interrupt.
xfer->regs->rxc &= ~USB_USB_RXC1_REG_USB_RFWL_Msk;
}
}
// USB_RX_EN bit is in same place for all endpoints.
xfer->regs->rxc = USB_USB_RXC0_REG_USB_RX_EN_Msk;
}
else // IN
{
transmit_packet(xfer);
}
return true;
}
void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr)
{
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
(void)rhport;
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
xfer->stall = 1;
if (epnum == 0)
{
// EP0 has just one registers to control stall for IN and OUT
REG_SET_BIT(USB_EPC0_REG, USB_STALL);
if (dir == TUSB_DIR_OUT)
{
xfer->regs->USB_RXC0_REG = USB_USB_RXC0_REG_USB_RX_EN_Msk;
}
else
{
if (xfer->regs->USB_RXC0_REG & USB_USB_RXC0_REG_USB_RX_EN_Msk)
{
// If RX is also enabled TX will not be stalled since RX has
// higher priority. Enable NAK interrupt to handle stall.
REG_SET_BIT(USB_MAMSK_REG, USB_M_EP0_NAK);
}
else
{
xfer->regs->USB_TXC0_REG |= USB_USB_TXC0_REG_USB_TX_EN_Msk;
}
}
}
else
{
if (dir == TUSB_DIR_OUT)
{
xfer->regs->epc_out |= USB_USB_EPC1_REG_USB_STALL_Msk;
xfer->regs->rxc |= USB_USB_RXC1_REG_USB_RX_EN_Msk;
}
else
{
xfer->regs->epc_in |= USB_USB_EPC1_REG_USB_STALL_Msk;
xfer->regs->txc |= USB_USB_TXC1_REG_USB_TX_EN_Msk | USB_USB_TXC1_REG_USB_LAST_Msk;
}
}
}
void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr)
{
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
(void)rhport;
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
// Clear stall is called in response to Clear Feature ENDPOINT_HALT, reset toggle
xfer->data1 = 0;
xfer->stall = 0;
if (dir == TUSB_DIR_OUT)
{
xfer->regs->epc_out &= ~USB_USB_EPC1_REG_USB_STALL_Msk;
}
else
{
xfer->regs->epc_in &= ~USB_USB_EPC1_REG_USB_STALL_Msk;
}
if (epnum == 0)
{
REG_CLR_BIT(USB_MAMSK_REG, USB_M_EP0_NAK);
}
}
/*------------------------------------------------------------------*/
/* Interrupt Handler
*------------------------------------------------------------------*/
void dcd_int_handler(uint8_t rhport)
{
uint32_t int_status = USB->USB_MAEV_REG;
(void)rhport;
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_WARN))
{
handle_fifo_warning();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_CH_EV))
{
// TODO: for now just clear interrupt
(void)USB->USB_CHARGER_STAT_REG;
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_EP0_NAK))
{
handle_ep0_nak();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_EP0_RX))
{
handle_ep0_rx();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_EP0_TX))
{
handle_ep0_tx();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_RX_EV))
{
handle_rx_ev();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_NAK))
{
(void)USB->USB_NAKEV_REG;
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_FRAME))
{
if (_dcd.in_reset)
{
// Enable reset detection
_dcd.in_reset = false;
(void)USB->USB_ALTEV_REG;
}
#if USE_SOF
dcd_event_bus_signal(0, DCD_EVENT_SOF, true);
#else
// SOF was used to re-enable reset detection
// No need to keep it enabled
USB->USB_MAMSK_REG &= ~USB_USB_MAMSK_REG_USB_M_FRAME_Msk;
#endif
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_TX_EV))
{
handle_tx_ev();
}
if (GET_BIT(int_status, USB_USB_MAEV_REG_USB_ALT))
{
handle_alt_ev();
}
}
#endif

View File

@ -93,6 +93,9 @@
// Espressif
#define OPT_MCU_ESP32S2 900 ///< Espressif ESP32-S2
// Dialog
#define OPT_MCU_DA1469X 1000 ///< Dialog Semiconductor DA1469x
/** @} */
/** \defgroup group_supported_os Supported RTOS