From 6d5973f9584b7816d6a362e14f9a070fd544f6bf Mon Sep 17 00:00:00 2001 From: Johann F Date: Tue, 6 Jan 2015 00:21:08 +0100 Subject: [PATCH] add support for Freescale KW22D512 SiP --- cpu/cortex-m4_common/crash.c | 67 + cpu/kw2x/Makefile | 7 + cpu/kw2x/Makefile.include | 37 + cpu/kw2x/cpu.c | 148 + cpu/kw2x/include/MKW22D5.h | 9388 +++++++++++++++++ cpu/kw2x/include/cpu-conf.h | 123 + cpu/kw2x/kw22d512_linkerscript.ld | 174 + cpu/kw2x/lpm_arch.c | 53 + cpu/kw2x/periph/Makefile | 3 + cpu/kw2x/reboot_arch.c | 34 + cpu/kw2x/startup.c | 492 + cpu/kw2x/syscalls.c | 345 + dist/tools/licenses/patterns/3c-BSD-freescale | 1 + doc/doxygen/riot.doxyfile | 1 + 14 files changed, 10873 insertions(+) create mode 100644 cpu/cortex-m4_common/crash.c create mode 100644 cpu/kw2x/Makefile create mode 100644 cpu/kw2x/Makefile.include create mode 100644 cpu/kw2x/cpu.c create mode 100644 cpu/kw2x/include/MKW22D5.h create mode 100644 cpu/kw2x/include/cpu-conf.h create mode 100644 cpu/kw2x/kw22d512_linkerscript.ld create mode 100644 cpu/kw2x/lpm_arch.c create mode 100644 cpu/kw2x/periph/Makefile create mode 100644 cpu/kw2x/reboot_arch.c create mode 100644 cpu/kw2x/startup.c create mode 100644 cpu/kw2x/syscalls.c create mode 100644 dist/tools/licenses/patterns/3c-BSD-freescale diff --git a/cpu/cortex-m4_common/crash.c b/cpu/cortex-m4_common/crash.c new file mode 100644 index 000000000000..9aa72b60f010 --- /dev/null +++ b/cpu/cortex-m4_common/crash.c @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2014 INRIA + * + * 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 cortex-m3_common + * @{ + * + * @file crash.c + * @brief Crash handling functions implementation for ARM Cortex-based MCUs + * + * @author Oliver Hahm + */ + +#include "cpu.h" +#include "lpm.h" +#include "crash.h" + +#include +#include + +/* "public" variables holding the crash data */ +char panic_str[80]; +int panic_code; + +/* flag preventing "recursive crash printing loop" */ +static int crashed = 0; + +/* WARNING: this function NEVER returns! */ +NORETURN void core_panic(int crash_code, const char *message) +{ + /* copy panic datas to "public" global variables */ + panic_code = crash_code; + strncpy(panic_str, message, 80); + /* print panic message to console (if possible) */ + if (crashed == 0) { + crashed = 1; + puts("******** SYSTEM FAILURE ********\n"); + puts(message); +#if DEVELHELP + puts("******** RIOT HALTS HERE ********\n"); +#else + puts("******** RIOT WILL REBOOT ********\n"); +#endif + puts("\n\n"); + } + /* disable watchdog and all possible sources of interrupts */ + //TODO + dINT(); +#if DEVELHELP + /* enter infinite loop, into deepest possible sleep mode */ + while (1) { + lpm_set(LPM_OFF); + } +#else + /* DEVELHELP not set => reboot system */ + (void) reboot(RB_AUTOBOOT); +#endif + + /* tell the compiler that we won't return from this function + (even if we actually won't even get here...) */ + UNREACHABLE(); +} diff --git a/cpu/kw2x/Makefile b/cpu/kw2x/Makefile new file mode 100644 index 000000000000..73e16d02df7e --- /dev/null +++ b/cpu/kw2x/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_M4_COMMON) $(KINETIS_COMMON) + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/kw2x/Makefile.include b/cpu/kw2x/Makefile.include new file mode 100644 index 000000000000..ffedd161bd02 --- /dev/null +++ b/cpu/kw2x/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-m4_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_M4_COMMON = $(RIOTCPU)/cortex-m4_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_M4_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/syscalls.o +export UNDEF += $(BINDIR)cpu/startup.o diff --git a/cpu/kw2x/cpu.c b/cpu/kw2x/cpu.c new file mode 100644 index 000000000000..8314d1d2412a --- /dev/null +++ b/cpu/kw2x/cpu.c @@ -0,0 +1,148 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014 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_kw2x + * @{ + * + * @file + * @brief Implementation of the KW2xD 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 + * + * WIP: Finally it initializes the PLL clock with 48 MHz. This is initial work. + */ +static void cpu_clock_init(void) +{ + /* setup MCG in FEI Mode, core clock = bus clock = 41.94MHz */ + /* setup system prescalers */ + SIM->CLKDIV1 = (uint32_t)SIM_CLKDIV1_OUTDIV4(1); + + /* enable and select slow internal reference clock */ + MCG->C1 = (uint8_t)(1 << MCG_C1_IREFS_SHIFT | 1 << MCG_C1_IRCLKEN_SHIFT); + + /* defaults */ + MCG->C2 = (uint8_t)0; + + /* DCO Range: 40MHz .. 50MHz, FLL Factor = 1280 */ + MCG->C4 &= ~(uint8_t)(1 << MCG_C4_DMX32_SHIFT); + MCG->C4 |= (uint8_t)MCG_C4_DRST_DRS(1); + + /* defaults */ + MCG->C5 = (uint8_t)0; + + /* defaults */ + MCG->C6 = (uint8_t)0; + + /* source of the FLL reference clock shall be internal reference clock */ + while ((MCG->S & MCG_S_IREFST_MASK) == 0); + + /* Wait until output of the FLL is selected */ + while (MCG->S & (MCG_S_LOCK0_MASK | MCG_S_LOLS_MASK)); + + SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK); + SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK); + /* Use the CLK_OUT of the modem as the clock source. */ + /* Path: FEI-Mode -> FBE-Mode -> PBE-Mode -> PEE-Mode */ + /* Modem RST_B is connected to PTB19 and can be used to reset the modem. */ + PORTB->PCR[19] = PORT_PCR_MUX(1); + GPIOB->PDDR |= (1 << 19); + GPIOB->PCOR |= (1 << 19); + /* Modem GPIO5 is connected to PTC0 and can be used to select CLK_OUT frequency, */ + /* set PTC0 high for CLK_OUT=32.787kHz and low for CLK_OUT=4MHz. */ + PORTC->PCR[0] = PORT_PCR_MUX(1); + GPIOC->PDDR |= (1 << 0); + GPIOC->PCOR |= (1 << 0); + /* Modem IRQ_B is connected to PTB3, modem interrupt request to the MCU. */ + PORTB->PCR[KW2XDRF_IRQ_PIN] = PORT_PCR_MUX(1); + GPIOB->PDDR &= ~(1 << KW2XDRF_IRQ_PIN); + + /* release the reset */ + GPIOB->PSOR |= (1 << 19); + + /* wait for modem IRQ_B interrupt request */ + while (GPIOB->PDIR & (1 << KW2XDRF_IRQ_PIN)); + + /* program PLL and switch MCU clock, 48MHz */ + /* setup system prescalers */ + SIM->CLKDIV1 = (uint32_t)SIM_CLKDIV1_OUTDIV4(1); + + /* clear OSC control register*/ + OSC->CR = (uint8_t)OSC_CR_ERCLKEN_MASK; + + /* Select OSCCLK */ + MCG->C7 = (uint8_t)0; + + /* select high frequency range and external clock mode*/ + MCG->C2 = (uint8_t)(MCG_C2_RANGE0(1)); + + /* select external reference clock and divide factor 128 */ + MCG->C1 = (uint8_t)(MCG_C1_CLKS(2) | MCG_C1_FRDIV(2)); + + /* wait fo OSC initialization */ + /* while ((MCG->S & MCG_S_OSCINIT0_MASK) == 0); */ + + /* source of the FLL reference clock shall be internal reference clock */ + while (MCG->S & MCG_S_IREFST_MASK); + + /* Wait until external reference clock is selected */ + while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(2)); + + /* clear DCO register */ + MCG->C4 &= (uint8_t)~(MCG_C4_FCTRIM_MASK | MCG_C4_SCFTRIM_MASK); + + /* set external reference devider to 2 (0b0001) */ + MCG->C5 = (uint8_t)(MCG_C5_PRDIV0(1)); + + /* select PLL */ + MCG->C6 = (uint8_t)(MCG_C6_PLLS_MASK); + + /* Wait until the source of the PLLS clock is PLL */ + while ((MCG->S & MCG_S_PLLST_MASK) == 0); + + /* Wait until PLL locked */ + while ((MCG->S & MCG_S_LOCK0_MASK) == 0); + + /* select internal reference clock and divide factor 128 */ + MCG->C1 = (uint8_t)(MCG_C1_FRDIV(2)); + + /* Wait until output of the PLL is selected */ + while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(3)); + + /* Wait until PLL locked */ + while ((MCG->S & MCG_S_LOCK0_MASK) == 0); +} diff --git a/cpu/kw2x/include/MKW22D5.h b/cpu/kw2x/include/MKW22D5.h new file mode 100644 index 000000000000..3797364071bf --- /dev/null +++ b/cpu/kw2x/include/MKW22D5.h @@ -0,0 +1,9388 @@ +/* +** ################################################################### +** Compilers: ARM 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: K22RM, Rev.4, Feb 2013 +** Version: rev. 1.7, 2014-05-27 +** Build: b140603 +** +** Abstract: +** CMSIS Peripheral Access Layer for MK22D5 +** +** Copyright (c) 1997 - 2014 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 (2012-06-06) +** Initial public version. +** - rev. 1.1 (2012-07-31) +** Fixed address of SIM_SDID register. +** - rev. 1.2 (2012-08-29) +** Update to Rev. 3 of reference manual. +** Updated UART0, RTC and CRC register definition. +** - rev. 1.3 (2012-10-11) +** PDB module update - PDB0_PO1DLY register added. +** - rev. 1.4 (2013-01-24) +** Update to Rev. 4 of reference manual. +** - rev. 1.5 (2013-04-05) +** Changed start of doxygen comment. +** - rev. 1.6 (2013-06-24) +** NV_FOPT register - NMI_DIS bit added. +** - rev. 1.7 (2014-05-27) +** Updated to Kinetis SDK support standard. +** MCG OSC clock select supported (MCG_C7[OSCSEL]). +** +** ################################################################### +*/ + +/*! + * @file MK22D5.h + * @version 1.7 + * @date 2014-05-27 + * @brief CMSIS Peripheral Access Layer for MK22D5 + * + * CMSIS Peripheral Access Layer for MK22D5 + */ + + +/* ---------------------------------------------------------------------------- + -- MCU activation + ---------------------------------------------------------------------------- */ + +/* Prevention from multiple including the same memory map */ +#if !defined(MK22D5_H_) /* Check if memory map has not been already included */ +#define MK22D5_H_ +#define MCU_MK22D5 + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* Check if another memory map has not been also included */ +#if (defined(MCU_ACTIVE)) + #error MK22D5 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 0x0007u + +/** + * @brief Macro to calculate address of an aliased word in the peripheral + * bitband area for a peripheral register and bit (bit band region 0x40000000 to + * 0x400FFFFF). + * @param Reg Register to access. + * @param Bit Bit number to access. + * @return Address of the aliased word in the peripheral bitband area. + */ +#define BITBAND_REGADDR(Reg,Bit) (0x42000000u + (32u*((uint32_t)&(Reg) - (uint32_t)0x40000000u)) + (4u*((uint32_t)(Bit)))) +/** + * @brief Macro to access a single bit of a peripheral register (bit band region + * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can + * be used for peripherals with 32bit access allowed. + * @param Reg Register to access. + * @param Bit Bit number to access. + * @return Value of the targeted bit in the bit band region. + */ +#define BITBAND_REG32(Reg,Bit) (*((uint32_t volatile*)(BITBAND_REGADDR(Reg,Bit)))) +#define BITBAND_REG(Reg,Bit) (BITBAND_REG32(Reg,Bit)) +/** + * @brief Macro to access a single bit of a peripheral register (bit band region + * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can + * be used for peripherals with 16bit access allowed. + * @param Reg Register to access. + * @param Bit Bit number to access. + * @return Value of the targeted bit in the bit band region. + */ +#define BITBAND_REG16(Reg,Bit) (*((uint16_t volatile*)(BITBAND_REGADDR(Reg,Bit)))) +/** + * @brief Macro to access a single bit of a peripheral register (bit band region + * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can + * be used for peripherals with 8bit access allowed. + * @param Reg Register to access. + * @param Bit Bit number to access. + * @return Value of the targeted bit in the bit band region. + */ +#define BITBAND_REG8(Reg,Bit) (*((uint8_t volatile*)(BITBAND_REGADDR(Reg,Bit)))) + +/* ---------------------------------------------------------------------------- + -- Interrupt vector numbers + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Interrupt_vector_numbers Interrupt vector numbers + * @{ + */ + +/** Interrupt Number Definitions */ +#define NUMBER_OF_INT_VECTORS 81 /**< Number of interrupts in the Vector table */ + +typedef enum IRQn { + /* Core interrupts */ + NonMaskableInt_IRQn = -14, /**< Non Maskable Interrupt */ + HardFault_IRQn = -13, /**< Cortex-M4 SV Hard Fault Interrupt */ + MemoryManagement_IRQn = -12, /**< Cortex-M4 Memory Management Interrupt */ + BusFault_IRQn = -11, /**< Cortex-M4 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /**< Cortex-M4 Usage Fault Interrupt */ + SVCall_IRQn = -5, /**< Cortex-M4 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /**< Cortex-M4 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /**< Cortex-M4 Pend SV Interrupt */ + SysTick_IRQn = -1, /**< Cortex-M4 System Tick Interrupt */ + + /* Device specific interrupts */ + DMA0_IRQn = 0, /**< DMA channel 0 transfer complete */ + DMA1_IRQn = 1, /**< DMA channel 1 transfer complete */ + DMA2_IRQn = 2, /**< DMA channel 2 transfer complete */ + DMA3_IRQn = 3, /**< DMA channel 3 transfer complete */ + DMA4_IRQn = 4, /**< DMA channel 4 transfer complete */ + DMA5_IRQn = 5, /**< DMA channel 5 transfer complete */ + DMA6_IRQn = 6, /**< DMA channel 6 transfer complete */ + DMA7_IRQn = 7, /**< DMA channel 7 transfer complete */ + DMA8_IRQn = 8, /**< DMA channel 8 transfer complete */ + DMA9_IRQn = 9, /**< DMA channel 9 transfer complete */ + DMA10_IRQn = 10, /**< DMA channel 10 transfer complete */ + DMA11_IRQn = 11, /**< DMA channel 11 transfer complete */ + DMA12_IRQn = 12, /**< DMA channel 12 transfer complete */ + DMA13_IRQn = 13, /**< DMA channel 13 transfer complete */ + DMA14_IRQn = 14, /**< DMA channel 14 transfer complete */ + DMA15_IRQn = 15, /**< DMA channel 15 transfer complete */ + DMA_Error_IRQn = 16, /**< DMA channel 0 - 15 error */ + MCM_IRQn = 17, /**< MCM normal interrupt */ + FTFL_IRQn = 18, /**< FTFL command complete */ + Read_Collision_IRQn = 19, /**< FTFL read collision */ + LVD_LVW_IRQn = 20, /**< PMC controller low-voltage detect, low-voltage warning */ + LLW_IRQn = 21, /**< Low leakage wakeup */ + Watchdog_IRQn = 22, /**< Single interrupt vector for WDOG and EWM */ + Reserved39_IRQn = 23, /**< Reserved interrupt */ + I2C0_IRQn = 24, /**< Inter-integrated circuit 0 */ + I2C1_IRQn = 25, /**< Inter-integrated circuit 1 */ + SPI0_IRQn = 26, /**< Serial peripheral Interface 0 */ + SPI1_IRQn = 27, /**< Serial peripheral Interface 1 */ + I2S0_Tx_IRQn = 28, /**< Integrated interchip sound 0 transmit interrupt */ + I2S0_Rx_IRQn = 29, /**< Integrated interchip sound 0 receive interrupt */ + Reserved46_IRQn = 30, /**< Reserved interrupt */ + UART0_RX_TX_IRQn = 31, /**< UART0 receive/transmit interrupt */ + UART0_ERR_IRQn = 32, /**< UART0 error interrupt */ + UART1_RX_TX_IRQn = 33, /**< UART1 receive/transmit interrupt */ + UART1_ERR_IRQn = 34, /**< UART1 error interrupt */ + UART2_RX_TX_IRQn = 35, /**< UART2 receive/transmit interrupt */ + UART2_ERR_IRQn = 36, /**< UART2 error interrupt */ + UART3_RX_TX_IRQn = 37, /**< UART3 receive/transmit interrupt */ + UART3_ERR_IRQn = 38, /**< UART3 error interrupt */ + ADC0_IRQn = 39, /**< Analog-to-digital converter 0 */ + CMP0_IRQn = 40, /**< Comparator 0 */ + CMP1_IRQn = 41, /**< Comparator 1 */ + FTM0_IRQn = 42, /**< FlexTimer module 0 fault, overflow and channels interrupt */ + FTM1_IRQn = 43, /**< FlexTimer module 1 fault, overflow and channels interrupt */ + FTM2_IRQn = 44, /**< FlexTimer module 2 fault, overflow and channels interrupt */ + CMT_IRQn = 45, /**< Carrier modulator transmitter */ + RTC_IRQn = 46, /**< Real time clock */ + RTC_Seconds_IRQn = 47, /**< Real time clock seconds */ + PIT0_IRQn = 48, /**< Periodic interrupt timer channel 0 */ + PIT1_IRQn = 49, /**< Periodic interrupt timer channel 1 */ + PIT2_IRQn = 50, /**< Periodic interrupt timer channel 2 */ + PIT3_IRQn = 51, /**< Periodic interrupt timer channel 3 */ + PDB0_IRQn = 52, /**< Programmable delay block */ + USB0_IRQn = 53, /**< USB OTG interrupt */ + USBDCD_IRQn = 54, /**< USB charger detect */ + Reserved71_IRQn = 55, /**< Reserved interrupt */ + DAC0_IRQn = 56, /**< Digital-to-analog converter 0 */ + MCG_IRQn = 57, /**< Multipurpose clock generator */ + LPTimer_IRQn = 58, /**< Low power timer interrupt */ + PORTA_IRQn = 59, /**< Port A pin detect interrupt */ + PORTB_IRQn = 60, /**< Port B pin detect interrupt */ + PORTC_IRQn = 61, /**< Port C pin detect interrupt */ + PORTD_IRQn = 62, /**< Port D pin detect interrupt */ + PORTE_IRQn = 63, /**< Port E pin detect interrupt */ + SWI_IRQn = 64 /**< Software interrupt */ +} IRQn_Type; + +/*! + * @} + */ /* end of group Interrupt_vector_numbers */ + + +/* ---------------------------------------------------------------------------- + -- Cortex M4 Core Configuration + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Cortex_Core_Configuration Cortex M4 Core Configuration + * @{ + */ + +#define __MPU_PRESENT 0 /**< Defines if an MPU is present or not */ +#define __NVIC_PRIO_BITS 4 /**< Number of priority bits implemented in the NVIC */ +#define __Vendor_SysTickConfig 0 /**< Vendor specific implementation of SysTickConfig is defined */ +#define __FPU_PRESENT 0 /**< Defines if an FPU is present or not */ + +#include "core_cm4.h" /* Core Peripheral Access Layer */ +//#include "system_MK22D5.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))<CGH1) +#define CMT_CGL1_REG(base) ((base)->CGL1) +#define CMT_CGH2_REG(base) ((base)->CGH2) +#define CMT_CGL2_REG(base) ((base)->CGL2) +#define CMT_OC_REG(base) ((base)->OC) +#define CMT_MSC_REG(base) ((base)->MSC) +#define CMT_CMD1_REG(base) ((base)->CMD1) +#define CMT_CMD2_REG(base) ((base)->CMD2) +#define CMT_CMD3_REG(base) ((base)->CMD3) +#define CMT_CMD4_REG(base) ((base)->CMD4) +#define CMT_PPS_REG(base) ((base)->PPS) +#define CMT_DMA_REG(base) ((base)->DMA) + +/*! + * @} + */ /* end of group CMT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- CMT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup CMT_Register_Masks CMT Register Masks + * @{ + */ + +/* CGH1 Bit Fields */ +#define CMT_CGH1_PH_MASK 0xFFu +#define CMT_CGH1_PH_SHIFT 0 +#define CMT_CGH1_PH(x) (((uint8_t)(((uint8_t)(x))<ACCESS16BIT.DATAL) +#define CRC_DATAH_REG(base) ((base)->ACCESS16BIT.DATAH) +#define CRC_DATA_REG(base) ((base)->DATA) +#define CRC_DATALL_REG(base) ((base)->ACCESS8BIT.DATALL) +#define CRC_DATALU_REG(base) ((base)->ACCESS8BIT.DATALU) +#define CRC_DATAHL_REG(base) ((base)->ACCESS8BIT.DATAHL) +#define CRC_DATAHU_REG(base) ((base)->ACCESS8BIT.DATAHU) +#define CRC_GPOLYL_REG(base) ((base)->GPOLY_ACCESS16BIT.GPOLYL) +#define CRC_GPOLYH_REG(base) ((base)->GPOLY_ACCESS16BIT.GPOLYH) +#define CRC_GPOLY_REG(base) ((base)->GPOLY) +#define CRC_GPOLYLL_REG(base) ((base)->GPOLY_ACCESS8BIT.GPOLYLL) +#define CRC_GPOLYLU_REG(base) ((base)->GPOLY_ACCESS8BIT.GPOLYLU) +#define CRC_GPOLYHL_REG(base) ((base)->GPOLY_ACCESS8BIT.GPOLYHL) +#define CRC_GPOLYHU_REG(base) ((base)->GPOLY_ACCESS8BIT.GPOLYHU) +#define CRC_CTRL_REG(base) ((base)->CTRL) +#define CRC_CTRLHU_REG(base) ((base)->CTRL_ACCESS8BIT.CTRLHU) + +/*! + * @} + */ /* end of group CRC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- CRC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup CRC_Register_Masks CRC Register Masks + * @{ + */ + +/* DATAL Bit Fields */ +#define CRC_DATAL_DATAL_MASK 0xFFFFu +#define CRC_DATAL_DATAL_SHIFT 0 +#define CRC_DATAL_DATAL(x) (((uint16_t)(((uint16_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))<CR) +#define DMA_ES_REG(base) ((base)->ES) +#define DMA_ERQ_REG(base) ((base)->ERQ) +#define DMA_EEI_REG(base) ((base)->EEI) +#define DMA_CEEI_REG(base) ((base)->CEEI) +#define DMA_SEEI_REG(base) ((base)->SEEI) +#define DMA_CERQ_REG(base) ((base)->CERQ) +#define DMA_SERQ_REG(base) ((base)->SERQ) +#define DMA_CDNE_REG(base) ((base)->CDNE) +#define DMA_SSRT_REG(base) ((base)->SSRT) +#define DMA_CERR_REG(base) ((base)->CERR) +#define DMA_CINT_REG(base) ((base)->CINT) +#define DMA_INT_REG(base) ((base)->INT) +#define DMA_ERR_REG(base) ((base)->ERR) +#define DMA_HRS_REG(base) ((base)->HRS) +#define DMA_DCHPRI3_REG(base) ((base)->DCHPRI3) +#define DMA_DCHPRI2_REG(base) ((base)->DCHPRI2) +#define DMA_DCHPRI1_REG(base) ((base)->DCHPRI1) +#define DMA_DCHPRI0_REG(base) ((base)->DCHPRI0) +#define DMA_DCHPRI7_REG(base) ((base)->DCHPRI7) +#define DMA_DCHPRI6_REG(base) ((base)->DCHPRI6) +#define DMA_DCHPRI5_REG(base) ((base)->DCHPRI5) +#define DMA_DCHPRI4_REG(base) ((base)->DCHPRI4) +#define DMA_DCHPRI11_REG(base) ((base)->DCHPRI11) +#define DMA_DCHPRI10_REG(base) ((base)->DCHPRI10) +#define DMA_DCHPRI9_REG(base) ((base)->DCHPRI9) +#define DMA_DCHPRI8_REG(base) ((base)->DCHPRI8) +#define DMA_DCHPRI15_REG(base) ((base)->DCHPRI15) +#define DMA_DCHPRI14_REG(base) ((base)->DCHPRI14) +#define DMA_DCHPRI13_REG(base) ((base)->DCHPRI13) +#define DMA_DCHPRI12_REG(base) ((base)->DCHPRI12) +#define DMA_SADDR_REG(base,index) ((base)->TCD[index].SADDR) +#define DMA_SOFF_REG(base,index) ((base)->TCD[index].SOFF) +#define DMA_ATTR_REG(base,index) ((base)->TCD[index].ATTR) +#define DMA_NBYTES_MLNO_REG(base,index) ((base)->TCD[index].NBYTES_MLNO) +#define DMA_NBYTES_MLOFFNO_REG(base,index) ((base)->TCD[index].NBYTES_MLOFFNO) +#define DMA_NBYTES_MLOFFYES_REG(base,index) ((base)->TCD[index].NBYTES_MLOFFYES) +#define DMA_SLAST_REG(base,index) ((base)->TCD[index].SLAST) +#define DMA_DADDR_REG(base,index) ((base)->TCD[index].DADDR) +#define DMA_DOFF_REG(base,index) ((base)->TCD[index].DOFF) +#define DMA_CITER_ELINKNO_REG(base,index) ((base)->TCD[index].CITER_ELINKNO) +#define DMA_CITER_ELINKYES_REG(base,index) ((base)->TCD[index].CITER_ELINKYES) +#define DMA_DLAST_SGA_REG(base,index) ((base)->TCD[index].DLAST_SGA) +#define DMA_CSR_REG(base,index) ((base)->TCD[index].CSR) +#define DMA_BITER_ELINKNO_REG(base,index) ((base)->TCD[index].BITER_ELINKNO) +#define DMA_BITER_ELINKYES_REG(base,index) ((base)->TCD[index].BITER_ELINKYES) + +/*! + * @} + */ /* end of group DMA_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- DMA Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup DMA_Register_Masks DMA Register Masks + * @{ + */ + +/* CR Bit Fields */ +#define DMA_CR_EDBG_MASK 0x2u +#define DMA_CR_EDBG_SHIFT 1 +#define DMA_CR_ERCA_MASK 0x4u +#define DMA_CR_ERCA_SHIFT 2 +#define DMA_CR_HOE_MASK 0x10u +#define DMA_CR_HOE_SHIFT 4 +#define DMA_CR_HALT_MASK 0x20u +#define DMA_CR_HALT_SHIFT 5 +#define DMA_CR_CLM_MASK 0x40u +#define DMA_CR_CLM_SHIFT 6 +#define DMA_CR_EMLM_MASK 0x80u +#define DMA_CR_EMLM_SHIFT 7 +#define DMA_CR_ECX_MASK 0x10000u +#define DMA_CR_ECX_SHIFT 16 +#define DMA_CR_CX_MASK 0x20000u +#define DMA_CR_CX_SHIFT 17 +/* ES Bit Fields */ +#define DMA_ES_DBE_MASK 0x1u +#define DMA_ES_DBE_SHIFT 0 +#define DMA_ES_SBE_MASK 0x2u +#define DMA_ES_SBE_SHIFT 1 +#define DMA_ES_SGE_MASK 0x4u +#define DMA_ES_SGE_SHIFT 2 +#define DMA_ES_NCE_MASK 0x8u +#define DMA_ES_NCE_SHIFT 3 +#define DMA_ES_DOE_MASK 0x10u +#define DMA_ES_DOE_SHIFT 4 +#define DMA_ES_DAE_MASK 0x20u +#define DMA_ES_DAE_SHIFT 5 +#define DMA_ES_SOE_MASK 0x40u +#define DMA_ES_SOE_SHIFT 6 +#define DMA_ES_SAE_MASK 0x80u +#define DMA_ES_SAE_SHIFT 7 +#define DMA_ES_ERRCHN_MASK 0xF00u +#define DMA_ES_ERRCHN_SHIFT 8 +#define DMA_ES_ERRCHN(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))<CTRL) +#define EWM_SERV_REG(base) ((base)->SERV) +#define EWM_CMPL_REG(base) ((base)->CMPL) +#define EWM_CMPH_REG(base) ((base)->CMPH) + +/*! + * @} + */ /* end of group EWM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- EWM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup EWM_Register_Masks EWM Register Masks + * @{ + */ + +/* CTRL Bit Fields */ +#define EWM_CTRL_EWMEN_MASK 0x1u +#define EWM_CTRL_EWMEN_SHIFT 0 +#define EWM_CTRL_ASSIN_MASK 0x2u +#define EWM_CTRL_ASSIN_SHIFT 1 +#define EWM_CTRL_INEN_MASK 0x4u +#define EWM_CTRL_INEN_SHIFT 2 +#define EWM_CTRL_INTEN_MASK 0x8u +#define EWM_CTRL_INTEN_SHIFT 3 +/* SERV Bit Fields */ +#define EWM_SERV_SERVICE_MASK 0xFFu +#define EWM_SERV_SERVICE_SHIFT 0 +#define EWM_SERV_SERVICE(x) (((uint8_t)(((uint8_t)(x))<PFAPR) +#define FMC_PFB0CR_REG(base) ((base)->PFB0CR) +#define FMC_PFB1CR_REG(base) ((base)->PFB1CR) +#define FMC_TAGVD_REG(base,index,index2) ((base)->TAGVD[index][index2]) +#define FMC_DATA_U_REG(base,index,index2) ((base)->SET[index][index2].DATA_U) +#define FMC_DATA_L_REG(base,index,index2) ((base)->SET[index][index2].DATA_L) + +/*! + * @} + */ /* end of group FMC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FMC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FMC_Register_Masks FMC Register Masks + * @{ + */ + +/* PFAPR Bit Fields */ +#define FMC_PFAPR_M0AP_MASK 0x3u +#define FMC_PFAPR_M0AP_SHIFT 0 +#define FMC_PFAPR_M0AP(x) (((uint32_t)(((uint32_t)(x))<FSTAT) +#define FTFL_FCNFG_REG(base) ((base)->FCNFG) +#define FTFL_FSEC_REG(base) ((base)->FSEC) +#define FTFL_FOPT_REG(base) ((base)->FOPT) +#define FTFL_FCCOB3_REG(base) ((base)->FCCOB3) +#define FTFL_FCCOB2_REG(base) ((base)->FCCOB2) +#define FTFL_FCCOB1_REG(base) ((base)->FCCOB1) +#define FTFL_FCCOB0_REG(base) ((base)->FCCOB0) +#define FTFL_FCCOB7_REG(base) ((base)->FCCOB7) +#define FTFL_FCCOB6_REG(base) ((base)->FCCOB6) +#define FTFL_FCCOB5_REG(base) ((base)->FCCOB5) +#define FTFL_FCCOB4_REG(base) ((base)->FCCOB4) +#define FTFL_FCCOBB_REG(base) ((base)->FCCOBB) +#define FTFL_FCCOBA_REG(base) ((base)->FCCOBA) +#define FTFL_FCCOB9_REG(base) ((base)->FCCOB9) +#define FTFL_FCCOB8_REG(base) ((base)->FCCOB8) +#define FTFL_FPROT3_REG(base) ((base)->FPROT3) +#define FTFL_FPROT2_REG(base) ((base)->FPROT2) +#define FTFL_FPROT1_REG(base) ((base)->FPROT1) +#define FTFL_FPROT0_REG(base) ((base)->FPROT0) +#define FTFL_FEPROT_REG(base) ((base)->FEPROT) +#define FTFL_FDPROT_REG(base) ((base)->FDPROT) + +/*! + * @} + */ /* end of group FTFL_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FTFL Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FTFL_Register_Masks FTFL Register Masks + * @{ + */ + +/* FSTAT Bit Fields */ +#define FTFL_FSTAT_MGSTAT0_MASK 0x1u +#define FTFL_FSTAT_MGSTAT0_SHIFT 0 +#define FTFL_FSTAT_FPVIOL_MASK 0x10u +#define FTFL_FSTAT_FPVIOL_SHIFT 4 +#define FTFL_FSTAT_ACCERR_MASK 0x20u +#define FTFL_FSTAT_ACCERR_SHIFT 5 +#define FTFL_FSTAT_RDCOLERR_MASK 0x40u +#define FTFL_FSTAT_RDCOLERR_SHIFT 6 +#define FTFL_FSTAT_CCIF_MASK 0x80u +#define FTFL_FSTAT_CCIF_SHIFT 7 +/* FCNFG Bit Fields */ +#define FTFL_FCNFG_EEERDY_MASK 0x1u +#define FTFL_FCNFG_EEERDY_SHIFT 0 +#define FTFL_FCNFG_RAMRDY_MASK 0x2u +#define FTFL_FCNFG_RAMRDY_SHIFT 1 +#define FTFL_FCNFG_PFLSH_MASK 0x4u +#define FTFL_FCNFG_PFLSH_SHIFT 2 +#define FTFL_FCNFG_SWAP_MASK 0x8u +#define FTFL_FCNFG_SWAP_SHIFT 3 +#define FTFL_FCNFG_ERSSUSP_MASK 0x10u +#define FTFL_FCNFG_ERSSUSP_SHIFT 4 +#define FTFL_FCNFG_ERSAREQ_MASK 0x20u +#define FTFL_FCNFG_ERSAREQ_SHIFT 5 +#define FTFL_FCNFG_RDCOLLIE_MASK 0x40u +#define FTFL_FCNFG_RDCOLLIE_SHIFT 6 +#define FTFL_FCNFG_CCIE_MASK 0x80u +#define FTFL_FCNFG_CCIE_SHIFT 7 +/* FSEC Bit Fields */ +#define FTFL_FSEC_SEC_MASK 0x3u +#define FTFL_FSEC_SEC_SHIFT 0 +#define FTFL_FSEC_SEC(x) (((uint8_t)(((uint8_t)(x))<SC) +#define FTM_CNT_REG(base) ((base)->CNT) +#define FTM_MOD_REG(base) ((base)->MOD) +#define FTM_CnSC_REG(base,index) ((base)->CONTROLS[index].CnSC) +#define FTM_CnV_REG(base,index) ((base)->CONTROLS[index].CnV) +#define FTM_CNTIN_REG(base) ((base)->CNTIN) +#define FTM_STATUS_REG(base) ((base)->STATUS) +#define FTM_MODE_REG(base) ((base)->MODE) +#define FTM_SYNC_REG(base) ((base)->SYNC) +#define FTM_OUTINIT_REG(base) ((base)->OUTINIT) +#define FTM_OUTMASK_REG(base) ((base)->OUTMASK) +#define FTM_COMBINE_REG(base) ((base)->COMBINE) +#define FTM_DEADTIME_REG(base) ((base)->DEADTIME) +#define FTM_EXTTRIG_REG(base) ((base)->EXTTRIG) +#define FTM_POL_REG(base) ((base)->POL) +#define FTM_FMS_REG(base) ((base)->FMS) +#define FTM_FILTER_REG(base) ((base)->FILTER) +#define FTM_FLTCTRL_REG(base) ((base)->FLTCTRL) +#define FTM_QDCTRL_REG(base) ((base)->QDCTRL) +#define FTM_CONF_REG(base) ((base)->CONF) +#define FTM_FLTPOL_REG(base) ((base)->FLTPOL) +#define FTM_SYNCONF_REG(base) ((base)->SYNCONF) +#define FTM_INVCTRL_REG(base) ((base)->INVCTRL) +#define FTM_SWOCTRL_REG(base) ((base)->SWOCTRL) +#define FTM_PWMLOAD_REG(base) ((base)->PWMLOAD) + +/*! + * @} + */ /* end of group FTM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FTM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FTM_Register_Masks FTM Register Masks + * @{ + */ + +/* SC Bit Fields */ +#define FTM_SC_PS_MASK 0x7u +#define FTM_SC_PS_SHIFT 0 +#define FTM_SC_PS(x) (((uint32_t)(((uint32_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))<TCSR) +#define I2S_TCR1_REG(base) ((base)->TCR1) +#define I2S_TCR2_REG(base) ((base)->TCR2) +#define I2S_TCR3_REG(base) ((base)->TCR3) +#define I2S_TCR4_REG(base) ((base)->TCR4) +#define I2S_TCR5_REG(base) ((base)->TCR5) +#define I2S_TDR_REG(base,index) ((base)->TDR[index]) +#define I2S_TFR_REG(base,index) ((base)->TFR[index]) +#define I2S_TMR_REG(base) ((base)->TMR) +#define I2S_RCSR_REG(base) ((base)->RCSR) +#define I2S_RCR1_REG(base) ((base)->RCR1) +#define I2S_RCR2_REG(base) ((base)->RCR2) +#define I2S_RCR3_REG(base) ((base)->RCR3) +#define I2S_RCR4_REG(base) ((base)->RCR4) +#define I2S_RCR5_REG(base) ((base)->RCR5) +#define I2S_RDR_REG(base,index) ((base)->RDR[index]) +#define I2S_RFR_REG(base,index) ((base)->RFR[index]) +#define I2S_RMR_REG(base) ((base)->RMR) +#define I2S_MCR_REG(base) ((base)->MCR) +#define I2S_MDR_REG(base) ((base)->MDR) + +/*! + * @} + */ /* end of group I2S_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- I2S Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup I2S_Register_Masks I2S Register Masks + * @{ + */ + +/* TCSR Bit Fields */ +#define I2S_TCSR_FRDE_MASK 0x1u +#define I2S_TCSR_FRDE_SHIFT 0 +#define I2S_TCSR_FWDE_MASK 0x2u +#define I2S_TCSR_FWDE_SHIFT 1 +#define I2S_TCSR_FRIE_MASK 0x100u +#define I2S_TCSR_FRIE_SHIFT 8 +#define I2S_TCSR_FWIE_MASK 0x200u +#define I2S_TCSR_FWIE_SHIFT 9 +#define I2S_TCSR_FEIE_MASK 0x400u +#define I2S_TCSR_FEIE_SHIFT 10 +#define I2S_TCSR_SEIE_MASK 0x800u +#define I2S_TCSR_SEIE_SHIFT 11 +#define I2S_TCSR_WSIE_MASK 0x1000u +#define I2S_TCSR_WSIE_SHIFT 12 +#define I2S_TCSR_FRF_MASK 0x10000u +#define I2S_TCSR_FRF_SHIFT 16 +#define I2S_TCSR_FWF_MASK 0x20000u +#define I2S_TCSR_FWF_SHIFT 17 +#define I2S_TCSR_FEF_MASK 0x40000u +#define I2S_TCSR_FEF_SHIFT 18 +#define I2S_TCSR_SEF_MASK 0x80000u +#define I2S_TCSR_SEF_SHIFT 19 +#define I2S_TCSR_WSF_MASK 0x100000u +#define I2S_TCSR_WSF_SHIFT 20 +#define I2S_TCSR_SR_MASK 0x1000000u +#define I2S_TCSR_SR_SHIFT 24 +#define I2S_TCSR_FR_MASK 0x2000000u +#define I2S_TCSR_FR_SHIFT 25 +#define I2S_TCSR_BCE_MASK 0x10000000u +#define I2S_TCSR_BCE_SHIFT 28 +#define I2S_TCSR_DBGE_MASK 0x20000000u +#define I2S_TCSR_DBGE_SHIFT 29 +#define I2S_TCSR_STOPE_MASK 0x40000000u +#define I2S_TCSR_STOPE_SHIFT 30 +#define I2S_TCSR_TE_MASK 0x80000000u +#define I2S_TCSR_TE_SHIFT 31 +/* TCR1 Bit Fields */ +#define I2S_TCR1_TFW_MASK 0x7u +#define I2S_TCR1_TFW_SHIFT 0 +#define I2S_TCR1_TFW(x) (((uint32_t)(((uint32_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) +#define LLWU_RST_REG(base) ((base)->RST) + +/*! + * @} + */ /* 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_C7_REG(base) ((base)->C7) +#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) + +/*! + * @} + */ /* 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))<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) +#define NV_FEPROT_REG(base) ((base)->FEPROT) +#define NV_FDPROT_REG(base) ((base)->FDPROT) + +/*! + * @} + */ /* 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 OSC base address */ +#define OSC_BASE (0x40065000u) +/** Peripheral OSC base pointer */ +#define OSC ((OSC_Type *)OSC_BASE) +#define OSC_BASE_PTR (OSC) +/** Array initializer of OSC peripheral base addresses */ +#define OSC_BASE_ADDRS { OSC_BASE } +/** Array initializer of OSC peripheral base pointers */ +#define OSC_BASE_PTRS { OSC } + +/* ---------------------------------------------------------------------------- + -- OSC - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup OSC_Register_Accessor_Macros OSC - Register accessor macros + * @{ + */ + + +/* OSC - Register instance definitions */ +/* OSC */ +#define OSC_CR OSC_CR_REG(OSC) + +/*! + * @} + */ /* end of group OSC_Register_Accessor_Macros */ + + +/*! + * @} + */ /* end of group OSC_Peripheral_Access_Layer */ + + +/* ---------------------------------------------------------------------------- + -- PDB Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PDB_Peripheral_Access_Layer PDB Peripheral Access Layer + * @{ + */ + +/** PDB - Register Layout Typedef */ +typedef struct { + __IO uint32_t SC; /**< Status and Control Register, offset: 0x0 */ + __IO uint32_t MOD; /**< Modulus Register, offset: 0x4 */ + __I uint32_t CNT; /**< Counter Register, offset: 0x8 */ + __IO uint32_t IDLY; /**< Interrupt Delay Register, offset: 0xC */ + struct { /* offset: 0x10, array step: 0x28 */ + __IO uint32_t C1; /**< Channel n Control Register 1, array offset: 0x10, array step: 0x28 */ + __IO uint32_t S; /**< Channel n Status Register, array offset: 0x14, array step: 0x28 */ + __IO uint32_t DLY[2]; /**< Channel n Delay 0 Register..Channel n Delay 1 Register, array offset: 0x18, array step: index*0x28, index2*0x4 */ + uint8_t RESERVED_0[24]; + } CH[2]; + uint8_t RESERVED_0[240]; + struct { /* offset: 0x150, array step: 0x8 */ + __IO uint32_t INTC; /**< DAC Interval Trigger n Control Register, array offset: 0x150, array step: 0x8 */ + __IO uint32_t INT; /**< DAC Interval n Register, array offset: 0x154, array step: 0x8 */ + } DAC[1]; + uint8_t RESERVED_1[56]; + __IO uint32_t POEN; /**< Pulse-Out n Enable Register, offset: 0x190 */ + __IO uint32_t PODLY[2]; /**< Pulse-Out n Delay Register, array offset: 0x194, array step: 0x4 */ +} PDB_Type, *PDB_MemMapPtr; + +/* ---------------------------------------------------------------------------- + -- PDB - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PDB_Register_Accessor_Macros PDB - Register accessor macros + * @{ + */ + + +/* PDB - Register accessors */ +#define PDB_SC_REG(base) ((base)->SC) +#define PDB_MOD_REG(base) ((base)->MOD) +#define PDB_CNT_REG(base) ((base)->CNT) +#define PDB_IDLY_REG(base) ((base)->IDLY) +#define PDB_C1_REG(base,index) ((base)->CH[index].C1) +#define PDB_S_REG(base,index) ((base)->CH[index].S) +#define PDB_DLY_REG(base,index,index2) ((base)->CH[index].DLY[index2]) +#define PDB_INTC_REG(base,index) ((base)->DAC[index].INTC) +#define PDB_INT_REG(base,index) ((base)->DAC[index].INT) +#define PDB_POEN_REG(base) ((base)->POEN) +#define PDB_PODLY_REG(base,index) ((base)->PODLY[index]) + +/*! + * @} + */ /* end of group PDB_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PDB Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PDB_Register_Masks PDB Register Masks + * @{ + */ + +/* SC Bit Fields */ +#define PDB_SC_LDOK_MASK 0x1u +#define PDB_SC_LDOK_SHIFT 0 +#define PDB_SC_CONT_MASK 0x2u +#define PDB_SC_CONT_SHIFT 1 +#define PDB_SC_MULT_MASK 0xCu +#define PDB_SC_MULT_SHIFT 2 +#define PDB_SC_MULT(x) (((uint32_t)(((uint32_t)(x))<MCR) +#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 +/* LDVAL Bit Fields */ +#define PIT_LDVAL_TSV_MASK 0xFFFFFFFFu +#define PIT_LDVAL_TSV_SHIFT 0 +#define PIT_LDVAL_TSV(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) +#define PORT_DFER_REG(base) ((base)->DFER) +#define PORT_DFCR_REG(base) ((base)->DFCR) +#define PORT_DFWR_REG(base) ((base)->DFWR) + +/*! + * @} + */ /* 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_ODE_MASK 0x20u +#define PORT_PCR_ODE_SHIFT 5 +#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) +#define RCM_MR_REG(base) ((base)->MR) + +/*! + * @} + */ /* 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_JTAG_MASK 0x1u +#define RCM_SRS1_JTAG_SHIFT 0 +#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_EZPT_MASK 0x10u +#define RCM_SRS1_EZPT_SHIFT 4 +#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))<REG[index]) + +/*! + * @} + */ /* end of group RFSYS_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- RFSYS Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup RFSYS_Register_Masks RFSYS Register Masks + * @{ + */ + +/* REG Bit Fields */ +#define RFSYS_REG_LL_MASK 0xFFu +#define RFSYS_REG_LL_SHIFT 0 +#define RFSYS_REG_LL(x) (((uint32_t)(((uint32_t)(x))<REG[index]) + +/*! + * @} + */ /* end of group RFVBAT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- RFVBAT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup RFVBAT_Register_Masks RFVBAT Register Masks + * @{ + */ + +/* REG Bit Fields */ +#define RFVBAT_REG_LL_MASK 0xFFu +#define RFVBAT_REG_LL_SHIFT 0 +#define RFVBAT_REG_LL(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) +#define RTC_TTSR_REG(base) ((base)->TTSR) +#define RTC_MER_REG(base) ((base)->MER) +#define RTC_MCLR_REG(base) ((base)->MCLR) +#define RTC_MCHR_REG(base) ((base)->MCHR) +#define RTC_WAR_REG(base) ((base)->WAR) +#define RTC_RAR_REG(base) ((base)->RAR) + +/*! + * @} + */ /* 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_SOPT1CFG_REG(base) ((base)->SOPT1CFG) +#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_CLKDIV2_REG(base) ((base)->CLKDIV2) +#define SIM_FCFG1_REG(base) ((base)->FCFG1) +#define SIM_FCFG2_REG(base) ((base)->FCFG2) +#define SIM_UIDH_REG(base) ((base)->UIDH) +#define SIM_UIDMH_REG(base) ((base)->UIDMH) +#define SIM_UIDML_REG(base) ((base)->UIDML) +#define SIM_UIDL_REG(base) ((base)->UIDL) + +/*! + * @} + */ /* end of group SIM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SIM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SIM_Register_Masks SIM Register Masks + * @{ + */ + +/* SOPT1 Bit Fields */ +#define SIM_SOPT1_RAMSIZE_MASK 0xF000u +#define SIM_SOPT1_RAMSIZE_SHIFT 12 +#define SIM_SOPT1_RAMSIZE(x) (((uint32_t)(((uint32_t)(x))<PMPROT) +#define SMC_PMCTRL_REG(base) ((base)->PMCTRL) +#define SMC_VLLSCTRL_REG(base) ((base)->VLLSCTRL) +#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))<MCR) +#define SPI_TCR_REG(base) ((base)->TCR) +#define SPI_CTAR_REG(base,index2) ((base)->CTAR[index2]) +#define SPI_CTAR_SLAVE_REG(base,index2) ((base)->CTAR_SLAVE[index2]) +#define SPI_SR_REG(base) ((base)->SR) +#define SPI_RSER_REG(base) ((base)->RSER) +#define SPI_PUSHR_REG(base) ((base)->PUSHR) +#define SPI_PUSHR_SLAVE_REG(base) ((base)->PUSHR_SLAVE) +#define SPI_POPR_REG(base) ((base)->POPR) +#define SPI_TXFR0_REG(base) ((base)->TXFR0) +#define SPI_TXFR1_REG(base) ((base)->TXFR1) +#define SPI_TXFR2_REG(base) ((base)->TXFR2) +#define SPI_TXFR3_REG(base) ((base)->TXFR3) +#define SPI_RXFR0_REG(base) ((base)->RXFR0) +#define SPI_RXFR1_REG(base) ((base)->RXFR1) +#define SPI_RXFR2_REG(base) ((base)->RXFR2) +#define SPI_RXFR3_REG(base) ((base)->RXFR3) + +/*! + * @} + */ /* end of group SPI_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SPI Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SPI_Register_Masks SPI Register Masks + * @{ + */ + +/* MCR Bit Fields */ +#define SPI_MCR_HALT_MASK 0x1u +#define SPI_MCR_HALT_SHIFT 0 +#define SPI_MCR_SMPL_PT_MASK 0x300u +#define SPI_MCR_SMPL_PT_SHIFT 8 +#define SPI_MCR_SMPL_PT(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_MA1_REG(base) ((base)->MA1) +#define UART_MA2_REG(base) ((base)->MA2) +#define UART_C4_REG(base) ((base)->C4) +#define UART_C5_REG(base) ((base)->C5) +#define UART_ED_REG(base) ((base)->ED) +#define UART_MODEM_REG(base) ((base)->MODEM) +#define UART_IR_REG(base) ((base)->IR) +#define UART_PFIFO_REG(base) ((base)->PFIFO) +#define UART_CFIFO_REG(base) ((base)->CFIFO) +#define UART_SFIFO_REG(base) ((base)->SFIFO) +#define UART_TWFIFO_REG(base) ((base)->TWFIFO) +#define UART_TCFIFO_REG(base) ((base)->TCFIFO) +#define UART_RWFIFO_REG(base) ((base)->RWFIFO) +#define UART_RCFIFO_REG(base) ((base)->RCFIFO) +#define UART_C7816_REG(base) ((base)->C7816) +#define UART_IE7816_REG(base) ((base)->IE7816) +#define UART_IS7816_REG(base) ((base)->IS7816) +#define UART_WP7816T0_REG(base) ((base)->WP7816T0) +#define UART_WP7816T1_REG(base) ((base)->WP7816T1) +#define UART_WN7816_REG(base) ((base)->WN7816) +#define UART_WF7816_REG(base) ((base)->WF7816) +#define UART_ET7816_REG(base) ((base)->ET7816) +#define UART_TL7816_REG(base) ((base)->TL7816) + +/*! + * @} + */ /* 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))<PERID) +#define USB_IDCOMP_REG(base) ((base)->IDCOMP) +#define USB_REV_REG(base) ((base)->REV) +#define USB_ADDINFO_REG(base) ((base)->ADDINFO) +#define USB_OTGISTAT_REG(base) ((base)->OTGISTAT) +#define USB_OTGICR_REG(base) ((base)->OTGICR) +#define USB_OTGSTAT_REG(base) ((base)->OTGSTAT) +#define USB_OTGCTL_REG(base) ((base)->OTGCTL) +#define USB_ISTAT_REG(base) ((base)->ISTAT) +#define USB_INTEN_REG(base) ((base)->INTEN) +#define USB_ERRSTAT_REG(base) ((base)->ERRSTAT) +#define USB_ERREN_REG(base) ((base)->ERREN) +#define USB_STAT_REG(base) ((base)->STAT) +#define USB_CTL_REG(base) ((base)->CTL) +#define USB_ADDR_REG(base) ((base)->ADDR) +#define USB_BDTPAGE1_REG(base) ((base)->BDTPAGE1) +#define USB_FRMNUML_REG(base) ((base)->FRMNUML) +#define USB_FRMNUMH_REG(base) ((base)->FRMNUMH) +#define USB_TOKEN_REG(base) ((base)->TOKEN) +#define USB_SOFTHLD_REG(base) ((base)->SOFTHLD) +#define USB_BDTPAGE2_REG(base) ((base)->BDTPAGE2) +#define USB_BDTPAGE3_REG(base) ((base)->BDTPAGE3) +#define USB_ENDPT_REG(base,index) ((base)->ENDPOINT[index].ENDPT) +#define USB_USBCTRL_REG(base) ((base)->USBCTRL) +#define USB_OBSERVE_REG(base) ((base)->OBSERVE) +#define USB_CONTROL_REG(base) ((base)->CONTROL) +#define USB_USBTRC0_REG(base) ((base)->USBTRC0) +#define USB_USBFRMADJUST_REG(base) ((base)->USBFRMADJUST) + +/*! + * @} + */ /* end of group USB_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- USB Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup USB_Register_Masks USB Register Masks + * @{ + */ + +/* PERID Bit Fields */ +#define USB_PERID_ID_MASK 0x3Fu +#define USB_PERID_ID_SHIFT 0 +#define USB_PERID_ID(x) (((uint8_t)(((uint8_t)(x))<CONTROL) +#define USBDCD_CLOCK_REG(base) ((base)->CLOCK) +#define USBDCD_STATUS_REG(base) ((base)->STATUS) +#define USBDCD_TIMER0_REG(base) ((base)->TIMER0) +#define USBDCD_TIMER1_REG(base) ((base)->TIMER1) +#define USBDCD_TIMER2_REG(base) ((base)->TIMER2) + +/*! + * @} + */ /* end of group USBDCD_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- USBDCD Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup USBDCD_Register_Masks USBDCD Register Masks + * @{ + */ + +/* CONTROL Bit Fields */ +#define USBDCD_CONTROL_IACK_MASK 0x1u +#define USBDCD_CONTROL_IACK_SHIFT 0 +#define USBDCD_CONTROL_IF_MASK 0x100u +#define USBDCD_CONTROL_IF_SHIFT 8 +#define USBDCD_CONTROL_IE_MASK 0x10000u +#define USBDCD_CONTROL_IE_SHIFT 16 +#define USBDCD_CONTROL_START_MASK 0x1000000u +#define USBDCD_CONTROL_START_SHIFT 24 +#define USBDCD_CONTROL_SR_MASK 0x2000000u +#define USBDCD_CONTROL_SR_SHIFT 25 +/* CLOCK Bit Fields */ +#define USBDCD_CLOCK_CLOCK_UNIT_MASK 0x1u +#define USBDCD_CLOCK_CLOCK_UNIT_SHIFT 0 +#define USBDCD_CLOCK_CLOCK_SPEED_MASK 0xFFCu +#define USBDCD_CLOCK_CLOCK_SPEED_SHIFT 2 +#define USBDCD_CLOCK_CLOCK_SPEED(x) (((uint32_t)(((uint32_t)(x))<TRM) +#define VREF_SC_REG(base) ((base)->SC) + +/*! + * @} + */ /* end of group VREF_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- VREF Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup VREF_Register_Masks VREF Register Masks + * @{ + */ + +/* TRM Bit Fields */ +#define VREF_TRM_TRIM_MASK 0x3Fu +#define VREF_TRM_TRIM_SHIFT 0 +#define VREF_TRM_TRIM(x) (((uint8_t)(((uint8_t)(x))<STCTRLH) +#define WDOG_STCTRLL_REG(base) ((base)->STCTRLL) +#define WDOG_TOVALH_REG(base) ((base)->TOVALH) +#define WDOG_TOVALL_REG(base) ((base)->TOVALL) +#define WDOG_WINH_REG(base) ((base)->WINH) +#define WDOG_WINL_REG(base) ((base)->WINL) +#define WDOG_REFRESH_REG(base) ((base)->REFRESH) +#define WDOG_UNLOCK_REG(base) ((base)->UNLOCK) +#define WDOG_TMROUTH_REG(base) ((base)->TMROUTH) +#define WDOG_TMROUTL_REG(base) ((base)->TMROUTL) +#define WDOG_RSTCNT_REG(base) ((base)->RSTCNT) +#define WDOG_PRESC_REG(base) ((base)->PRESC) + +/*! + * @} + */ /* end of group WDOG_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- WDOG Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup WDOG_Register_Masks WDOG Register Masks + * @{ + */ + +/* STCTRLH Bit Fields */ +#define WDOG_STCTRLH_WDOGEN_MASK 0x1u +#define WDOG_STCTRLH_WDOGEN_SHIFT 0 +#define WDOG_STCTRLH_CLKSRC_MASK 0x2u +#define WDOG_STCTRLH_CLKSRC_SHIFT 1 +#define WDOG_STCTRLH_IRQRSTEN_MASK 0x4u +#define WDOG_STCTRLH_IRQRSTEN_SHIFT 2 +#define WDOG_STCTRLH_WINEN_MASK 0x8u +#define WDOG_STCTRLH_WINEN_SHIFT 3 +#define WDOG_STCTRLH_ALLOWUPDATE_MASK 0x10u +#define WDOG_STCTRLH_ALLOWUPDATE_SHIFT 4 +#define WDOG_STCTRLH_DBGEN_MASK 0x20u +#define WDOG_STCTRLH_DBGEN_SHIFT 5 +#define WDOG_STCTRLH_STOPEN_MASK 0x40u +#define WDOG_STCTRLH_STOPEN_SHIFT 6 +#define WDOG_STCTRLH_WAITEN_MASK 0x80u +#define WDOG_STCTRLH_WAITEN_SHIFT 7 +#define WDOG_STCTRLH_TESTWDOG_MASK 0x400u +#define WDOG_STCTRLH_TESTWDOG_SHIFT 10 +#define WDOG_STCTRLH_TESTSEL_MASK 0x800u +#define WDOG_STCTRLH_TESTSEL_SHIFT 11 +#define WDOG_STCTRLH_BYTESEL_MASK 0x3000u +#define WDOG_STCTRLH_BYTESEL_SHIFT 12 +#define WDOG_STCTRLH_BYTESEL(x) (((uint16_t)(((uint16_t)(x))< + * @author Johann Fischer + */ + +#ifndef __CPU_CONF_H +#define __CPU_CONF_H + +#ifdef CPU_MODEL_KW22D512 +#include "MKW22D5.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 (16) + +/** + * @brief Pointer to CPU_ID + */ +#define CPUID_ID_PTR ((void *)(&(SIM_UIDH))) + +/** + * @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 */ + +/** + * @name Clock settings for the lptmr timer + */ +#define LPTIMER_CLKSRC_MCGIRCLK 0 /**< internal reference clock (4MHz) */ +#define LPTIMER_CLKSRC_LPO 1 /**< PMC 1kHz output */ +#define LPTIMER_CLKSRC_ERCLK32K 2 /**< RTC clock 32768Hz */ +#define LPTIMER_CLKSRC_OSCERCLK 3 /**< system oscillator output, clock from RF-Part */ + +#ifndef LPTIMER_CLKSRC +#define LPTIMER_CLKSRC LPTIMER_CLKSRC_LPO /**< default clock source */ +#endif + +#if (LPTIMER_CLKSRC == LPTIMER_CLKSRC_MCGIRCLK) +#define LPTIMER_CLK_PRESCALE 1 +#define LPTIMER_SPEED 1000000 +#elif (LPTIMER_CLKSRC == LPTIMER_CLKSRC_OSCERCLK) +#define LPTIMER_CLK_PRESCALE 1 +#define LPTIMER_SPEED 1000000 +#elif (LPTIMER_CLKSRC == LPTIMER_CLKSRC_ERCLK32K) +#define LPTIMER_CLK_PRESCALE 0 +#define LPTIMER_SPEED 32768 +#else +#define LPTIMER_CLK_PRESCALE 0 +#define LPTIMER_SPEED 1000 +#endif + +/** + * @name KW2XD SiP internal interconnects between MCU and Modem. + * + * @{ + */ +#define KW2XDRF_PORT PORTB /**< MCU Port connected to Modem*/ +#define KW2XDRF_GPIO GPIOB /**< GPIO Device connected to Modem */ +#define KW2XDRF_PORT_IRQn PORTB_IRQn +#define KW2XDRF_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK)) /**< Clock Enable for PORTB*/ +#define KW2XDRF_PIN_AF 2 /**< Pin Muxing Parameter for GPIO Device*/ +#define KW2XDRF_PCS0_PIN 10 /**< SPI Slave Select Pin */ +#define KW2XDRF_SCK_PIN 11 /**< SPI Clock Output Pin */ +#define KW2XDRF_SOUT_PIN 16 /**< SPI Master Data Output Pin */ +#define KW2XDRF_SIN_PIN 17 /**< SPI Master Data Input Pin */ + +#define KW2XDRF_IRQ_PIN 3 /**< Modem's IRQ Output (activ low) */ +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CPU_CONF_H */ +/** @} */ diff --git a/cpu/kw2x/kw22d512_linkerscript.ld b/cpu/kw2x/kw22d512_linkerscript.ld new file mode 100644 index 000000000000..80c6ea4857cf --- /dev/null +++ b/cpu/kw2x/kw22d512_linkerscript.ld @@ -0,0 +1,174 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL 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. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom_vectors (rx) : ORIGIN = 0x00000000, LENGTH = 0x400 + rom_fcfield (rx) : ORIGIN = 0x00000400, LENGTH = 0x10 + rom (rx) : ORIGIN = 0x00000410, LENGTH = 512K - 0x410 + ram (rwx) : ORIGIN = 0x1fff8000, LENGTH = 64K + /* ram (rwx) : ORIGIN = 0x1fff8000, LENGTH = 32K */ + /* uram (rwx): ORIGIN = 0x20000000, LENGTH = 32K */ +} + +/* The stack size used by the application. NOTE: you need to adjust */ +STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x4000 ; + + +/* Section Definitions */ +SECTIONS +{ + .vectors : + { + __vector_table = .; + . = ALIGN(4); + KEEP(*(.vectors .vectors.*)) + . = ALIGN(4); + } > rom_vectors + + .fcfield : + { + . = ALIGN(4); + KEEP(*(.fcfield)) + . = ALIGN(4); + } > rom_fcfield + + .text : + { + . = ALIGN(4); + _sfixed = .; + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + KEEP(*(.eh_frame*)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + . = ALIGN(4); + __heap_size = ORIGIN(ram) + LENGTH(ram) - . - STACK_SIZE; + .heap : + { + PROVIDE(__heap_start = .); + __end__ = .; + end = __end__; + *(.heap*) + . = . + __heap_size; + PROVIDE(__heap_max = .); + } >ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(4); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(4); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} diff --git a/cpu/kw2x/lpm_arch.c b/cpu/kw2x/lpm_arch.c new file mode 100644 index 000000000000..89d7d7b28ccd --- /dev/null +++ b/cpu/kw2x/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_kw2x + * @{ + * + * @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/kw2x/periph/Makefile b/cpu/kw2x/periph/Makefile new file mode 100644 index 000000000000..6d1887b64009 --- /dev/null +++ b/cpu/kw2x/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/kw2x/reboot_arch.c b/cpu/kw2x/reboot_arch.c new file mode 100644 index 000000000000..c630456b9b51 --- /dev/null +++ b/cpu/kw2x/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_kw2x + * @{ + * + * @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/kw2x/startup.c b/cpu/kw2x/startup.c new file mode 100644 index 000000000000..76037d111db1 --- /dev/null +++ b/cpu/kw2x/startup.c @@ -0,0 +1,492 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014 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_kw2x + * @{ + * + * @file + * @brief Startup code and interrupt vector definition + * + * @author Hauke Petersen + * @author Johann Fischer + * + * @} + */ + +#include +#include "cpu-conf.h" + +/** + * memory markers as defined in the linker script + */ +extern uint32_t _sfixed; +extern uint32_t _efixed; +extern uint32_t _etext; +extern uint32_t _srelocate; +extern uint32_t _erelocate; +extern uint32_t _szero; +extern uint32_t _ezero; +extern uint32_t _sstack; +extern uint32_t _estack; + +/** + * @brief functions for initializing the board, std-lib and kernel + */ +extern void board_init(void); +extern void kernel_init(void); +extern void __libc_init_array(void); + +/** + * @brief This function is the entry point after a system reset + * + * After a system reset, the following steps are necessary and carried out: + * 0. disable the Watchdog Timer + * 1. load data section from flash to ram + * 2. overwrite uninitialized data section (BSS) with zeros + * 3. initialize the newlib + * 4. initialize the board (sync clock, setup std-IO) + * 5. initialize and start RIOTs kernel + */ +void reset_handler(void) +{ + uint32_t *dst; + uint32_t *src = &_etext; + + /* unlock and disable the WDOG */ + WDOG->UNLOCK = (uint16_t)0xc520; + WDOG->UNLOCK = (uint16_t)0xd928; + WDOG->STCTRLH = (uint16_t)(WDOG_STCTRLH_WAITEN_MASK + | WDOG_STCTRLH_STOPEN_MASK + | WDOG_STCTRLH_ALLOWUPDATE_MASK + | WDOG_STCTRLH_CLKSRC_MASK); + + /* load data section from flash to ram */ + for (dst = &_srelocate; dst < &_erelocate;) { + *(dst++) = *(src++); + } + + /* default bss section to zero */ + for (dst = &_szero; dst < &_ezero;) { + *(dst++) = 0; + } + + /* initialize the board and startup the kernel */ + board_init(); + /* initialize std-c library (this should be done after board_init) */ + __libc_init_array(); + /* startup the kernel */ + kernel_init(); +} + +/** + * @brief Default handler is called in case no interrupt handler was defined + */ +void dummy_handler(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_nmi(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_mem_manage(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_debug_mon(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_hard_fault(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_bus_fault(void) +{ + while (1) { + asm("nop"); + } +} + +void isr_usage_fault(void) +{ + while (1) { + asm("nop"); + } +} + +/* 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"))); + +/* MKW22D512 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_dma4(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma5(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma6(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma7(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma8(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma9(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma10(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma11(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma12(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma13(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma14(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma15(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dma_error(void) __attribute__((weak, alias("dummy_handler"))); +void isr_mcm(void) __attribute__((weak, alias("dummy_handler"))); +void isr_ftfl(void) __attribute__((weak, alias("dummy_handler"))); +void isr_ftfl_collision(void) __attribute__((weak, alias("dummy_handler"))); +void isr_pmc(void) __attribute__((weak, alias("dummy_handler"))); +void isr_llwu(void) __attribute__((weak, alias("dummy_handler"))); +void isr_wdog_ewm(void) __attribute__((weak, alias("dummy_handler"))); +void isr_rng(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_i2s0_tx(void) __attribute__((weak, alias("dummy_handler"))); +void isr_i2s0_rx(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart0_rx_tx(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart0_err(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart1_rx_tx(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart1_err(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart2_rx_tx(void) __attribute__((weak, alias("dummy_handler"))); +void isr_uart2_err(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_cmp1(void) __attribute__((weak, alias("dummy_handler"))); +void isr_ftm0(void) __attribute__((weak, alias("dummy_handler"))); +void isr_ftm1(void) __attribute__((weak, alias("dummy_handler"))); +void isr_ftm2(void) __attribute__((weak, alias("dummy_handler"))); +void isr_cmt(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_pit0(void) __attribute__((weak, alias("dummy_handler"))); +void isr_pit1(void) __attribute__((weak, alias("dummy_handler"))); +void isr_pit2(void) __attribute__((weak, alias("dummy_handler"))); +void isr_pit3(void) __attribute__((weak, alias("dummy_handler"))); +void isr_pdb0(void) __attribute__((weak, alias("dummy_handler"))); +void isr_usb0(void) __attribute__((weak, alias("dummy_handler"))); +void isr_usbdcd(void) __attribute__((weak, alias("dummy_handler"))); +void isr_dac0(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_portb(void) __attribute__((weak, alias("dummy_handler"))); +void isr_portc(void) __attribute__((weak, alias("dummy_handler"))); +void isr_portd(void) __attribute__((weak, alias("dummy_handler"))); +void isr_porte(void) __attribute__((weak, alias("dummy_handler"))); +void isr_swi(void) __attribute__((weak, alias("dummy_handler"))); + + +/* interrupt vector table */ +__attribute__((section(".vectors"))) +const void *interrupt_vector[] = { + /* 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 *) isr_mem_manage, /* memory controller interrupt */ + (void *) isr_bus_fault, /* also not good to end up here */ + (void *) isr_usage_fault, /* autsch */ + (void *)(0UL), /* Reserved */ + (void *)(0UL), /* Reserved */ + (void *)(0UL), /* Reserved */ + (void *)(0UL), /* Reserved */ + (void *) isr_svc, /* system call interrupt */ + (void *) isr_debug_mon, /* debug interrupt */ + (void *)(0UL), /* Reserved */ + (void *) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */ + (void *) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* MKW22D512 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 *) isr_dma4, /* DMA channel 4 transfer complete */ + (void *) isr_dma5, /* DMA channel 5 transfer complete */ + (void *) isr_dma6, /* DMA channel 6 transfer complete */ + (void *) isr_dma7, /* DMA channel 7 transfer complete */ + (void *) isr_dma8, /* DMA channel 8 transfer complete */ + (void *) isr_dma9, /* DMA channel 9 transfer complete */ + (void *) isr_dma10, /* DMA channel 10 transfer complete */ + (void *) isr_dma11, /* DMA channel 11 transfer complete */ + (void *) isr_dma12, /* DMA channel 12 transfer complete */ + (void *) isr_dma13, /* DMA channel 13 transfer complete */ + (void *) isr_dma14, /* DMA channel 14 transfer complete */ + (void *) isr_dma15, /* DMA channel 15 transfer complete */ + (void *) isr_dma_error, /* DMA channel 0 - 15 error */ + (void *) isr_mcm, /* MCM normal interrupt */ + (void *) isr_ftfl, /* FTFL command complete */ + (void *) isr_ftfl_collision, /* FTFL read collision */ + (void *) isr_pmc, /* PMC controller low-voltage detect low-voltage warning */ + (void *) isr_llwu, /* Low leakage wakeup */ + (void *) isr_wdog_ewm, /* Single interrupt vector for WDOG and EWM */ + (void *) isr_rng, /* Randon number generator */ + (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_i2s0_tx, /* Integrated interchip sound 0 transmit interrupt */ + (void *) isr_i2s0_rx, /* Integrated interchip sound 0 receive interrupt */ + (void *) dummy_handler, /* Reserved interrupt */ + (void *) isr_uart0_rx_tx, /* UART0 receive/transmit interrupt */ + (void *) isr_uart0_err, /* UART0 error interrupt */ + (void *) isr_uart1_rx_tx, /* UART1 receive/transmit interrupt */ + (void *) isr_uart1_err, /* UART1 error interrupt */ + (void *) isr_uart2_rx_tx, /* UART2 receive/transmit interrupt */ + (void *) isr_uart2_err, /* UART2 error interrupt */ + (void *) dummy_handler, /* Reserved interrupt */ + (void *) dummy_handler, /* Reserved interrupt */ + (void *) isr_adc0, /* Analog-to-digital converter 0 */ + (void *) isr_cmp0, /* Comparator 0 */ + (void *) isr_cmp1, /* Comparator 1 */ + (void *) isr_ftm0, /* FlexTimer module 0 fault overflow and channels interrupt */ + (void *) isr_ftm1, /* FlexTimer module 1 fault overflow and channels interrupt */ + (void *) isr_ftm2, /* FlexTimer module 2 fault overflow and channels interrupt */ + (void *) isr_cmt, /* Carrier modulator transmitter */ + (void *) isr_rtc, /* Real time clock */ + (void *) isr_rtc_seconds, /* Real time clock seconds */ + (void *) isr_pit0, /* Periodic interrupt timer channel 0 */ + (void *) isr_pit1, /* Periodic interrupt timer channel 1 */ + (void *) isr_pit2, /* Periodic interrupt timer channel 2 */ + (void *) isr_pit3, /* Periodic interrupt timer channel 3 */ + (void *) isr_pdb0, /* Programmable delay block */ + (void *) isr_usb0, /* USB OTG interrupt */ + (void *) isr_usbdcd, /* USB charger detect */ + (void *) dummy_handler, /* Reserved interrupt */ + (void *) isr_dac0, /* Digital-to-analog converter 0 */ + (void *) isr_mcg, /* Multipurpose clock generator */ + (void *) isr_lptmr0, /* Low power timer interrupt */ + (void *) isr_porta, /* Port A pin detect interrupt */ + (void *) isr_portb, /* Port B pin detect interrupt */ + (void *) isr_portc, /* Port C pin detect interrupt */ + (void *) isr_portd, /* Port D pin detect interrupt */ + (void *) isr_porte, /* Port E pin detect interrupt */ + (void *) isr_swi, /* Software interrupt */ + (void *) dummy_handler, /* reserved 81 */ + (void *) dummy_handler, /* reserved 82 */ + (void *) dummy_handler, /* reserved 83 */ + (void *) dummy_handler, /* reserved 84 */ + (void *) dummy_handler, /* reserved 85 */ + (void *) dummy_handler, /* reserved 86 */ + (void *) dummy_handler, /* reserved 87 */ + (void *) dummy_handler, /* reserved 88 */ + (void *) dummy_handler, /* reserved 89 */ + (void *) dummy_handler, /* reserved 90 */ + (void *) dummy_handler, /* reserved 91 */ + (void *) dummy_handler, /* reserved 92 */ + (void *) dummy_handler, /* reserved 93 */ + (void *) dummy_handler, /* reserved 94 */ + (void *) dummy_handler, /* reserved 95 */ + (void *) dummy_handler, /* reserved 96 */ + (void *) dummy_handler, /* reserved 97 */ + (void *) dummy_handler, /* reserved 98 */ + (void *) dummy_handler, /* reserved 99 */ + (void *) dummy_handler, /* reserved 100 */ + (void *) dummy_handler, /* reserved 101 */ + (void *) dummy_handler, /* reserved 102 */ + (void *) dummy_handler, /* reserved 103 */ + (void *) dummy_handler, /* reserved 104 */ + (void *) dummy_handler, /* reserved 105 */ + (void *) dummy_handler, /* reserved 106 */ + (void *) dummy_handler, /* reserved 107 */ + (void *) dummy_handler, /* reserved 108 */ + (void *) dummy_handler, /* reserved 109 */ + (void *) dummy_handler, /* reserved 110 */ + (void *) dummy_handler, /* reserved 111 */ + (void *) dummy_handler, /* reserved 112 */ + (void *) dummy_handler, /* reserved 113 */ + (void *) dummy_handler, /* reserved 114 */ + (void *) dummy_handler, /* reserved 115 */ + (void *) dummy_handler, /* reserved 116 */ + (void *) dummy_handler, /* reserved 117 */ + (void *) dummy_handler, /* reserved 118 */ + (void *) dummy_handler, /* reserved 119 */ + (void *) dummy_handler, /* reserved 120 */ + (void *) dummy_handler, /* reserved 121 */ + (void *) dummy_handler, /* reserved 122 */ + (void *) dummy_handler, /* reserved 123 */ + (void *) dummy_handler, /* reserved 124 */ + (void *) dummy_handler, /* reserved 125 */ + (void *) dummy_handler, /* reserved 126 */ + (void *) dummy_handler, /* reserved 127 */ + (void *) dummy_handler, /* reserved 128 */ + (void *) dummy_handler, /* reserved 129 */ + (void *) dummy_handler, /* reserved 130 */ + (void *) dummy_handler, /* reserved 131 */ + (void *) dummy_handler, /* reserved 132 */ + (void *) dummy_handler, /* reserved 133 */ + (void *) dummy_handler, /* reserved 134 */ + (void *) dummy_handler, /* reserved 135 */ + (void *) dummy_handler, /* reserved 136 */ + (void *) dummy_handler, /* reserved 137 */ + (void *) dummy_handler, /* reserved 138 */ + (void *) dummy_handler, /* reserved 139 */ + (void *) dummy_handler, /* reserved 140 */ + (void *) dummy_handler, /* reserved 141 */ + (void *) dummy_handler, /* reserved 142 */ + (void *) dummy_handler, /* reserved 143 */ + (void *) dummy_handler, /* reserved 144 */ + (void *) dummy_handler, /* reserved 145 */ + (void *) dummy_handler, /* reserved 146 */ + (void *) dummy_handler, /* reserved 147 */ + (void *) dummy_handler, /* reserved 148 */ + (void *) dummy_handler, /* reserved 149 */ + (void *) dummy_handler, /* reserved 150 */ + (void *) dummy_handler, /* reserved 151 */ + (void *) dummy_handler, /* reserved 152 */ + (void *) dummy_handler, /* reserved 153 */ + (void *) dummy_handler, /* reserved 154 */ + (void *) dummy_handler, /* reserved 155 */ + (void *) dummy_handler, /* reserved 156 */ + (void *) dummy_handler, /* reserved 157 */ + (void *) dummy_handler, /* reserved 158 */ + (void *) dummy_handler, /* reserved 159 */ + (void *) dummy_handler, /* reserved 160 */ + (void *) dummy_handler, /* reserved 161 */ + (void *) dummy_handler, /* reserved 162 */ + (void *) dummy_handler, /* reserved 163 */ + (void *) dummy_handler, /* reserved 164 */ + (void *) dummy_handler, /* reserved 165 */ + (void *) dummy_handler, /* reserved 166 */ + (void *) dummy_handler, /* reserved 167 */ + (void *) dummy_handler, /* reserved 168 */ + (void *) dummy_handler, /* reserved 169 */ + (void *) dummy_handler, /* reserved 170 */ + (void *) dummy_handler, /* reserved 171 */ + (void *) dummy_handler, /* reserved 172 */ + (void *) dummy_handler, /* reserved 173 */ + (void *) dummy_handler, /* reserved 174 */ + (void *) dummy_handler, /* reserved 175 */ + (void *) dummy_handler, /* reserved 176 */ + (void *) dummy_handler, /* reserved 177 */ + (void *) dummy_handler, /* reserved 178 */ + (void *) dummy_handler, /* reserved 179 */ + (void *) dummy_handler, /* reserved 180 */ + (void *) dummy_handler, /* reserved 181 */ + (void *) dummy_handler, /* reserved 182 */ + (void *) dummy_handler, /* reserved 183 */ + (void *) dummy_handler, /* reserved 184 */ + (void *) dummy_handler, /* reserved 185 */ + (void *) dummy_handler, /* reserved 186 */ + (void *) dummy_handler, /* reserved 187 */ + (void *) dummy_handler, /* reserved 188 */ + (void *) dummy_handler, /* reserved 189 */ + (void *) dummy_handler, /* reserved 190 */ + (void *) dummy_handler, /* reserved 191 */ + (void *) dummy_handler, /* reserved 192 */ + (void *) dummy_handler, /* reserved 193 */ + (void *) dummy_handler, /* reserved 194 */ + (void *) dummy_handler, /* reserved 195 */ + (void *) dummy_handler, /* reserved 196 */ + (void *) dummy_handler, /* reserved 197 */ + (void *) dummy_handler, /* reserved 198 */ + (void *) dummy_handler, /* reserved 199 */ + (void *) dummy_handler, /* reserved 200 */ + (void *) dummy_handler, /* reserved 201 */ + (void *) dummy_handler, /* reserved 202 */ + (void *) dummy_handler, /* reserved 203 */ + (void *) dummy_handler, /* reserved 204 */ + (void *) dummy_handler, /* reserved 205 */ + (void *) dummy_handler, /* reserved 206 */ + (void *) dummy_handler, /* reserved 207 */ + (void *) dummy_handler, /* reserved 208 */ + (void *) dummy_handler, /* reserved 209 */ + (void *) dummy_handler, /* reserved 210 */ + (void *) dummy_handler, /* reserved 211 */ + (void *) dummy_handler, /* reserved 212 */ + (void *) dummy_handler, /* reserved 213 */ + (void *) dummy_handler, /* reserved 214 */ + (void *) dummy_handler, /* reserved 215 */ + (void *) dummy_handler, /* reserved 216 */ + (void *) dummy_handler, /* reserved 217 */ + (void *) dummy_handler, /* reserved 218 */ + (void *) dummy_handler, /* reserved 219 */ + (void *) dummy_handler, /* reserved 220 */ + (void *) dummy_handler, /* reserved 221 */ + (void *) dummy_handler, /* reserved 222 */ + (void *) dummy_handler, /* reserved 223 */ + (void *) dummy_handler, /* reserved 224 */ + (void *) dummy_handler, /* reserved 225 */ + (void *) dummy_handler, /* reserved 226 */ + (void *) dummy_handler, /* reserved 227 */ + (void *) dummy_handler, /* reserved 228 */ + (void *) dummy_handler, /* reserved 229 */ + (void *) dummy_handler, /* reserved 230 */ + (void *) dummy_handler, /* reserved 231 */ + (void *) dummy_handler, /* reserved 232 */ + (void *) dummy_handler, /* reserved 233 */ + (void *) dummy_handler, /* reserved 234 */ + (void *) dummy_handler, /* reserved 235 */ + (void *) dummy_handler, /* reserved 236 */ + (void *) dummy_handler, /* reserved 237 */ + (void *) dummy_handler, /* reserved 238 */ + (void *) dummy_handler, /* reserved 239 */ + (void *) dummy_handler, /* reserved 240 */ + (void *) dummy_handler, /* reserved 241 */ + (void *) dummy_handler, /* reserved 242 */ + (void *) dummy_handler, /* reserved 243 */ + (void *) dummy_handler, /* reserved 244 */ + (void *) dummy_handler, /* reserved 245 */ + (void *) dummy_handler, /* reserved 246 */ + (void *) dummy_handler, /* reserved 247 */ + (void *) dummy_handler, /* reserved 248 */ + (void *) dummy_handler, /* reserved 249 */ + (void *) dummy_handler, /* reserved 250 */ + (void *) dummy_handler, /* reserved 251 */ + (void *) dummy_handler, /* reserved 252 */ + (void *) dummy_handler, /* reserved 253 */ + (void *) dummy_handler, /* reserved 254 */ + (void *) dummy_handler, /* reserved 255 */ +}; + +/* fcfield table */ +__attribute__((section(".fcfield"))) +const uint8_t flash_configuration_field[] = { + 0xff, /* backdoor comparison key 3., offset: 0x0 */ + 0xff, /* backdoor comparison key 2., offset: 0x1 */ + 0xff, /* backdoor comparison key 1., offset: 0x2 */ + 0xff, /* backdoor comparison key 0., offset: 0x3 */ + 0xff, /* backdoor comparison key 7., offset: 0x4 */ + 0xff, /* backdoor comparison key 6., offset: 0x5 */ + 0xff, /* backdoor comparison key 5., offset: 0x6 */ + 0xff, /* backdoor comparison key 4., offset: 0x7 */ + 0xff, /* non-volatile p-flash protection 1 - low register, offset: 0x8 */ + 0xff, /* non-volatile p-flash protection 1 - high register, offset: 0x9 */ + 0xff, /* non-volatile p-flash protection 0 - low register, offset: 0xa */ + 0xff, /* non-volatile p-flash protection 0 - high register, offset: 0xb */ + 0xfe, /* non-volatile flash security register, offset: 0xc */ + 0xff, /* non-volatile flash option register, offset: 0xd */ + 0xff, /* non-volatile eeram protection register, offset: 0xe */ + 0xff, /* non-volatile d-flash protection register, offset: 0xf */ +}; diff --git a/cpu/kw2x/syscalls.c b/cpu/kw2x/syscalls.c new file mode 100644 index 000000000000..9ebf339fc97e --- /dev/null +++ b/cpu/kw2x/syscalls.c @@ -0,0 +1,345 @@ +/* + * 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_kw2x + * @{ + * + * @file + * @brief NewLib system call implementations for KW2xD 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/dist/tools/licenses/patterns/3c-BSD-freescale b/dist/tools/licenses/patterns/3c-BSD-freescale new file mode 100644 index 000000000000..1e8605850339 --- /dev/null +++ b/dist/tools/licenses/patterns/3c-BSD-freescale @@ -0,0 +1 @@ +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\. diff --git a/doc/doxygen/riot.doxyfile b/doc/doxygen/riot.doxyfile index 8c6614ed1391..da773b617f70 100644 --- a/doc/doxygen/riot.doxyfile +++ b/doc/doxygen/riot.doxyfile @@ -825,6 +825,7 @@ EXCLUDE_PATTERNS = */board/*/tools/* \ */boards/*/include/periph_conf.h \ */cpu/x86/include/x86_pci.h \ */cpu/sam3x8e/include/sam3x8e.h \ + */cpu/kw2x/include/MKW22D5.h \ # The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names