From 1000b1abd3ca68adbea639b0a98aaffc8331abb0 Mon Sep 17 00:00:00 2001 From: Johann F Date: Tue, 30 Dec 2014 19:45:15 +0100 Subject: [PATCH 1/3] add initial support for MKW01Z128 SiP --- cpu/kinetis_common/ldscripts/kinetis-kl0x.ld | 257 + cpu/kw0x/Makefile | 7 + cpu/kw0x/Makefile.include | 37 + cpu/kw0x/cpu.c | 73 + cpu/kw0x/include/MKW01Z4.h | 6066 ++++++++++++++++++ cpu/kw0x/include/cpu-conf.h | 97 + cpu/kw0x/interrupt-vector.c | 129 + cpu/kw0x/kw01z128_linkerscript.ld | 13 + cpu/kw0x/lpm_arch.c | 53 + cpu/kw0x/periph/Makefile | 3 + cpu/kw0x/reboot_arch.c | 34 + cpu/kw0x/syscalls.c | 337 + doc/doxygen/riot.doxyfile | 1 + 13 files changed, 7107 insertions(+) create mode 100644 cpu/kinetis_common/ldscripts/kinetis-kl0x.ld create mode 100644 cpu/kw0x/Makefile create mode 100644 cpu/kw0x/Makefile.include create mode 100644 cpu/kw0x/cpu.c create mode 100644 cpu/kw0x/include/MKW01Z4.h create mode 100644 cpu/kw0x/include/cpu-conf.h create mode 100644 cpu/kw0x/interrupt-vector.c create mode 100644 cpu/kw0x/kw01z128_linkerscript.ld create mode 100644 cpu/kw0x/lpm_arch.c create mode 100644 cpu/kw0x/periph/Makefile create mode 100644 cpu/kw0x/reboot_arch.c create mode 100644 cpu/kw0x/syscalls.c diff --git a/cpu/kinetis_common/ldscripts/kinetis-kl0x.ld b/cpu/kinetis_common/ldscripts/kinetis-kl0x.ld new file mode 100644 index 000000000000..02404059ca5f --- /dev/null +++ b/cpu/kinetis_common/ldscripts/kinetis-kl0x.ld @@ -0,0 +1,257 @@ +/* RAM limits */ +__sram_start = ORIGIN(sram); +__sram_length = LENGTH(sram); +__sram_end = __sram_start + __sram_length; +_ramcode_start = 0x0; +_ramcode_end = 0x0; +_ramcode_load = 0x0; + +/* Define the default stack size for interrupt mode. As no context is + saved on this stack and ISRs are supposed to be short, it can be fairly + small. 512 byte should be a safe assumption here */ +STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x200; /* 512 byte */ + +RAMVECT_SIZE = DEFINED(RAMVECT_SIZE) ? RAMVECT_SIZE : 0; + +SECTIONS +{ + /* Interrupt vectors 0x00-0x3ff. */ + .vector_table : + { + _vector_rom = .; + KEEP(*(.isr_vector)) + KEEP(*(.vector_table)) + } > vectors + ASSERT (SIZEOF(.vector_table) == 0x100, "Interrupt vector table of invalid size.") + ASSERT (ADDR(.vector_table) == 0x00000000, "Interrupt vector table at invalid location (linker-script error?)") + ASSERT (LOADADDR(.vector_table) == 0x00000000, "Interrupt vector table at invalid location (linker-script error?)") + + /* Flash configuration field, very important in order to not accidentally lock the device */ + /* Flash configuration field 0x400-0x40f. */ + .fcfield : + { + . = ALIGN(4); + KEEP(*(.fcfield)) + . = ALIGN(4); + } > flashsec + ASSERT (SIZEOF(.fcfield) == 0x10, "Flash configuration field of invalid size (linker-script error?)") + ASSERT (ADDR(.fcfield) == 0x400, "Flash configuration field at invalid position (linker-script error?)") + ASSERT (LOADADDR(.fcfield) == 0x400, "Flash configuration field at invalid position (linker-script error?)") + + /* Program code 0x410-. */ + .text : + { + . = ALIGN(4); + _text_load = LOADADDR(.text); + _text_start = .; + /* preinit data */ + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP(*(SORT(.preinit_array.*))) + KEEP(*(.preinit_array)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + + /* init data */ + PROVIDE_HIDDEN (__init_array_start = .); + KEEP(*(SORT(.init_array.*))) + KEEP(*(.init_array)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + + /* fini data */ + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP(*(SORT(.fini_array.*))) + KEEP(*(.fini_array)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + + KEEP (*(SORT_NONE(.init))) + KEEP (*(SORT_NONE(.fini))) + /* Default ISR handlers */ + KEEP(*(.default_handlers)) + *(.text.unlikely .text.*_unlikely .text.unlikely.*) + *(.text.exit .text.exit.*) + *(.text.startup .text.startup.*) + *(.text.hot .text.hot.*) + *(.text .stub .text.* .gnu.linkonce.t.*) + + /* gcc uses crtbegin.o to find the start of + the constructors, so we make sure it is + first. Because this is a wildcard, it + doesn't matter if the user does not + actually link against crtbegin.o; the + linker won't look for a file to match a + wildcard. The wildcard also means that it + doesn't matter which directory crtbegin.o + is in. */ + KEEP (*crtbegin.o(.ctors)) + KEEP (*crtbegin?.o(.ctors)) + KEEP (*crtbeginTS.o(.ctors)) + /* We don't want to include the .ctor section from + the crtend.o file until after the sorted ctors. + The .ctor section from the crtend file contains the + end of ctors marker and it must be last */ + KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + + KEEP (*crtbegin.o(.dtors)) + KEEP (*crtbegin?.o(.dtors)) + KEEP (*crtbeginTS.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*(.dtors)) + . = ALIGN(4); + _rodata_start = .; + *(.rodata .rodata* .gnu.linkonce.r.*) + . = ALIGN(4); + _rodata_end = .; + _text_end = .; + } > flash + + /* The .extab, .exidx sections are used for C++ exception handling */ + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > flash + + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > flash + PROVIDE_HIDDEN (__exidx_end = .); + + .eh_frame_hdr : + { + *(.eh_frame_hdr) + } > flash + + .eh_frame : ONLY_IF_RO + { + KEEP (*(.eh_frame)) + } > flash + + .gcc_except_table : ONLY_IF_RO + { + *(.gcc_except_table .gcc_except_table.*) + } > flash + + . = ALIGN(4); + _etext = .; + + /* + * Allocate space for interrupt vector in RAM + * This can safely be removed to free up 0x100 bytes of RAM if the code does + * not make use of this CPU feature. + */ + .ramvect : + { + . = ALIGN(4); + _vector_ram_start = .; + . = _vector_ram_start + RAMVECT_SIZE; + . = ALIGN(4); + _vector_ram_end = .; + } > sram + + /* Program data, values stored in flash and loaded upon init. */ + .relocate : AT (_etext) + { + . = ALIGN(4); + _data_load = LOADADDR(.relocate); + _data_start = .; + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + _data_end = .; + } > sram + + /* .bss section, zeroed out during init. */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + __bss_start = .; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + __bss_end = .; + _ezero = .; + } > sram + + /* Make sure we set _end, in case we want dynamic memory management... */ + _end = .; + __end = .; + __end__ = .; + PROVIDE(end = .); + + . = ALIGN(8); + HEAP_SIZE = ORIGIN(sram) + LENGTH(sram) - STACK_SIZE - .; + + .heap (NOLOAD): + { + _heap_start = .; + PROVIDE(__heap_start = .); + . = . + HEAP_SIZE; + _heap_end = .; + PROVIDE(__heap_max = .); + } > sram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + _estack = .; + } > sram + + /* Any debugging sections */ + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line .debug_line.* .debug_line_end ) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } + /* DWARF 3 */ + .debug_pubtypes 0 : { *(.debug_pubtypes) } + .debug_ranges 0 : { *(.debug_ranges) } + /* DWARF Extension. */ + .debug_macro 0 : { *(.debug_macro) } + + /* XXX: what is the purpose of these sections? */ + .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) KEEP (*(.gnu.attributes)) } + .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) } + /DISCARD/ : { *(.note.GNU-stack) *(.gnu_debuglink) *(.gnu.lto_*) } +} diff --git a/cpu/kw0x/Makefile b/cpu/kw0x/Makefile new file mode 100644 index 000000000000..10c5a9688f64 --- /dev/null +++ b/cpu/kw0x/Makefile @@ -0,0 +1,7 @@ +# define the module that is build +MODULE = cpu + +# add a list of subdirectories, that should also be build +DIRS = periph $(CORTEX_M0_COMMON) $(KINETIS_COMMON) + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/kw0x/Makefile.include b/cpu/kw0x/Makefile.include new file mode 100644 index 000000000000..118b97381f04 --- /dev/null +++ b/cpu/kw0x/Makefile.include @@ -0,0 +1,37 @@ +# this CPU implementation is using the explicit core/CPU interface +export CFLAGS += -DCOREIF_NG=1 + +# export the peripheral drivers to be linked into the final binary +export USEMODULE += periph + +# tell the build system that the CPU depends on the Cortex-M common files +export USEMODULE += cortex-m0_common + +# tell the build system that the CPU depends on the Kinetis common files +export USEMODULE += kinetis_common + +# define path to cortex-m common module, which is needed for this CPU +export CORTEX_M0_COMMON = $(RIOTCPU)/cortex-m0_common/ + +# define path to kinetis module, which is needed for this CPU +export KINETIS_COMMON = $(RIOTCPU)/kinetis_common/ + +# CPU depends on the cortex-m common module, so include it +include $(CORTEX_M0_COMMON)Makefile.include + +# CPU depends on the kinetis module, so include it +include $(KINETIS_COMMON)Makefile.include + +# define the linker script to use for this CPU +export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld + +#export the CPU model +MODEL = $(shell echo $(CPU_MODEL)|tr 'a-z' 'A-Z') +export CFLAGS += -DCPU_MODEL_$(MODEL) + +# include CPU specific includes +export INCLUDES += -I$(RIOTCPU)/$(CPU)/include + +# add the CPU specific system calls implementations for the linker +export UNDEF += $(BINDIR)cpu/interrupt-vector.o +export UNDEF += $(BINDIR)cpu/syscalls.o diff --git a/cpu/kw0x/cpu.c b/cpu/kw0x/cpu.c new file mode 100644 index 000000000000..0724695801d0 --- /dev/null +++ b/cpu/kw0x/cpu.c @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_kw0x + * @{ + * + * @file + * @brief Implementation of the KW0x CPU initialization + * + * @author Hauke Petersen + * @author Johann Fischer + * @} + */ + +#include +#include "cpu-conf.h" + +#define FLASH_BASE (0x00000000) + +static void cpu_clock_init(void); + +/** + * @brief Initialize the CPU, set IRQ priorities + */ +void cpu_init(void) +{ + /* configure the vector table location to internal flash */ + SCB->VTOR = FLASH_BASE; + + /* initialize the clock system */ + cpu_clock_init(); + + /* set pendSV interrupt to lowest possible priority */ + NVIC_SetPriority(PendSV_IRQn, 0xff); +} + +/** + * @brief Configure the controllers clock system + * + */ +static void cpu_clock_init(void) +{ + /* setup system prescalers */ + SIM->CLKDIV1 = (uint32_t)SIM_CLKDIV1_OUTDIV4(1); + + kinetis_mcg_set_mode(KINETIS_MCG_FEE); + + /* Setup System Intergraion Module */ + SIM->SOPT2 = SIM_SOPT2_UART0SRC(1) | SIM_SOPT2_TPMSRC(1); + /* Selects the clock source OSC32KCLK for RTC and LPTMR (ERCLK32K) */ + SIM->SOPT1 = SIM_SOPT1_OSC32KSEL(0); + +#ifdef KW01Z128_FLL_PLL_TEST + SIM->SCGC5 |= (SIM_SCGC5_PORTE_MASK); + PORTE->PCR[0] = PORT_PCR_MUX(4); + /* OSCERCLK is output on the RTC_CLKOUT pin */ + SIM->SOPT2 |= SIM_SOPT2_RTCCLKOUTSEL_MASK; + + SIM->SCGC5 |= (SIM_SCGC5_PORTA_MASK); + PORTA->PCR[1] = PORT_PCR_MUX(1); + GPIOA->PDDR |= (1 << 1); + while(42) { + GPIOA->PTOR = (1 << 1); + } +#endif +} diff --git a/cpu/kw0x/include/MKW01Z4.h b/cpu/kw0x/include/MKW01Z4.h new file mode 100644 index 000000000000..d7fb5f97970b --- /dev/null +++ b/cpu/kw0x/include/MKW01Z4.h @@ -0,0 +1,6066 @@ +/* +** ################################################################### +** Compilers: Keil ARM C/C++ Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** GNU C Compiler - CodeSourcery Sourcery G++ +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manual: MKW01xxRM, Rev.1, December 2013 +** Version: rev. 1.0, 2013-11-22 +** Build: b141128 +** +** Abstract: +** CMSIS Peripheral Access Layer for MKW01Z4 +** +** Copyright (c) 1997 - 2013 Freescale Semiconductor, Inc. +** All rights reserved. +** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** +** o Redistributions of source code must retain the above copyright notice, this list +** of conditions and the following disclaimer. +** +** o 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. +** +** o Neither the name of Freescale Semiconductor, Inc. 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 THE COPYRIGHT HOLDER OR 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. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2013-11-22) +** Initial version. +** +** ################################################################### +*/ + +/*! + * @file MKW01Z4.h + * @version 1.0 + * @date 2013-11-22 + * @brief CMSIS Peripheral Access Layer for MKW01Z4 + * + * CMSIS Peripheral Access Layer for MKW01Z4 + */ + + +/* ---------------------------------------------------------------------------- + -- MCU activation + ---------------------------------------------------------------------------- */ + +/* Prevention from multiple including the same memory map */ +#if !defined(MKW01Z4_H_) /* Check if memory map has not been already included */ +#define MKW01Z4_H_ +#define MCU_MKW01Z4 + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* Check if another memory map has not been also included */ +#if (defined(MCU_ACTIVE)) + #error MKW01Z4 memory map: There is already included another memory map. Only one memory map can be included. +#endif /* (defined(MCU_ACTIVE)) */ +#define MCU_ACTIVE + +#include + +/** Memory map major version (memory maps with equal major version number are + * compatible) */ +#define MCU_MEM_MAP_VERSION 0x0100u +/** Memory map minor version */ +#define MCU_MEM_MAP_VERSION_MINOR 0x0000u + + +/* ---------------------------------------------------------------------------- + -- Interrupt vector numbers + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Interrupt_vector_numbers Interrupt vector numbers + * @{ + */ + +/** Interrupt Number Definitions */ +#define NUMBER_OF_INT_VECTORS 48 /**< Number of interrupts in the Vector table */ + +typedef enum IRQn { + /* Auxiliary constants */ + NotAvail_IRQn = -128, /**< Not available device specific interrupt */ + + /* Core interrupts */ + NonMaskableInt_IRQn = -14, /**< Non Maskable Interrupt */ + HardFault_IRQn = -13, /**< Cortex-M0 SV Hard Fault Interrupt */ + SVCall_IRQn = -5, /**< Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /**< Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /**< Cortex-M0 System Tick Interrupt */ + + /* Device specific interrupts */ + DMA0_IRQn = 0, /**< DMA channel 0 transfer complete and error interrupt */ + DMA1_IRQn = 1, /**< DMA channel 1 transfer complete and error interrupt */ + DMA2_IRQn = 2, /**< DMA channel 2 transfer complete and error interrupt */ + DMA3_IRQn = 3, /**< DMA channel 3 transfer complete and error interrupt */ + Reserved20_IRQn = 4, /**< Reserved interrupt */ + FTFA_IRQn = 5, /**< FTFA command complete and read collision */ + LVD_LVW_IRQn = 6, /**< Low-voltage detect, low-voltage warning */ + LLWU_IRQn = 7, /**< Low Leakage Wakeup */ + I2C0_IRQn = 8, /**< I2C0 interrupt */ + I2C1_IRQn = 9, /**< I2C1 interrupt */ + SPI0_IRQn = 10, /**< SPI0 single interrupt vector for all sources */ + SPI1_IRQn = 11, /**< SPI1 single interrupt vector for all sources */ + UART0_IRQn = 12, /**< UART0 status and error */ + UART1_IRQn = 13, /**< UART1 status and error */ + UART2_IRQn = 14, /**< UART2 status and error */ + ADC0_IRQn = 15, /**< ADC0 interrupt */ + CMP0_IRQn = 16, /**< CMP0 interrupt */ + TPM0_IRQn = 17, /**< TPM0 single interrupt vector for all sources */ + TPM1_IRQn = 18, /**< TPM1 single interrupt vector for all sources */ + TPM2_IRQn = 19, /**< TPM2 single interrupt vector for all sources */ + RTC_IRQn = 20, /**< RTC alarm interrupt */ + RTC_Seconds_IRQn = 21, /**< RTC seconds interrupt */ + PIT_IRQn = 22, /**< PIT single interrupt vector for all channels */ + Reserved39_IRQn = 23, /**< Reserved interrupt */ + Reserved40_IRQn = 24, /**< Reserved interrupt */ + DAC0_IRQn = 25, /**< DAC0 interrupt */ + TSI0_IRQn = 26, /**< TSI0 interrupt */ + MCG_IRQn = 27, /**< MCG interrupt */ + LPTMR0_IRQn = 28, /**< LPTMR0 interrupt */ + Reserved45_IRQn = 29, /**< Reserved interrupt */ + PORTA_IRQn = 30, /**< PORTA pin detect */ + PORTC_PORTD_IRQn = 31 /**< Single interrupt vector for PORTC and PORTD pin detect */ +} IRQn_Type; + +/*! + * @} + */ /* end of group Interrupt_vector_numbers */ + + +/* ---------------------------------------------------------------------------- + -- Cortex M0 Core Configuration + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Cortex_Core_Configuration Cortex M0 Core Configuration + * @{ + */ + +#define __CM0PLUS_REV 0x0000 /**< Core revision r0p0 */ +#define __MPU_PRESENT 0 /**< Defines if an MPU is present or not */ +#define __VTOR_PRESENT 1 /**< Defines if an MPU is present or not */ +#define __NVIC_PRIO_BITS 2 /**< Number of priority bits implemented in the NVIC */ +#define __Vendor_SysTickConfig 0 /**< Vendor specific implementation of SysTickConfig is defined */ + +#include "core_cm0plus.h" /* Core Peripheral Access Layer */ +//#include "system_MKW01Z4.h" /* Device specific configuration file */ + +/*! + * @} + */ /* end of group Cortex_Core_Configuration */ + + +/* ---------------------------------------------------------------------------- + -- Device Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Peripheral_access_layer Device Peripheral Access Layer + * @{ + */ + + +/* +** Start of section using anonymous unions +*/ + +#if defined(__ARMCC_VERSION) + #pragma push + #pragma anon_unions +#elif defined(__CWCC__) + #pragma push + #pragma cpp_extensions on +#elif defined(__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined(__IAR_SYSTEMS_ICC__) + #pragma language=extended +#else + #error Not supported compiler type +#endif + +/* ---------------------------------------------------------------------------- + -- ADC Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ADC_Peripheral_Access_Layer ADC Peripheral Access Layer + * @{ + */ + +/** ADC - Register Layout Typedef */ +typedef struct { + __IO uint32_t SC1[2]; /**< ADC Status and Control Registers 1, array offset: 0x0, array step: 0x4 */ + __IO uint32_t CFG1; /**< ADC Configuration Register 1, offset: 0x8 */ + __IO uint32_t CFG2; /**< ADC Configuration Register 2, offset: 0xC */ + __I uint32_t R[2]; /**< ADC Data Result Register, array offset: 0x10, array step: 0x4 */ + __IO uint32_t CV1; /**< Compare Value Registers, offset: 0x18 */ + __IO uint32_t CV2; /**< Compare Value Registers, offset: 0x1C */ + __IO uint32_t SC2; /**< Status and Control Register 2, offset: 0x20 */ + __IO uint32_t SC3; /**< Status and Control Register 3, offset: 0x24 */ + __IO uint32_t OFS; /**< ADC Offset Correction Register, offset: 0x28 */ + __IO uint32_t PG; /**< ADC Plus-Side Gain Register, offset: 0x2C */ + __IO uint32_t MG; /**< ADC Minus-Side Gain Register, offset: 0x30 */ + __IO uint32_t CLPD; /**< ADC Plus-Side General Calibration Value Register, offset: 0x34 */ + __IO uint32_t CLPS; /**< ADC Plus-Side General Calibration Value Register, offset: 0x38 */ + __IO uint32_t CLP4; /**< ADC Plus-Side General Calibration Value Register, offset: 0x3C */ + __IO uint32_t CLP3; /**< ADC Plus-Side General Calibration Value Register, offset: 0x40 */ + __IO uint32_t CLP2; /**< ADC Plus-Side General Calibration Value Register, offset: 0x44 */ + __IO uint32_t CLP1; /**< ADC Plus-Side General Calibration Value Register, offset: 0x48 */ + __IO uint32_t CLP0; /**< ADC Plus-Side General Calibration Value Register, offset: 0x4C */ + uint8_t RESERVED_0[4]; + __IO uint32_t CLMD; /**< ADC Minus-Side General Calibration Value Register, offset: 0x54 */ + __IO uint32_t CLMS; /**< ADC Minus-Side General Calibration Value Register, offset: 0x58 */ + __IO uint32_t CLM4; /**< ADC Minus-Side General Calibration Value Register, offset: 0x5C */ + __IO uint32_t CLM3; /**< ADC Minus-Side General Calibration Value Register, offset: 0x60 */ + __IO uint32_t CLM2; /**< ADC Minus-Side General Calibration Value Register, offset: 0x64 */ + __IO uint32_t CLM1; /**< ADC Minus-Side General Calibration Value Register, offset: 0x68 */ + __IO uint32_t CLM0; /**< ADC Minus-Side General Calibration Value Register, offset: 0x6C */ +} ADC_Type, *ADC_MemMapPtr; + +/* ---------------------------------------------------------------------------- + -- ADC - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ADC_Register_Accessor_Macros ADC - Register accessor macros + * @{ + */ + + +/* ADC - Register accessors */ +#define ADC_SC1_REG(base,index) ((base)->SC1[index]) +#define ADC_CFG1_REG(base) ((base)->CFG1) +#define ADC_CFG2_REG(base) ((base)->CFG2) +#define ADC_R_REG(base,index) ((base)->R[index]) +#define ADC_CV1_REG(base) ((base)->CV1) +#define ADC_CV2_REG(base) ((base)->CV2) +#define ADC_SC2_REG(base) ((base)->SC2) +#define ADC_SC3_REG(base) ((base)->SC3) +#define ADC_OFS_REG(base) ((base)->OFS) +#define ADC_PG_REG(base) ((base)->PG) +#define ADC_MG_REG(base) ((base)->MG) +#define ADC_CLPD_REG(base) ((base)->CLPD) +#define ADC_CLPS_REG(base) ((base)->CLPS) +#define ADC_CLP4_REG(base) ((base)->CLP4) +#define ADC_CLP3_REG(base) ((base)->CLP3) +#define ADC_CLP2_REG(base) ((base)->CLP2) +#define ADC_CLP1_REG(base) ((base)->CLP1) +#define ADC_CLP0_REG(base) ((base)->CLP0) +#define ADC_CLMD_REG(base) ((base)->CLMD) +#define ADC_CLMS_REG(base) ((base)->CLMS) +#define ADC_CLM4_REG(base) ((base)->CLM4) +#define ADC_CLM3_REG(base) ((base)->CLM3) +#define ADC_CLM2_REG(base) ((base)->CLM2) +#define ADC_CLM1_REG(base) ((base)->CLM1) +#define ADC_CLM0_REG(base) ((base)->CLM0) + +/*! + * @} + */ /* end of group ADC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- ADC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ADC_Register_Masks ADC Register Masks + * @{ + */ + +/* SC1 Bit Fields */ +#define ADC_SC1_ADCH_MASK 0x1Fu +#define ADC_SC1_ADCH_SHIFT 0 +#define ADC_SC1_ADCH(x) (((uint32_t)(((uint32_t)(x))<CR0) +#define CMP_CR1_REG(base) ((base)->CR1) +#define CMP_FPR_REG(base) ((base)->FPR) +#define CMP_SCR_REG(base) ((base)->SCR) +#define CMP_DACCR_REG(base) ((base)->DACCR) +#define CMP_MUXCR_REG(base) ((base)->MUXCR) + +/*! + * @} + */ /* end of group CMP_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- CMP Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup CMP_Register_Masks CMP Register Masks + * @{ + */ + +/* CR0 Bit Fields */ +#define CMP_CR0_HYSTCTR_MASK 0x3u +#define CMP_CR0_HYSTCTR_SHIFT 0 +#define CMP_CR0_HYSTCTR(x) (((uint8_t)(((uint8_t)(x))<DAT[index].DATL) +#define DAC_DATH_REG(base,index) ((base)->DAT[index].DATH) +#define DAC_SR_REG(base) ((base)->SR) +#define DAC_C0_REG(base) ((base)->C0) +#define DAC_C1_REG(base) ((base)->C1) +#define DAC_C2_REG(base) ((base)->C2) + +/*! + * @} + */ /* end of group DAC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- DAC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup DAC_Register_Masks DAC Register Masks + * @{ + */ + +/* DATL Bit Fields */ +#define DAC_DATL_DATA0_MASK 0xFFu +#define DAC_DATL_DATA0_SHIFT 0 +#define DAC_DATL_DATA0(x) (((uint8_t)(((uint8_t)(x))<DMA[index].SAR) +#define DMA_DAR_REG(base,index) ((base)->DMA[index].DAR) +#define DMA_DSR_BCR_REG(base,index) ((base)->DMA[index].DSR_BCR) +#define DMA_DSR_REG(base,index) ((base)->DMA[index].DMA_DSR_ACCESS8BIT.DSR) +#define DMA_DCR_REG(base,index) ((base)->DMA[index].DCR) + +/*! + * @} + */ /* end of group DMA_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- DMA Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup DMA_Register_Masks DMA Register Masks + * @{ + */ + +/* SAR Bit Fields */ +#define DMA_SAR_SAR_MASK 0xFFFFFFFFu +#define DMA_SAR_SAR_SHIFT 0 +#define DMA_SAR_SAR(x) (((uint32_t)(((uint32_t)(x))<CHCFG[index]) + +/*! + * @} + */ /* end of group DMAMUX_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- DMAMUX Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup DMAMUX_Register_Masks DMAMUX Register Masks + * @{ + */ + +/* CHCFG Bit Fields */ +#define DMAMUX_CHCFG_SOURCE_MASK 0x3Fu +#define DMAMUX_CHCFG_SOURCE_SHIFT 0 +#define DMAMUX_CHCFG_SOURCE(x) (((uint8_t)(((uint8_t)(x))<PDOR) +#define FGPIO_PSOR_REG(base) ((base)->PSOR) +#define FGPIO_PCOR_REG(base) ((base)->PCOR) +#define FGPIO_PTOR_REG(base) ((base)->PTOR) +#define FGPIO_PDIR_REG(base) ((base)->PDIR) +#define FGPIO_PDDR_REG(base) ((base)->PDDR) + +/*! + * @} + */ /* end of group FGPIO_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FGPIO Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FGPIO_Register_Masks FGPIO Register Masks + * @{ + */ + +/* PDOR Bit Fields */ +#define FGPIO_PDOR_PDO_MASK 0xFFFFFFFFu +#define FGPIO_PDOR_PDO_SHIFT 0 +#define FGPIO_PDOR_PDO(x) (((uint32_t)(((uint32_t)(x))<FSTAT) +#define FTFA_FCNFG_REG(base) ((base)->FCNFG) +#define FTFA_FSEC_REG(base) ((base)->FSEC) +#define FTFA_FOPT_REG(base) ((base)->FOPT) +#define FTFA_FCCOB3_REG(base) ((base)->FCCOB3) +#define FTFA_FCCOB2_REG(base) ((base)->FCCOB2) +#define FTFA_FCCOB1_REG(base) ((base)->FCCOB1) +#define FTFA_FCCOB0_REG(base) ((base)->FCCOB0) +#define FTFA_FCCOB7_REG(base) ((base)->FCCOB7) +#define FTFA_FCCOB6_REG(base) ((base)->FCCOB6) +#define FTFA_FCCOB5_REG(base) ((base)->FCCOB5) +#define FTFA_FCCOB4_REG(base) ((base)->FCCOB4) +#define FTFA_FCCOBB_REG(base) ((base)->FCCOBB) +#define FTFA_FCCOBA_REG(base) ((base)->FCCOBA) +#define FTFA_FCCOB9_REG(base) ((base)->FCCOB9) +#define FTFA_FCCOB8_REG(base) ((base)->FCCOB8) +#define FTFA_FPROT3_REG(base) ((base)->FPROT3) +#define FTFA_FPROT2_REG(base) ((base)->FPROT2) +#define FTFA_FPROT1_REG(base) ((base)->FPROT1) +#define FTFA_FPROT0_REG(base) ((base)->FPROT0) + +/*! + * @} + */ /* end of group FTFA_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FTFA Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FTFA_Register_Masks FTFA Register Masks + * @{ + */ + +/* FSTAT Bit Fields */ +#define FTFA_FSTAT_MGSTAT0_MASK 0x1u +#define FTFA_FSTAT_MGSTAT0_SHIFT 0 +#define FTFA_FSTAT_FPVIOL_MASK 0x10u +#define FTFA_FSTAT_FPVIOL_SHIFT 4 +#define FTFA_FSTAT_ACCERR_MASK 0x20u +#define FTFA_FSTAT_ACCERR_SHIFT 5 +#define FTFA_FSTAT_RDCOLERR_MASK 0x40u +#define FTFA_FSTAT_RDCOLERR_SHIFT 6 +#define FTFA_FSTAT_CCIF_MASK 0x80u +#define FTFA_FSTAT_CCIF_SHIFT 7 +/* FCNFG Bit Fields */ +#define FTFA_FCNFG_ERSSUSP_MASK 0x10u +#define FTFA_FCNFG_ERSSUSP_SHIFT 4 +#define FTFA_FCNFG_ERSAREQ_MASK 0x20u +#define FTFA_FCNFG_ERSAREQ_SHIFT 5 +#define FTFA_FCNFG_RDCOLLIE_MASK 0x40u +#define FTFA_FCNFG_RDCOLLIE_SHIFT 6 +#define FTFA_FCNFG_CCIE_MASK 0x80u +#define FTFA_FCNFG_CCIE_SHIFT 7 +/* FSEC Bit Fields */ +#define FTFA_FSEC_SEC_MASK 0x3u +#define FTFA_FSEC_SEC_SHIFT 0 +#define FTFA_FSEC_SEC(x) (((uint8_t)(((uint8_t)(x))<PDOR) +#define GPIO_PSOR_REG(base) ((base)->PSOR) +#define GPIO_PCOR_REG(base) ((base)->PCOR) +#define GPIO_PTOR_REG(base) ((base)->PTOR) +#define GPIO_PDIR_REG(base) ((base)->PDIR) +#define GPIO_PDDR_REG(base) ((base)->PDDR) + +/*! + * @} + */ /* end of group GPIO_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- GPIO Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup GPIO_Register_Masks GPIO Register Masks + * @{ + */ + +/* PDOR Bit Fields */ +#define GPIO_PDOR_PDO_MASK 0xFFFFFFFFu +#define GPIO_PDOR_PDO_SHIFT 0 +#define GPIO_PDOR_PDO(x) (((uint32_t)(((uint32_t)(x))<A1) +#define I2C_F_REG(base) ((base)->F) +#define I2C_C1_REG(base) ((base)->C1) +#define I2C_S_REG(base) ((base)->S) +#define I2C_D_REG(base) ((base)->D) +#define I2C_C2_REG(base) ((base)->C2) +#define I2C_FLT_REG(base) ((base)->FLT) +#define I2C_RA_REG(base) ((base)->RA) +#define I2C_SMB_REG(base) ((base)->SMB) +#define I2C_A2_REG(base) ((base)->A2) +#define I2C_SLTH_REG(base) ((base)->SLTH) +#define I2C_SLTL_REG(base) ((base)->SLTL) + +/*! + * @} + */ /* end of group I2C_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- I2C Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup I2C_Register_Masks I2C Register Masks + * @{ + */ + +/* A1 Bit Fields */ +#define I2C_A1_AD_MASK 0xFEu +#define I2C_A1_AD_SHIFT 1 +#define I2C_A1_AD(x) (((uint8_t)(((uint8_t)(x))<PE1) +#define LLWU_PE2_REG(base) ((base)->PE2) +#define LLWU_PE3_REG(base) ((base)->PE3) +#define LLWU_PE4_REG(base) ((base)->PE4) +#define LLWU_ME_REG(base) ((base)->ME) +#define LLWU_F1_REG(base) ((base)->F1) +#define LLWU_F2_REG(base) ((base)->F2) +#define LLWU_F3_REG(base) ((base)->F3) +#define LLWU_FILT1_REG(base) ((base)->FILT1) +#define LLWU_FILT2_REG(base) ((base)->FILT2) + +/*! + * @} + */ /* end of group LLWU_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- LLWU Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup LLWU_Register_Masks LLWU Register Masks + * @{ + */ + +/* PE1 Bit Fields */ +#define LLWU_PE1_WUPE0_MASK 0x3u +#define LLWU_PE1_WUPE0_SHIFT 0 +#define LLWU_PE1_WUPE0(x) (((uint8_t)(((uint8_t)(x))<CSR) +#define LPTMR_PSR_REG(base) ((base)->PSR) +#define LPTMR_CMR_REG(base) ((base)->CMR) +#define LPTMR_CNR_REG(base) ((base)->CNR) + +/*! + * @} + */ /* end of group LPTMR_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- LPTMR Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup LPTMR_Register_Masks LPTMR Register Masks + * @{ + */ + +/* CSR Bit Fields */ +#define LPTMR_CSR_TEN_MASK 0x1u +#define LPTMR_CSR_TEN_SHIFT 0 +#define LPTMR_CSR_TMS_MASK 0x2u +#define LPTMR_CSR_TMS_SHIFT 1 +#define LPTMR_CSR_TFC_MASK 0x4u +#define LPTMR_CSR_TFC_SHIFT 2 +#define LPTMR_CSR_TPP_MASK 0x8u +#define LPTMR_CSR_TPP_SHIFT 3 +#define LPTMR_CSR_TPS_MASK 0x30u +#define LPTMR_CSR_TPS_SHIFT 4 +#define LPTMR_CSR_TPS(x) (((uint32_t)(((uint32_t)(x))<C1) +#define MCG_C2_REG(base) ((base)->C2) +#define MCG_C3_REG(base) ((base)->C3) +#define MCG_C4_REG(base) ((base)->C4) +#define MCG_C5_REG(base) ((base)->C5) +#define MCG_C6_REG(base) ((base)->C6) +#define MCG_S_REG(base) ((base)->S) +#define MCG_SC_REG(base) ((base)->SC) +#define MCG_ATCVH_REG(base) ((base)->ATCVH) +#define MCG_ATCVL_REG(base) ((base)->ATCVL) +#define MCG_C8_REG(base) ((base)->C8) +#define MCG_C9_REG(base) ((base)->C9) +#define MCG_C10_REG(base) ((base)->C10) + +/*! + * @} + */ /* end of group MCG_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- MCG Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup MCG_Register_Masks MCG Register Masks + * @{ + */ + +/* C1 Bit Fields */ +#define MCG_C1_IREFSTEN_MASK 0x1u +#define MCG_C1_IREFSTEN_SHIFT 0 +#define MCG_C1_IRCLKEN_MASK 0x2u +#define MCG_C1_IRCLKEN_SHIFT 1 +#define MCG_C1_IREFS_MASK 0x4u +#define MCG_C1_IREFS_SHIFT 2 +#define MCG_C1_FRDIV_MASK 0x38u +#define MCG_C1_FRDIV_SHIFT 3 +#define MCG_C1_FRDIV(x) (((uint8_t)(((uint8_t)(x))<PLASC) +#define MCM_PLAMC_REG(base) ((base)->PLAMC) +#define MCM_PLACR_REG(base) ((base)->PLACR) +#define MCM_CPO_REG(base) ((base)->CPO) + +/*! + * @} + */ /* end of group MCM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- MCM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup MCM_Register_Masks MCM Register Masks + * @{ + */ + +/* PLASC Bit Fields */ +#define MCM_PLASC_ASC_MASK 0xFFu +#define MCM_PLASC_ASC_SHIFT 0 +#define MCM_PLASC_ASC(x) (((uint16_t)(((uint16_t)(x))<POSITION) +#define MTB_MASTER_REG(base) ((base)->MASTER) +#define MTB_FLOW_REG(base) ((base)->FLOW) +#define MTB_BASE_REG(base) ((base)->BASE) +#define MTB_MODECTRL_REG(base) ((base)->MODECTRL) +#define MTB_TAGSET_REG(base) ((base)->TAGSET) +#define MTB_TAGCLEAR_REG(base) ((base)->TAGCLEAR) +#define MTB_LOCKACCESS_REG(base) ((base)->LOCKACCESS) +#define MTB_LOCKSTAT_REG(base) ((base)->LOCKSTAT) +#define MTB_AUTHSTAT_REG(base) ((base)->AUTHSTAT) +#define MTB_DEVICEARCH_REG(base) ((base)->DEVICEARCH) +#define MTB_DEVICECFG_REG(base) ((base)->DEVICECFG) +#define MTB_DEVICETYPID_REG(base) ((base)->DEVICETYPID) +#define MTB_PERIPHID_REG(base,index) ((base)->PERIPHID[index]) +#define MTB_COMPID_REG(base,index) ((base)->COMPID[index]) + +/*! + * @} + */ /* end of group MTB_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- MTB Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup MTB_Register_Masks MTB Register Masks + * @{ + */ + +/* POSITION Bit Fields */ +#define MTB_POSITION_WRAP_MASK 0x4u +#define MTB_POSITION_WRAP_SHIFT 2 +#define MTB_POSITION_POINTER_MASK 0xFFFFFFF8u +#define MTB_POSITION_POINTER_SHIFT 3 +#define MTB_POSITION_POINTER(x) (((uint32_t)(((uint32_t)(x))<CTRL) +#define MTBDWT_COMP_REG(base,index) ((base)->COMPARATOR[index].COMP) +#define MTBDWT_MASK_REG(base,index) ((base)->COMPARATOR[index].MASK) +#define MTBDWT_FCT_REG(base,index) ((base)->COMPARATOR[index].FCT) +#define MTBDWT_TBCTRL_REG(base) ((base)->TBCTRL) +#define MTBDWT_DEVICECFG_REG(base) ((base)->DEVICECFG) +#define MTBDWT_DEVICETYPID_REG(base) ((base)->DEVICETYPID) +#define MTBDWT_PERIPHID_REG(base,index) ((base)->PERIPHID[index]) +#define MTBDWT_COMPID_REG(base,index) ((base)->COMPID[index]) + +/*! + * @} + */ /* end of group MTBDWT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- MTBDWT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup MTBDWT_Register_Masks MTBDWT Register Masks + * @{ + */ + +/* CTRL Bit Fields */ +#define MTBDWT_CTRL_DWTCFGCTRL_MASK 0xFFFFFFFu +#define MTBDWT_CTRL_DWTCFGCTRL_SHIFT 0 +#define MTBDWT_CTRL_DWTCFGCTRL(x) (((uint32_t)(((uint32_t)(x))<BACKKEY3) +#define NV_BACKKEY2_REG(base) ((base)->BACKKEY2) +#define NV_BACKKEY1_REG(base) ((base)->BACKKEY1) +#define NV_BACKKEY0_REG(base) ((base)->BACKKEY0) +#define NV_BACKKEY7_REG(base) ((base)->BACKKEY7) +#define NV_BACKKEY6_REG(base) ((base)->BACKKEY6) +#define NV_BACKKEY5_REG(base) ((base)->BACKKEY5) +#define NV_BACKKEY4_REG(base) ((base)->BACKKEY4) +#define NV_FPROT3_REG(base) ((base)->FPROT3) +#define NV_FPROT2_REG(base) ((base)->FPROT2) +#define NV_FPROT1_REG(base) ((base)->FPROT1) +#define NV_FPROT0_REG(base) ((base)->FPROT0) +#define NV_FSEC_REG(base) ((base)->FSEC) +#define NV_FOPT_REG(base) ((base)->FOPT) + +/*! + * @} + */ /* end of group NV_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- NV Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup NV_Register_Masks NV Register Masks + * @{ + */ + +/* BACKKEY3 Bit Fields */ +#define NV_BACKKEY3_KEY_MASK 0xFFu +#define NV_BACKKEY3_KEY_SHIFT 0 +#define NV_BACKKEY3_KEY(x) (((uint8_t)(((uint8_t)(x))<CR) + +/*! + * @} + */ /* end of group OSC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- OSC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup OSC_Register_Masks OSC Register Masks + * @{ + */ + +/* CR Bit Fields */ +#define OSC_CR_SC16P_MASK 0x1u +#define OSC_CR_SC16P_SHIFT 0 +#define OSC_CR_SC8P_MASK 0x2u +#define OSC_CR_SC8P_SHIFT 1 +#define OSC_CR_SC4P_MASK 0x4u +#define OSC_CR_SC4P_SHIFT 2 +#define OSC_CR_SC2P_MASK 0x8u +#define OSC_CR_SC2P_SHIFT 3 +#define OSC_CR_EREFSTEN_MASK 0x20u +#define OSC_CR_EREFSTEN_SHIFT 5 +#define OSC_CR_ERCLKEN_MASK 0x80u +#define OSC_CR_ERCLKEN_SHIFT 7 + +/*! + * @} + */ /* end of group OSC_Register_Masks */ + + +/* OSC - Peripheral instance base addresses */ +/** Peripheral OSC0 base address */ +#define OSC0_BASE (0x40065000u) +/** Peripheral OSC0 base pointer */ +#define OSC0 ((OSC_Type *)OSC0_BASE) +#define OSC0_BASE_PTR (OSC0) +/** Array initializer of OSC peripheral base addresses */ +#define OSC_BASE_ADDRS { OSC0_BASE } +/** Array initializer of OSC peripheral base pointers */ +#define OSC_BASE_PTRS { OSC0 } + +/* ---------------------------------------------------------------------------- + -- OSC - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup OSC_Register_Accessor_Macros OSC - Register accessor macros + * @{ + */ + + +/* OSC - Register instance definitions */ +/* OSC0 */ +#define OSC0_CR OSC_CR_REG(OSC0) + +/*! + * @} + */ /* end of group OSC_Register_Accessor_Macros */ + + +/*! + * @} + */ /* end of group OSC_Peripheral_Access_Layer */ + + +/* ---------------------------------------------------------------------------- + -- PIT Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PIT_Peripheral_Access_Layer PIT Peripheral Access Layer + * @{ + */ + +/** PIT - Register Layout Typedef */ +typedef struct { + __IO uint32_t MCR; /**< PIT Module Control Register, offset: 0x0 */ + uint8_t RESERVED_0[220]; + __I uint32_t LTMR64H; /**< PIT Upper Lifetime Timer Register, offset: 0xE0 */ + __I uint32_t LTMR64L; /**< PIT Lower Lifetime Timer Register, offset: 0xE4 */ + uint8_t RESERVED_1[24]; + struct { /* offset: 0x100, array step: 0x10 */ + __IO uint32_t LDVAL; /**< Timer Load Value Register, array offset: 0x100, array step: 0x10 */ + __I uint32_t CVAL; /**< Current Timer Value Register, array offset: 0x104, array step: 0x10 */ + __IO uint32_t TCTRL; /**< Timer Control Register, array offset: 0x108, array step: 0x10 */ + __IO uint32_t TFLG; /**< Timer Flag Register, array offset: 0x10C, array step: 0x10 */ + } CHANNEL[2]; +} PIT_Type, *PIT_MemMapPtr; + +/* ---------------------------------------------------------------------------- + -- PIT - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PIT_Register_Accessor_Macros PIT - Register accessor macros + * @{ + */ + + +/* PIT - Register accessors */ +#define PIT_MCR_REG(base) ((base)->MCR) +#define PIT_LTMR64H_REG(base) ((base)->LTMR64H) +#define PIT_LTMR64L_REG(base) ((base)->LTMR64L) +#define PIT_LDVAL_REG(base,index) ((base)->CHANNEL[index].LDVAL) +#define PIT_CVAL_REG(base,index) ((base)->CHANNEL[index].CVAL) +#define PIT_TCTRL_REG(base,index) ((base)->CHANNEL[index].TCTRL) +#define PIT_TFLG_REG(base,index) ((base)->CHANNEL[index].TFLG) + +/*! + * @} + */ /* end of group PIT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PIT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PIT_Register_Masks PIT Register Masks + * @{ + */ + +/* MCR Bit Fields */ +#define PIT_MCR_FRZ_MASK 0x1u +#define PIT_MCR_FRZ_SHIFT 0 +#define PIT_MCR_MDIS_MASK 0x2u +#define PIT_MCR_MDIS_SHIFT 1 +/* LTMR64H Bit Fields */ +#define PIT_LTMR64H_LTH_MASK 0xFFFFFFFFu +#define PIT_LTMR64H_LTH_SHIFT 0 +#define PIT_LTMR64H_LTH(x) (((uint32_t)(((uint32_t)(x))<LVDSC1) +#define PMC_LVDSC2_REG(base) ((base)->LVDSC2) +#define PMC_REGSC_REG(base) ((base)->REGSC) + +/*! + * @} + */ /* end of group PMC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PMC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PMC_Register_Masks PMC Register Masks + * @{ + */ + +/* LVDSC1 Bit Fields */ +#define PMC_LVDSC1_LVDV_MASK 0x3u +#define PMC_LVDSC1_LVDV_SHIFT 0 +#define PMC_LVDSC1_LVDV(x) (((uint8_t)(((uint8_t)(x))<PCR[index]) +#define PORT_GPCLR_REG(base) ((base)->GPCLR) +#define PORT_GPCHR_REG(base) ((base)->GPCHR) +#define PORT_ISFR_REG(base) ((base)->ISFR) + +/*! + * @} + */ /* end of group PORT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PORT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PORT_Register_Masks PORT Register Masks + * @{ + */ + +/* PCR Bit Fields */ +#define PORT_PCR_PS_MASK 0x1u +#define PORT_PCR_PS_SHIFT 0 +#define PORT_PCR_PE_MASK 0x2u +#define PORT_PCR_PE_SHIFT 1 +#define PORT_PCR_SRE_MASK 0x4u +#define PORT_PCR_SRE_SHIFT 2 +#define PORT_PCR_PFE_MASK 0x10u +#define PORT_PCR_PFE_SHIFT 4 +#define PORT_PCR_DSE_MASK 0x40u +#define PORT_PCR_DSE_SHIFT 6 +#define PORT_PCR_MUX_MASK 0x700u +#define PORT_PCR_MUX_SHIFT 8 +#define PORT_PCR_MUX(x) (((uint32_t)(((uint32_t)(x))<SRS0) +#define RCM_SRS1_REG(base) ((base)->SRS1) +#define RCM_RPFC_REG(base) ((base)->RPFC) +#define RCM_RPFW_REG(base) ((base)->RPFW) + +/*! + * @} + */ /* end of group RCM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- RCM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup RCM_Register_Masks RCM Register Masks + * @{ + */ + +/* SRS0 Bit Fields */ +#define RCM_SRS0_WAKEUP_MASK 0x1u +#define RCM_SRS0_WAKEUP_SHIFT 0 +#define RCM_SRS0_LVD_MASK 0x2u +#define RCM_SRS0_LVD_SHIFT 1 +#define RCM_SRS0_LOC_MASK 0x4u +#define RCM_SRS0_LOC_SHIFT 2 +#define RCM_SRS0_LOL_MASK 0x8u +#define RCM_SRS0_LOL_SHIFT 3 +#define RCM_SRS0_WDOG_MASK 0x20u +#define RCM_SRS0_WDOG_SHIFT 5 +#define RCM_SRS0_PIN_MASK 0x40u +#define RCM_SRS0_PIN_SHIFT 6 +#define RCM_SRS0_POR_MASK 0x80u +#define RCM_SRS0_POR_SHIFT 7 +/* SRS1 Bit Fields */ +#define RCM_SRS1_LOCKUP_MASK 0x2u +#define RCM_SRS1_LOCKUP_SHIFT 1 +#define RCM_SRS1_SW_MASK 0x4u +#define RCM_SRS1_SW_SHIFT 2 +#define RCM_SRS1_MDM_AP_MASK 0x8u +#define RCM_SRS1_MDM_AP_SHIFT 3 +#define RCM_SRS1_SACKERR_MASK 0x20u +#define RCM_SRS1_SACKERR_SHIFT 5 +/* RPFC Bit Fields */ +#define RCM_RPFC_RSTFLTSRW_MASK 0x3u +#define RCM_RPFC_RSTFLTSRW_SHIFT 0 +#define RCM_RPFC_RSTFLTSRW(x) (((uint8_t)(((uint8_t)(x))<ENTRY[index]) +#define ROM_TABLEMARK_REG(base) ((base)->TABLEMARK) +#define ROM_SYSACCESS_REG(base) ((base)->SYSACCESS) +#define ROM_PERIPHID4_REG(base) ((base)->PERIPHID4) +#define ROM_PERIPHID5_REG(base) ((base)->PERIPHID5) +#define ROM_PERIPHID6_REG(base) ((base)->PERIPHID6) +#define ROM_PERIPHID7_REG(base) ((base)->PERIPHID7) +#define ROM_PERIPHID0_REG(base) ((base)->PERIPHID0) +#define ROM_PERIPHID1_REG(base) ((base)->PERIPHID1) +#define ROM_PERIPHID2_REG(base) ((base)->PERIPHID2) +#define ROM_PERIPHID3_REG(base) ((base)->PERIPHID3) +#define ROM_COMPID_REG(base,index) ((base)->COMPID[index]) + +/*! + * @} + */ /* end of group ROM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- ROM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ROM_Register_Masks ROM Register Masks + * @{ + */ + +/* ENTRY Bit Fields */ +#define ROM_ENTRY_ENTRY_MASK 0xFFFFFFFFu +#define ROM_ENTRY_ENTRY_SHIFT 0 +#define ROM_ENTRY_ENTRY(x) (((uint32_t)(((uint32_t)(x))<TSR) +#define RTC_TPR_REG(base) ((base)->TPR) +#define RTC_TAR_REG(base) ((base)->TAR) +#define RTC_TCR_REG(base) ((base)->TCR) +#define RTC_CR_REG(base) ((base)->CR) +#define RTC_SR_REG(base) ((base)->SR) +#define RTC_LR_REG(base) ((base)->LR) +#define RTC_IER_REG(base) ((base)->IER) + +/*! + * @} + */ /* end of group RTC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- RTC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup RTC_Register_Masks RTC Register Masks + * @{ + */ + +/* TSR Bit Fields */ +#define RTC_TSR_TSR_MASK 0xFFFFFFFFu +#define RTC_TSR_TSR_SHIFT 0 +#define RTC_TSR_TSR(x) (((uint32_t)(((uint32_t)(x))<SOPT1) +#define SIM_SOPT2_REG(base) ((base)->SOPT2) +#define SIM_SOPT4_REG(base) ((base)->SOPT4) +#define SIM_SOPT5_REG(base) ((base)->SOPT5) +#define SIM_SOPT7_REG(base) ((base)->SOPT7) +#define SIM_SDID_REG(base) ((base)->SDID) +#define SIM_SCGC4_REG(base) ((base)->SCGC4) +#define SIM_SCGC5_REG(base) ((base)->SCGC5) +#define SIM_SCGC6_REG(base) ((base)->SCGC6) +#define SIM_SCGC7_REG(base) ((base)->SCGC7) +#define SIM_CLKDIV1_REG(base) ((base)->CLKDIV1) +#define SIM_FCFG1_REG(base) ((base)->FCFG1) +#define SIM_FCFG2_REG(base) ((base)->FCFG2) +#define SIM_UIDMH_REG(base) ((base)->UIDMH) +#define SIM_UIDML_REG(base) ((base)->UIDML) +#define SIM_UIDL_REG(base) ((base)->UIDL) +#define SIM_COPC_REG(base) ((base)->COPC) +#define SIM_SRVCOP_REG(base) ((base)->SRVCOP) + +/*! + * @} + */ /* end of group SIM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SIM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SIM_Register_Masks SIM Register Masks + * @{ + */ + +/* SOPT1 Bit Fields */ +#define SIM_SOPT1_OSC32KSEL_MASK 0xC0000u +#define SIM_SOPT1_OSC32KSEL_SHIFT 18 +#define SIM_SOPT1_OSC32KSEL(x) (((uint32_t)(((uint32_t)(x))<PMPROT) +#define SMC_PMCTRL_REG(base) ((base)->PMCTRL) +#define SMC_STOPCTRL_REG(base) ((base)->STOPCTRL) +#define SMC_PMSTAT_REG(base) ((base)->PMSTAT) + +/*! + * @} + */ /* end of group SMC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SMC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SMC_Register_Masks SMC Register Masks + * @{ + */ + +/* PMPROT Bit Fields */ +#define SMC_PMPROT_AVLLS_MASK 0x2u +#define SMC_PMPROT_AVLLS_SHIFT 1 +#define SMC_PMPROT_ALLS_MASK 0x8u +#define SMC_PMPROT_ALLS_SHIFT 3 +#define SMC_PMPROT_AVLP_MASK 0x20u +#define SMC_PMPROT_AVLP_SHIFT 5 +/* PMCTRL Bit Fields */ +#define SMC_PMCTRL_STOPM_MASK 0x7u +#define SMC_PMCTRL_STOPM_SHIFT 0 +#define SMC_PMCTRL_STOPM(x) (((uint8_t)(((uint8_t)(x))<S) +#define SPI_BR_REG(base) ((base)->BR) +#define SPI_C2_REG(base) ((base)->C2) +#define SPI_C1_REG(base) ((base)->C1) +#define SPI_ML_REG(base) ((base)->ML) +#define SPI_MH_REG(base) ((base)->MH) +#define SPI_DL_REG(base) ((base)->DL) +#define SPI_DH_REG(base) ((base)->DH) +#define SPI_CI_REG(base) ((base)->CI) +#define SPI_C3_REG(base) ((base)->C3) + +/*! + * @} + */ /* end of group SPI_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SPI Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SPI_Register_Masks SPI Register Masks + * @{ + */ + +/* S Bit Fields */ +#define SPI_S_RFIFOEF_MASK 0x1u +#define SPI_S_RFIFOEF_SHIFT 0 +#define SPI_S_TXFULLF_MASK 0x2u +#define SPI_S_TXFULLF_SHIFT 1 +#define SPI_S_TNEAREF_MASK 0x4u +#define SPI_S_TNEAREF_SHIFT 2 +#define SPI_S_RNFULLF_MASK 0x8u +#define SPI_S_RNFULLF_SHIFT 3 +#define SPI_S_MODF_MASK 0x10u +#define SPI_S_MODF_SHIFT 4 +#define SPI_S_SPTEF_MASK 0x20u +#define SPI_S_SPTEF_SHIFT 5 +#define SPI_S_SPMF_MASK 0x40u +#define SPI_S_SPMF_SHIFT 6 +#define SPI_S_SPRF_MASK 0x80u +#define SPI_S_SPRF_SHIFT 7 +/* BR Bit Fields */ +#define SPI_BR_SPR_MASK 0xFu +#define SPI_BR_SPR_SHIFT 0 +#define SPI_BR_SPR(x) (((uint8_t)(((uint8_t)(x))<SC) +#define TPM_CNT_REG(base) ((base)->CNT) +#define TPM_MOD_REG(base) ((base)->MOD) +#define TPM_CnSC_REG(base,index) ((base)->CONTROLS[index].CnSC) +#define TPM_CnV_REG(base,index) ((base)->CONTROLS[index].CnV) +#define TPM_STATUS_REG(base) ((base)->STATUS) +#define TPM_CONF_REG(base) ((base)->CONF) + +/*! + * @} + */ /* end of group TPM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- TPM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup TPM_Register_Masks TPM Register Masks + * @{ + */ + +/* SC Bit Fields */ +#define TPM_SC_PS_MASK 0x7u +#define TPM_SC_PS_SHIFT 0 +#define TPM_SC_PS(x) (((uint32_t)(((uint32_t)(x))<GENCS) +#define TSI_DATA_REG(base) ((base)->DATA) +#define TSI_TSHD_REG(base) ((base)->TSHD) + +/*! + * @} + */ /* end of group TSI_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- TSI Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup TSI_Register_Masks TSI Register Masks + * @{ + */ + +/* GENCS Bit Fields */ +#define TSI_GENCS_CURSW_MASK 0x2u +#define TSI_GENCS_CURSW_SHIFT 1 +#define TSI_GENCS_EOSF_MASK 0x4u +#define TSI_GENCS_EOSF_SHIFT 2 +#define TSI_GENCS_SCNIP_MASK 0x8u +#define TSI_GENCS_SCNIP_SHIFT 3 +#define TSI_GENCS_STM_MASK 0x10u +#define TSI_GENCS_STM_SHIFT 4 +#define TSI_GENCS_STPE_MASK 0x20u +#define TSI_GENCS_STPE_SHIFT 5 +#define TSI_GENCS_TSIIEN_MASK 0x40u +#define TSI_GENCS_TSIIEN_SHIFT 6 +#define TSI_GENCS_TSIEN_MASK 0x80u +#define TSI_GENCS_TSIEN_SHIFT 7 +#define TSI_GENCS_NSCN_MASK 0x1F00u +#define TSI_GENCS_NSCN_SHIFT 8 +#define TSI_GENCS_NSCN(x) (((uint32_t)(((uint32_t)(x))<BDH) +#define UART_BDL_REG(base) ((base)->BDL) +#define UART_C1_REG(base) ((base)->C1) +#define UART_C2_REG(base) ((base)->C2) +#define UART_S1_REG(base) ((base)->S1) +#define UART_S2_REG(base) ((base)->S2) +#define UART_C3_REG(base) ((base)->C3) +#define UART_D_REG(base) ((base)->D) +#define UART_C4_REG(base) ((base)->C4) + +/*! + * @} + */ /* end of group UART_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- UART Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup UART_Register_Masks UART Register Masks + * @{ + */ + +/* BDH Bit Fields */ +#define UART_BDH_SBR_MASK 0x1Fu +#define UART_BDH_SBR_SHIFT 0 +#define UART_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))<BDH) +#define UART0_BDL_REG(base) ((base)->BDL) +#define UART0_C1_REG(base) ((base)->C1) +#define UART0_C2_REG(base) ((base)->C2) +#define UART0_S1_REG(base) ((base)->S1) +#define UART0_S2_REG(base) ((base)->S2) +#define UART0_C3_REG(base) ((base)->C3) +#define UART0_D_REG(base) ((base)->D) +#define UART0_MA1_REG(base) ((base)->MA1) +#define UART0_MA2_REG(base) ((base)->MA2) +#define UART0_C4_REG(base) ((base)->C4) +#define UART0_C5_REG(base) ((base)->C5) + +/*! + * @} + */ /* end of group UART0_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- UART0 Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup UART0_Register_Masks UART0 Register Masks + * @{ + */ + +/* BDH Bit Fields */ +#define UART0_BDH_SBR_MASK 0x1Fu +#define UART0_BDH_SBR_SHIFT 0 +#define UART0_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))< + * @author Johann Fischer + */ + +#ifndef __CPU_CONF_H +#define __CPU_CONF_H + +#ifdef CPU_MODEL_KW01Z128 +#include "MKW01Z4.h" +#include "mcg.h" +#endif + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * @name Kernel configuration + * + * @{ + */ +#define KERNEL_CONF_STACKSIZE_PRINTF (1024) + +#ifndef KERNEL_CONF_STACKSIZE_DEFAULT +#define KERNEL_CONF_STACKSIZE_DEFAULT (1024) +#endif + +#define KERNEL_CONF_STACKSIZE_IDLE (256) +/** @} */ + +/** + * @brief Length for reading CPU_ID in octets + */ +#define CPUID_ID_LEN (12) + +/** + * @brief Pointer to CPU_ID + */ +#define CPUID_ID_PTR ((void *)(&(SIM->UIDMH))) + +/** + * @name UART0 buffer size definition for compatibility reasons. + * + * TODO: remove once the remodeling of the uart0 driver is done. + * @{ + */ +#ifndef UART0_BUFSIZE +#define UART0_BUFSIZE (128) +#endif +/** @} */ + +#define TRANSCEIVER_BUFFER_SIZE (3) /**< Buffer Size for Transceiver Module */ + +/** + * @brief MCU specific Low Power Timer settings. + */ +#define LPTIMER_CLKSRC LPTIMER_CLKSRC_LPO +#define LPTIMER_DEV (LPTMR0) /**< LPTIMER hardware module */ +#define LPTIMER_CLKEN() (SIM->SCGC5 |= SIM_SCGC5_LPTMR_MASK) /**< Enable LPTMR0 clock gate */ +#define LPTIMER_CLKDIS() (SIM->SCGC5 &= ~SIM_SCGC5_PTMR_MASK) /**< Disable LPTMR0 clock gate */ +#define LPTIMER_CNR_NEEDS_LATCHING 1 /**< LPTMR.CNR register do not need latching */ + +/** + * @name MKW0XD SiP internal interconnects between MCU and Modem. + * + * @{ + */ +/* TODO */ +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CPU_CONF_H */ +/** @} */ diff --git a/cpu/kw0x/interrupt-vector.c b/cpu/kw0x/interrupt-vector.c new file mode 100644 index 000000000000..38de9c47044d --- /dev/null +++ b/cpu/kw0x/interrupt-vector.c @@ -0,0 +1,129 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_kw0x + * @{ + * + * @file + * @brief Startup code and interrupt vector definition + * + * @author Hauke Petersen + * @author Johann Fischer + * + * @} + */ + +#include +#include "cpu-conf.h" +#include "fault_handlers.h" + +/** + * memory markers as defined in the linker script + */ +extern uint32_t _estack; + +extern void reset_handler(void); + +void dummy_handler(void) +{ + isr_unhandled(); +} + +/* Cortex-M specific interrupt vectors */ +void isr_svc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_systick(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* MKW01Z128 specific interrupt vector */ +void isr_dma0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_ftfa(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_lvd_lvw(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_llwu(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_adc0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_cmp0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tpm0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tpm1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tpm2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc_seconds(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pit(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2s0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dac0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tsi0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_mcg(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_lptmr0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_porta(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_portc_portd(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* interrupt vector table */ +__attribute__((section(".vector_table"))) +const void *interrupt_vector[64] = { + /* Stack pointer */ + (void*) (&_estack), /* pointer to the top of the empty stack */ + /* Cortex-M4 handlers */ + (void*) reset_handler, /* entry point of the program */ + (void*) isr_nmi, /* non maskable interrupt handler */ + (void*) isr_hard_fault, /* if you end up here its not good */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) isr_svc, /* system call interrupt */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */ + (void*) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* MKW01Z128 specific peripheral handlers */ + (void*) isr_dma0, /* DMA channel 0 transfer complete */ + (void*) isr_dma1, /* DMA channel 1 transfer complete */ + (void*) isr_dma2, /* DMA channel 2 transfer complete */ + (void*) isr_dma3, /* DMA channel 3 transfer complete */ + (void*) dummy_handler, /* Reserved interrupt 4 */ + (void*) isr_ftfa, /* FTFA command complete */ + (void*) isr_lvd_lvw, /* Low-Voltage detect and warning */ + (void*) isr_llwu, /* Low leakage wakeup */ + (void*) isr_i2c0, /* Inter-integrated circuit 0 */ + (void*) isr_i2c1, /* Inter-integrated circuit 1 */ + (void*) isr_spi0, /* Serial peripheral Interface 0 */ + (void*) isr_spi1, /* Serial peripheral Interface 1 */ + (void*) isr_uart0, /* UART0 receive/transmit/error interrupt */ + (void*) isr_uart1, /* UART1 receive/transmit/error interrupt */ + (void*) isr_uart2, /* UART2 receive/transmit/error interrupt */ + (void*) isr_adc0, /* Analog-to-digital converter 0 */ + (void*) isr_cmp0, /* Comparator 0 */ + (void*) isr_tpm0, /* Timer module 0 status interrupt */ + (void*) isr_tpm1, /* Timer module 1 status interrupt */ + (void*) isr_tpm2, /* Timer module 2 status interrupt */ + (void*) isr_rtc, /* Real time clock */ + (void*) isr_rtc_seconds, /* Real time clock seconds */ + (void*) isr_pit, /* Periodic interrupt timer channel 0 */ + (void*) isr_i2s0, /* Integrated interchip sound 0 transmit interrupt */ + (void*) dummy_handler, /* Reserved interrupt */ + (void*) isr_dac0, /* Digital-to-analog converter 0 */ + (void*) isr_tsi0, /* TSI0 interrupt */ + (void*) isr_mcg, /* Multipurpose clock generator */ + (void*) isr_lptmr0, /* Low power timer interrupt */ + (void*) dummy_handler, /* Reserved interrupt 29 */ + (void*) isr_porta, /* Port A pin detect interrupt */ + (void*) isr_portc_portd, /* Port C+D pin detect interrupt */ +}; diff --git a/cpu/kw0x/kw01z128_linkerscript.ld b/cpu/kw0x/kw01z128_linkerscript.ld new file mode 100644 index 000000000000..59e54269ca15 --- /dev/null +++ b/cpu/kw0x/kw01z128_linkerscript.ld @@ -0,0 +1,13 @@ +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) + +/* Memory Spaces Definitions */ +MEMORY +{ + vectors (rx) : ORIGIN = 0x00000000, LENGTH = 0x400 + flashsec (rx) : ORIGIN = 0x00000400, LENGTH = 0x10 + flash (rx) : ORIGIN = 0x00000410, LENGTH = 128K - 0x410 + sram (rwx) : ORIGIN = 0x1ffff000, LENGTH = 16K +} + +INCLUDE kinetis-kl0x.ld diff --git a/cpu/kw0x/lpm_arch.c b/cpu/kw0x/lpm_arch.c new file mode 100644 index 000000000000..bf2c1cbf3387 --- /dev/null +++ b/cpu/kw0x/lpm_arch.c @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_kw0x + * @{ + * + * @file + * @brief Implementation of the kernels power management interface + * + * @author Hauke Petersen + * + * @} + */ + +#include "arch/lpm_arch.h" + +void lpm_arch_init(void) +{ + /* TODO */ +} + +enum lpm_mode lpm_arch_set(enum lpm_mode target) +{ + /* TODO */ + return 0; +} + +enum lpm_mode lpm_arch_get(void) +{ + /* TODO */ + return 0; +} + +void lpm_arch_awake(void) +{ + /* TODO */ +} + +void lpm_arch_begin_awake(void) +{ + /* TODO */ +} + +void lpm_arch_end_awake(void) +{ + /* TODO */ +} diff --git a/cpu/kw0x/periph/Makefile b/cpu/kw0x/periph/Makefile new file mode 100644 index 000000000000..6d1887b64009 --- /dev/null +++ b/cpu/kw0x/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/kw0x/reboot_arch.c b/cpu/kw0x/reboot_arch.c new file mode 100644 index 000000000000..7b51ba07cc59 --- /dev/null +++ b/cpu/kw0x/reboot_arch.c @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_kw0x + * @{ + * + * @file + * @brief Implementation of the kernels reboot interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "arch/reboot_arch.h" +#include "cpu.h" + + +int reboot_arch(int mode) +{ + printf("Going into reboot, mode %i\n", mode); + + NVIC_SystemReset(); + + return 0; +} diff --git a/cpu/kw0x/syscalls.c b/cpu/kw0x/syscalls.c new file mode 100644 index 000000000000..81ac4996c8da --- /dev/null +++ b/cpu/kw0x/syscalls.c @@ -0,0 +1,337 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_kw0x + * @{ + * + * @file + * @brief NewLib system call implementations for MKW2xD SiP + * + * @author Michael Baar + * @author Stefan Pfeiffer + * @author Hauke Petersen + * @author Johann Fischer + * + * @} + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "board.h" +#include "thread.h" +#include "kernel.h" +#include "mutex.h" +#include "ringbuffer.h" +#include "irq.h" +#include "periph/uart.h" + +#ifdef MODULE_UART0 +#include "board_uart0.h" +#endif + +/** + * manage the heap + */ +extern uintptr_t __heap_start; /* start of heap memory space */ +extern uintptr_t __heap_max; /* maximum for end of heap memory space */ + +/* current position in heap */ +static caddr_t heap = {(caddr_t)&__heap_start}; +/* maximum position in heap */ +static const caddr_t heap_max = {(caddr_t)&__heap_max}; +/* start position in heap */ +static const caddr_t heap_start = {(caddr_t)&__heap_start}; + +#ifndef MODULE_UART0 +/** + * @brief use mutex for waiting on incoming UART chars + */ +static mutex_t uart_rx_mutex; +static char rx_buf_mem[STDIO_RX_BUFSIZE]; +static ringbuffer_t rx_buf; +#endif + +/** + * @brief Receive a new character from the UART and put it into the receive buffer + */ +void rx_cb(void *arg, char data) +{ +#ifndef MODULE_UART0 + (void)arg; + + ringbuffer_add_one(&rx_buf, data); + mutex_unlock(&uart_rx_mutex); +#else + if (uart0_handler_pid) { + uart0_handle_incoming(data); + + uart0_notify_thread(); + } +#endif +} + +/** + * @brief Initialize NewLib, called by __libc_init_array() from the startup script + */ +void _init(void) +{ +#ifndef MODULE_UART0 + mutex_init(&uart_rx_mutex); + ringbuffer_init(&rx_buf, rx_buf_mem, STDIO_RX_BUFSIZE); +#endif + uart_init(STDIO, STDIO_BAUDRATE, rx_cb, 0, 0); +} + +/** + * @brief Free resources on NewLib de-initialization, not used for RIOT + */ +void _fini(void) +{ + /* nothing to do here */ +} + +/** + * @brief Exit a program without cleaning up files + * + * If your system doesn't provide this, it is best to avoid linking with subroutines that + * require it (exit, system). + * + * @param n the exit code, 0 for all OK, >0 for not OK + */ +void _exit(int n) +{ + printf("#! exit %i: resetting\n", n); + NVIC_SystemReset(); + while(1); +} + +/** + * @brief Allocate memory from the heap. + * + * The current heap implementation is very rudimentary, it is only able to allocate + * memory. But it does not + * - check if the returned address is valid (no check if the memory very exists) + * - have any means to free memory again + * + * @return [description] + */ +caddr_t _sbrk_r(struct _reent *r, size_t incr) +{ + uint32_t cpsr = disableIRQ(); + + caddr_t new_heap = heap + incr; + + /* check the heap for a chunk of the requested size */ + if( new_heap <= heap_max ) { + caddr_t prev_heap = heap; + heap = new_heap; + + r->_errno = 0; + restoreIRQ(cpsr); + return prev_heap; + } + + restoreIRQ(cpsr); + r->_errno = ENOMEM; + return NULL; +} + +/** + * @brief Get the process-ID of the current thread + * + * @return the process ID of the current thread + */ +int _getpid(void) +{ + return sched_active_thread->pid; +} + +/** + * @brief Send a signal to a given thread + * + * @param r TODO + * @param pid TODO + * @param sig TODO + * + * @return TODO + */ +int _kill_r(struct _reent *r, int pid, int sig) +{ + r->_errno = ESRCH; /* not implemented yet */ + return -1; +} + +/** + * @brief Open a file + * + * @param r TODO + * @param name TODO + * @param mode TODO + * + * @return TODO + */ +int _open_r(struct _reent *r, const char *name, int mode) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Read from a file + * + * All input is read from UART_0. The function will block until a byte is actually read. + * + * Note: the read function does not buffer - data will be lost if the function is not + * called fast enough. + * + * TODO: implement more sophisticated read call. + * + * @param r TODO + * @param fd TODO + * @param buffer TODO + * @param int TODO + * + * @return TODO + */ +int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count) +{ +#ifndef MODULE_UART0 + while (rx_buf.avail == 0) { + mutex_lock(&uart_rx_mutex); + } + return ringbuffer_get(&rx_buf, (char*)buffer, rx_buf.avail); +#else + char *res = (char*)buffer; + res[0] = (char)uart0_readc(); + return 1; +#endif +} + +/** + * @brief Write characters to a file + * + * All output is currently directed to UART_0, independent of the given file descriptor. + * The write call will further block until the byte is actually written to the UART. + * + * TODO: implement more sophisticated write call. + * + * @param r TODO + * @param fd TODO + * @param data TODO + * @param int TODO + * + * @return TODO + */ +int _write_r(struct _reent *r, int fd, const void *data, unsigned int count) +{ + char *c = (char*)data; + for (int i = 0; i < count; i++) { + uart_write_blocking(STDIO, c[i]); + } + return count; +} + +/** + * @brief Close a file + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _close_r(struct _reent *r, int fd) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Set position in a file + * + * @param r TODO + * @param fd TODO + * @param pos TODO + * @param dir TODO + * + * @return TODO + */ +_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of an open file + * + * @param r TODO + * @param fd TODO + * @param stat TODO + * + * @return TODO + */ +int _fstat_r(struct _reent *r, int fd, struct stat * st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of a file (by name) + * + * @param r TODO + * @param name TODO + * @param stat TODO + * + * @return TODO + */ +int _stat_r(struct _reent *r, char *name, struct stat *st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Query whether output stream is a terminal + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _isatty_r(struct _reent *r, int fd) +{ + r->_errno = 0; + if(fd == STDOUT_FILENO || fd == STDERR_FILENO) { + return 1; + } + else { + return 0; + } +} + +/** + * @brief Remove a file's directory entry + * + * @param r TODO + * @param path TODO + * + * @return TODO + */ +int _unlink_r(struct _reent *r, char* path) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} diff --git a/doc/doxygen/riot.doxyfile b/doc/doxygen/riot.doxyfile index c825054888d6..5089764f7921 100644 --- a/doc/doxygen/riot.doxyfile +++ b/doc/doxygen/riot.doxyfile @@ -826,6 +826,7 @@ EXCLUDE_PATTERNS = */board/*/tools/* \ */cpu/x86/include/x86_pci.h \ */cpu/sam3x8e/include/sam3x8e.h \ */cpu/stm32l1/include/stm32l1xx.h \ + */cpu/kw0x/include/MKW01Z4.h \ # The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names From d45bc7b31b5a83289dedbf8b1be03d2c8311661a Mon Sep 17 00:00:00 2001 From: Johann F Date: Tue, 30 Dec 2014 19:47:51 +0100 Subject: [PATCH 2/3] add support for phyWAVE-KW01 Board, pba-d-01-kw01 --- boards/pba-d-01-kw01/Makefile | 4 + boards/pba-d-01-kw01/Makefile.features | 6 + boards/pba-d-01-kw01/Makefile.include | 49 +++++ boards/pba-d-01-kw01/board.c | 54 +++++ boards/pba-d-01-kw01/dist/debug.sh | 38 ++++ boards/pba-d-01-kw01/dist/flash.sh | 52 +++++ boards/pba-d-01-kw01/dist/gdb.conf | 4 + boards/pba-d-01-kw01/dist/mkw01z128.cfg | 71 +++++++ boards/pba-d-01-kw01/dist/reset.sh | 6 + boards/pba-d-01-kw01/include/board.h | 103 ++++++++++ boards/pba-d-01-kw01/include/periph_conf.h | 228 +++++++++++++++++++++ 11 files changed, 615 insertions(+) create mode 100644 boards/pba-d-01-kw01/Makefile create mode 100644 boards/pba-d-01-kw01/Makefile.features create mode 100644 boards/pba-d-01-kw01/Makefile.include create mode 100644 boards/pba-d-01-kw01/board.c create mode 100755 boards/pba-d-01-kw01/dist/debug.sh create mode 100755 boards/pba-d-01-kw01/dist/flash.sh create mode 100644 boards/pba-d-01-kw01/dist/gdb.conf create mode 100644 boards/pba-d-01-kw01/dist/mkw01z128.cfg create mode 100755 boards/pba-d-01-kw01/dist/reset.sh create mode 100644 boards/pba-d-01-kw01/include/board.h create mode 100644 boards/pba-d-01-kw01/include/periph_conf.h diff --git a/boards/pba-d-01-kw01/Makefile b/boards/pba-d-01-kw01/Makefile new file mode 100644 index 000000000000..37891de8e6a2 --- /dev/null +++ b/boards/pba-d-01-kw01/Makefile @@ -0,0 +1,4 @@ +# tell the Makefile.base which module to build +MODULE = $(BOARD)_base + +include $(RIOTBASE)/Makefile.base diff --git a/boards/pba-d-01-kw01/Makefile.features b/boards/pba-d-01-kw01/Makefile.features new file mode 100644 index 000000000000..2c1f2218f03c --- /dev/null +++ b/boards/pba-d-01-kw01/Makefile.features @@ -0,0 +1,6 @@ +FEATURES_PROVIDED += periph_uart +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_i2c +FEATURES_PROVIDED += periph_rtt +FEATURES_PROVIDED += periph_rtc +FEATURES_PROVIDED += periph_cpuid diff --git a/boards/pba-d-01-kw01/Makefile.include b/boards/pba-d-01-kw01/Makefile.include new file mode 100644 index 000000000000..8458de420f60 --- /dev/null +++ b/boards/pba-d-01-kw01/Makefile.include @@ -0,0 +1,49 @@ +# define the cpu used by the phyWAVE-KW01 Board +export CPU = kw0x +export CPU_MODEL = kw01z128 + +#define the default port depending on the host OS +OS := $(shell uname) +ifeq ($(OS),Linux) + PORT ?= /dev/ttyACM0 +else ifeq ($(OS),Darwin) + PORT ?= $(shell ls -1 /dev/tty.SLAB_USBtoUART* | head -n 1) +else + $(info CAUTION: No flash tool for your host system found!) +endif +export PORT + +# define tools used for building the project +export PREFIX = arm-none-eabi- +export CC = $(PREFIX)gcc +export AR = $(PREFIX)ar +export AS = $(PREFIX)as +export LINK = $(PREFIX)gcc +export SIZE = $(PREFIX)size +export OBJCOPY = $(PREFIX)objcopy +export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm +export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/flash.sh +export DEBUGGER = $(RIOTBOARD)/$(BOARD)/dist/debug.sh +export RESET = $(RIOTBOARD)/$(BOARD)/dist/reset.sh +export DEBUGSERVER = openocd + +# define build specific options +CPU_USAGE = -mcpu=cortex-m0 -mabi=aapcs +FPU_USAGE = -msoft-float +export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -mthumb -mno-thumb-interwork -nostartfiles +export CFLAGS += -ffunction-sections -fdata-sections -fno-builtin +export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian +export LINKFLAGS += -g3 -ggdb -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -static -lgcc -mthumb -mthumb-interwork -nostartfiles +export LINKFLAGS += -T$(LINKERSCRIPT) +export OFLAGS = -O binary +export FFLAGS = $(HEXFILE) +export DEBUGGER_FLAGS = $(RIOTBOARD)/$(BOARD)/dist/gdb.conf $(ELFFILE) +export TERMFLAGS = -p $(PORT) + +# use newLib nano-specs if available +ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null + * + * @} + */ + +#include "board.h" + +static void leds_init(void); + +void board_init(void) +{ + leds_init(); + cpu_init(); +} + +/** + * @brief Initialize the boards on-board RGB-LED + * + */ +static void leds_init(void) +{ + /* enable clock */ + LED_B_PORT_CLKEN(); + LED_G_PORT_CLKEN(); + LED_R_PORT_CLKEN(); + /* configure pins as gpio */ + LED_B_PORT->PCR[LED_B_PIN] = PORT_PCR_MUX(1); + LED_G_PORT->PCR[LED_G_PIN] = PORT_PCR_MUX(1); + LED_R_PORT->PCR[LED_R_PIN] = PORT_PCR_MUX(1); + LED_B_GPIO->PDDR |= (1 << LED_B_PIN); + LED_G_GPIO->PDDR |= (1 << LED_G_PIN); + LED_R_GPIO->PDDR |= (1 << LED_R_PIN); + /* turn all LEDs off */ + LED_B_GPIO->PSOR |= (1 << LED_B_PIN); + LED_G_GPIO->PSOR |= (1 << LED_G_PIN); + LED_R_GPIO->PSOR |= (1 << LED_R_PIN); +} diff --git a/boards/pba-d-01-kw01/dist/debug.sh b/boards/pba-d-01-kw01/dist/debug.sh new file mode 100755 index 000000000000..82a17591c40c --- /dev/null +++ b/boards/pba-d-01-kw01/dist/debug.sh @@ -0,0 +1,38 @@ +#!/bin/bash + +# Based on iot-lab_M3 debug.sh script. +# Author: Jonas Remmert j.remmert@phytec.de + +red='\033[0;31m' +green='\033[0;32m' +NC='\033[0m' + +openocd -f "$RIOTBASE/boards/pba-d-01-kw01/dist/mkw01z128.cfg" \ + -c "tcl_port 6333" \ + -c "telnet_port 4444" \ + -c "init" \ + -c "targets" \ + -c "reset halt" \ + -l /dev/null & + +# save pid to terminate afterwards +OCD_PID=$? + +# needed for openocd to set up +sleep 1 + +retval=$(arm-none-eabi-readelf -x .fcfield $2 | awk '/0x00000400/ {print $2 $3 $4 $5}') +unlocked_fcfield="fffffffffffffffffffffffffeffffff" + +if [ "$retval" == "$unlocked_fcfield" ]; then +echo -e "Flash configuration tested...${green} [OK]${NC}" +arm-none-eabi-gdb -tui --command=${1} ${2} +#cgdb -d arm-none-eabi-gdb --command=${1} ${2} + +else +echo "Hexdump, .fcfield of $2" +retval=$(arm-none-eabi-readelf -x .fcfield $2) +echo $retval +echo -e "Fcfield not fitting to MKW01Z128, danger of bricking the device during flash...${red} [ABORT]${NC}" +fi +kill ${OCD_PID} diff --git a/boards/pba-d-01-kw01/dist/flash.sh b/boards/pba-d-01-kw01/dist/flash.sh new file mode 100755 index 000000000000..5324a60f32e9 --- /dev/null +++ b/boards/pba-d-01-kw01/dist/flash.sh @@ -0,0 +1,52 @@ +#!/bin/bash + +# Based on iot-lab_M3 debug.sh script. +# Author: Jonas Remmert j.remmert@phytec.de + +elffile=`echo $1 | sed 's/.hex/.elf/'` + +red='\033[0;31m' +green='\033[0;32m' +NC='\033[0m' + +echo The file: $elffile will be flashed to the board: $BOARD . +echo Press y to proceed, v to proceed with verify or any other key to abort. +read x + +retval=$(arm-none-eabi-readelf -x .fcfield $elffile | awk '/0x00000400/ {print $2 $3 $4 $5}') +unlocked_fcfield="fffffffffffffffffffffffffeffffff" + +if [ "$retval" != "$unlocked_fcfield" ]; then +echo "Hexdump, .fcfield of $elffile" +retval=$(arm-none-eabi-readelf -x .fcfield $elffile) +echo $retval +echo -e "Fcfield not fitting to MKW01Z128, danger of bricking the device during flash...${red} [ABORT]${NC}" +exit 0 +fi +echo -e "Flash configuration tested...${green} [OK]${NC}" + + +# flash without verify +#if [ $x = "y" ] || [ $x = "v" ];# -o $x -eq v ]; +#then +echo -e "${red}Flashing device, do not disconnect or reset the target until this script exits!!!${NC}" +openocd -f "$RIOTBASE/boards/pba-d-01-kw01/dist/mkw01z128.cfg" \ + -c "init" \ + -c "reset halt" \ + -c "flash write_image erase $elffile" \ + -c "reset run" \ + -c "exit" +#fi + +# verify +#if [ "$x" = "v" ]; +#then +#echo -e "${red}Flashing device, do not disconnect or reset the target until this script exits!!!${NC}" +#openocd -f "$RIOTBASE/boards/pba-d-01-kw01/dist/mkw01z128.cfg" \ +# -c "init" \ +# -c "reset halt" \ +# -c "verify_image $elffile" \ +# -c "reset run" \ +# -c "exit" +#fi +echo -e "${green}done...${NC}" diff --git a/boards/pba-d-01-kw01/dist/gdb.conf b/boards/pba-d-01-kw01/dist/gdb.conf new file mode 100644 index 000000000000..4e958739f36e --- /dev/null +++ b/boards/pba-d-01-kw01/dist/gdb.conf @@ -0,0 +1,4 @@ +target remote localhost:3333 +monitor reset halt +set print pretty +set arm force-mode thumb diff --git a/boards/pba-d-01-kw01/dist/mkw01z128.cfg b/boards/pba-d-01-kw01/dist/mkw01z128.cfg new file mode 100644 index 000000000000..c0f8998d79e7 --- /dev/null +++ b/boards/pba-d-01-kw01/dist/mkw01z128.cfg @@ -0,0 +1,71 @@ +# +# Freescale Kinetis MKW01Z128 devices +# +source [find interface/cmsis-dap.cfg] + +# +# K21 devices support both JTAG and SWD transports. +# +source [find target/swj-dp.tcl] + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME kw01z128 +} + +# Work-area is a space in RAM used for flash programming +set WORKAREASIZE 0x1000 + +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x1000 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +if { [info exists CPUTAPID] } { + set _CPUTAPID $CPUTAPID +} else { + set _CPUTAPID 0x0bc11477 +} + +set _TARGETNAME $_CHIPNAME.cpu + +swj_newdap $_CHIPNAME cpu -irlen 4 -expected-id $_CPUTAPID +#swj_newdap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +target create $_TARGETNAME cortex_m -chain-position $_CHIPNAME.cpu + +$_CHIPNAME.cpu configure -event examine-start { puts "START..." ; } + +# It is important that "kinetis mdm check_security" is called for +# 'examine-end' event and not 'eximine-start'. Calling it in 'examine-start' +# causes "kinetis mdm check_security" to fail the first time openocd +# calls it when it tries to connect after the CPU has been power-cycled. +$_CHIPNAME.cpu configure -event examine-end { + kinetis mdm check_security +} + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME kinetis 0 0 0 0 $_TARGETNAME + +#reset_config srst_only srst_nogate connect_assert_srst +adapter_khz 10000 + +if {![using_hla]} { + # if srst is not fitted use SYSRESETREQ to + # perform a soft reset + cortex_m reset_config sysresetreq +} + +$_TARGETNAME configure -event reset-init { + adapter_khz 24000 +} diff --git a/boards/pba-d-01-kw01/dist/reset.sh b/boards/pba-d-01-kw01/dist/reset.sh new file mode 100755 index 000000000000..68f193131d3a --- /dev/null +++ b/boards/pba-d-01-kw01/dist/reset.sh @@ -0,0 +1,6 @@ +#!/bin/bash + +openocd -f "$RIOTBASE/boards/pba-d-01-kw01/dist/mkw01z128.cfg" \ + -c "init" \ + -c "reset run" \ + -c "shutdown" diff --git a/boards/pba-d-01-kw01/include/board.h b/boards/pba-d-01-kw01/include/board.h new file mode 100644 index 000000000000..09e64b2b2b4b --- /dev/null +++ b/boards/pba-d-01-kw01/include/board.h @@ -0,0 +1,103 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @defgroup board_pba-d-01-kw01 phyWAVE-KW01 Evalboard + * @ingroup boards + * @brief Board specific implementations for the phyWAVE-KW01 evaluation board + * @{ + * + * @file + * @brief Board specific definitions for the phyWAVE-KW01 evaluation board + * + * @author Johann Fischer + */ + +#ifndef __BOARD_H +#define __BOARD_H + +#include "cpu.h" +#include "periph_conf.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * Define the nominal CPU core clock in this board + */ +#define F_CPU CLOCK_CORECLOCK + +/** + * @name Define UART device and baudrate for stdio + * @{ + */ +#define STDIO UART_0 +#define STDIO_RX_BUFSIZE (64U) +#define STDIO_BAUDRATE (115200U) +/** @} */ + +/** + * @name LED pin definitions + * @{ + */ +#define LED_R_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTA_MASK)) /**< Clock Enable for PORTD*/ +#define LED_G_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK)) /**< Clock Enable for PORTD*/ +#define LED_B_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK)) /**< Clock Enable for PORTA*/ +#define LED_R_PORT PORTA /**< PORT for Red LED */ +#define LED_R_GPIO GPIOA /**< GPIO-Device for Red LED */ +#define LED_G_PORT PORTB /**< PORT for Green LED */ +#define LED_G_GPIO GPIOB /**< GPIO-Device for Green LED */ +#define LED_B_PORT PORTC /**< PORT for Blue LED */ +#define LED_B_GPIO GPIOC /**< GPIO-Device for Blue LED */ +#define LED_R_PIN 4 /**< Red LED connected to PINx */ +#define LED_G_PIN 2 /**< Green LED connected to PINx */ +#define LED_B_PIN 3 /**< Blue LED connected to PINx */ +/** @} */ + +/** + * @name Macros for controlling the on-board LEDs. + * @{ + */ +#define LED_B_ON (LED_B_GPIO->PCOR |= (1 << LED_B_PIN)) +#define LED_B_OFF (LED_B_GPIO->PSOR |= (1 << LED_B_PIN)) +#define LED_B_TOGGLE (LED_B_GPIO->PTOR |= (1 << LED_B_PIN)) +#define LED_G_ON (LED_G_GPIO->PCOR |= (1 << LED_G_PIN)) +#define LED_G_OFF (LED_G_GPIO->PSOR |= (1 << LED_G_PIN)) +#define LED_G_TOGGLE (LED_G_GPIO->PTOR |= (1 << LED_G_PIN)) +#define LED_R_ON (LED_R_GPIO->PCOR |= (1 << LED_R_PIN)) +#define LED_R_OFF (LED_R_GPIO->PSOR |= (1 << LED_R_PIN)) +#define LED_R_TOGGLE (LED_R_GPIO->PTOR |= (1 << LED_R_PIN)) + +/* for compatability to other boards */ +#define LED_GREEN_ON LED_G_ON +#define LED_GREEN_OFF LED_G_OFF +#define LED_GREEN_TOGGLE LED_G_TOGGLE +#define LED_RED_ON LED_R_ON +#define LED_RED_OFF LED_R_OFF +#define LED_RED_TOGGLE LED_R_TOGGLE +/** @} */ + +/** + * Define the type for the radio packet length for the transceiver + */ +typedef uint8_t radio_packet_length_t; + +/** + * @brief Initialize board specific hardware, including clock, LEDs and std-IO + */ +void board_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /** __BOARD_H */ +/** @} */ diff --git a/boards/pba-d-01-kw01/include/periph_conf.h b/boards/pba-d-01-kw01/include/periph_conf.h new file mode 100644 index 000000000000..37cec6fe5a4b --- /dev/null +++ b/boards/pba-d-01-kw01/include/periph_conf.h @@ -0,0 +1,228 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2015 PHYTEC Messtechnik GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup board_pba-d-01-kw01 + * @{ + * + * @file + * @name Peripheral MCU configuration for the phyWAVE-KW01 + * + * @author Hauke Petersen + * @author Johann Fischer + */ + +#ifndef __PERIPH_CONF_H +#define __PERIPH_CONF_H + +#include "cpu-conf.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * @name Clock system configuration + * @{ + */ +#define KINETIS_CPU_USE_MCG 1 + +#define KINETIS_MCG_USE_ERC 1 +#define KINETIS_MCG_ERC_FREQ 32768 +#define KINETIS_MCG_ERC_FRDIV 0 +#define KINETIS_MCG_ERC_RANGE 0 +#define KINETIS_MCG_ERC_OSCILLATOR 1 + +#define KINETIS_MCG_USE_PLL 0 + +#define KINETIS_MCG_USE_FAST_IRC 0 + +#define CLOCK_CORECLOCK (48e6) /* core clock frequency */ +/** @} */ + + +/** + * @name Timer configuration + * @{ + */ +#define TIMER_NUMOF (0U) +#define TIMER_0_EN 0 +#define TIMER_1_EN 0 +#define TIMER_2_EN 0 +#define TIMER_IRQ_PRIO 1 +/** @} */ + + +/** + * @name UART configuration + * @{ + */ +#define UART_NUMOF (1U) +#define UART_0_EN 1 +#define UART_1_EN 0 +#define UART_IRQ_PRIO 1 +#define UART_CLK (48e6) + +/* UART 0 device configuration */ +#define KINETIS_UART UART0_Type +#define UART_0_DEV UART0 +#define UART_0_CLKEN() (SIM->SCGC4 |= (SIM_SCGC4_UART0_MASK)) +#define UART_0_CLK UART_CLK +#define UART_0_IRQ_CHAN UART0_IRQn +#define UART_0_ISR isr_uart0 +/* UART 0 pin configuration */ +#define UART_0_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTA_MASK)) +#define UART_0_PORT PORTA +#define UART_0_RX_PIN 1 +#define UART_0_TX_PIN 2 +#define UART_0_AF 2 +/** @} */ + + +/** + * @name ADC configuration + * @{ + */ +#define ADC_NUMOF (0U) +#define ADC_0_EN 0 +#define ADC_MAX_CHANNELS 0 +/** @} */ + + +/** + * @name PWM configuration + * @{ + */ +#define PWM_NUMOF (0U) +#define PWM_0_EN 0 +#define PWM_MAX_CHANNELS 0 +/** @} */ + + +/** + * @name SPI configuration + * @{ + */ +#define SPI_NUMOF (0U) +#define SPI_CLK (48e6) +#define SPI_0_EN 0 +#define SPI_IRQ_PRIO 1 + +/* SPI 0 device config */ +#define SPI_0_DEV SPI0 +#define SPI_0_CLKEN() (SIM->SCGC6 |= (SIM_SCGC4_SPI1_MASK)) +#define SPI_0_CLKDIS() (SIM->SCGC6 &= ~(SIM_SCGC4_SPI1_MASK)) +#define SPI_0_IRQ SPI0_IRQn +#define SPI_0_IRQ_HANDLER isr_spi0 +/* SPI 0 pin configuration */ +#define SPI_0_PORT PORTD +#define SPI_0_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTD_MASK)) +#define SPI_0_PIN_AF 2 +#define SPI_0_PCS0_PIN 4 +#define SPI_0_SCK_PIN 5 +#define SPI_0_SOUT_PIN 6 +#define SPI_0_SIN_PIN 7 +/** @} */ + + +/** + * @name I2C configuration + * @{ + */ +#define I2C_NUMOF (1U) +#define I2C_CLK (48e6) +#define I2C_0_EN 1 +#define I2C_IRQ_PRIO 1 +/* Low (10 kHz): MUL = 4, SCL divider = 2560, total: 10240 */ +#define KINETIS_I2C_F_ICR_LOW (0x3D) +#define KINETIS_I2C_F_MULT_LOW (2) +/* Normal (100 kHz): MUL = 2, SCL divider = 240, total: 480 */ +#define KINETIS_I2C_F_ICR_NORMAL (0x1F) +#define KINETIS_I2C_F_MULT_NORMAL (1) +/* Fast (400 kHz): MUL = 1, SCL divider = 128, total: 128 */ +#define KINETIS_I2C_F_ICR_FAST (0x17) +#define KINETIS_I2C_F_MULT_FAST (0) +/* Fast plus (1000 kHz): MUL = 1, SCL divider = 48, total: 48 */ +#define KINETIS_I2C_F_ICR_FAST_PLUS (0x10) +#define KINETIS_I2C_F_MULT_FAST_PLUS (0) + +/* I2C 0 device configuration */ +#define I2C_0_DEV I2C1 +#define I2C_0_CLKEN() (SIM->SCGC4 |= (SIM_SCGC4_I2C1_MASK)) +#define I2C_0_CLKDIS() (SIM->SCGC4 &= ~(SIM_SCGC4_I2C1_MASK)) +#define I2C_0_IRQ I2C1_IRQn +#define I2C_0_IRQ_HANDLER isr_i2c1 +/* I2C 0 pin configuration */ +#define I2C_0_PORT PORTC +#define I2C_0_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK)) +#define I2C_0_PIN_AF 2 +#define I2C_0_SDA_PIN 2 +#define I2C_0_SCL_PIN 1 +#define I2C_0_PORT_CFG (PORT_PCR_MUX(I2C_0_PIN_AF)) + +/** @} */ + + +/** + * @name GPIO configuration + * @{ + */ +#define GPIO_NUMOF 3 +#define GPIO_0_EN 1 /* DIO11 */ +#define GPIO_1_EN 1 /* DIO27 */ +#define GPIO_2_EN 1 /* DIO2 */ +#define GPIO_IRQ_PRIO 1 + +/* GPIO channel 0 config */ +#define GPIO_0_DEV GPIOA +#define GPIO_0_PORT PORTA +#define GPIO_0_PIN 4 +#define GPIO_0_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTA_MASK)) +#define GPIO_0_IRQ PORTA_IRQn +#define GPIO_0_ISR isr_porta +/* GPIO channel 1 config */ +#define GPIO_1_DEV GPIOC +#define GPIO_1_PORT PORTC +#define GPIO_1_PIN 3 +#define GPIO_1_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK)) +#define GPIO_1_IRQ PORTC_PORTD_IRQn +#define GPIO_1_ISR isr_portc +/* GPIO channel 3 config */ +#define GPIO_2_DEV GPIOD +#define GPIO_2_PORT PORTD +#define GPIO_2_PIN 4 +#define GPIO_2_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTD_MASK)) +#define GPIO_2_IRQ PORTC_PORTD_IRQn +#define GPIO_2_ISR isr_portd +/** @} */ + +/** +* @name RTT and RTC configuration +* @{ +*/ +#define RTT_NUMOF (1U) +#define RTC_NUMOF (1U) +#define RTT_DEV RTC +#define RTT_IRQ RTC_IRQn +#define RTT_IRQ_PRIO 10 +#define RTT_UNLOCK() (SIM->SCGC6 |= (SIM_SCGC6_RTC_MASK)) +#define RTT_ISR isr_rtc +#define RTT_FREQUENCY (1) +#define RTT_MAX_VALUE (0xffffffff) +/** @} */ + +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* __PERIPH_CONF_H */ +/** @} */ From 08cc10860c5d6351e0a7f5034d7fb9f1b7bf3c9d Mon Sep 17 00:00:00 2001 From: Johann Fischer Date: Mon, 23 Mar 2015 14:47:17 +0100 Subject: [PATCH 3/3] tests: add pba-d-01-kw01 to the pthread_rwlock, thread_cooperation insufficient ram blasklists --- tests/pthread_rwlock/Makefile | 2 +- tests/thread_cooperation/Makefile | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/tests/pthread_rwlock/Makefile b/tests/pthread_rwlock/Makefile index fc571f233625..3b722a909f43 100644 --- a/tests/pthread_rwlock/Makefile +++ b/tests/pthread_rwlock/Makefile @@ -14,6 +14,6 @@ CFLAGS += -DNATIVE_AUTO_EXIT BOARD_INSUFFICIENT_RAM += chronos mbed_lpc1768 msb-430 msb-430h stm32f0discovery \ pca10000 pca10005 yunjia-nrf51822 spark-core nucleo-f334 \ - airfy-beacon + airfy-beacon pba-d-01-kw01 include $(RIOTBASE)/Makefile.include diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index 8b88072e974b..82f3f84eb6b6 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -2,7 +2,8 @@ APPLICATION = thread_cooperation include ../Makefile.tests_common BOARD_INSUFFICIENT_RAM := chronos msb-430 msb-430h mbed_lpc1768 redbee-econotag stm32f0discovery \ - pca10000 pca10005 yunjia-nrf51822 spark-core airfy-beacon nucleo-f334 + pca10000 pca10005 yunjia-nrf51822 spark-core airfy-beacon nucleo-f334 \ + pba-d-01-kw01 DISABLE_MODULE += auto_init