From 40bcfc9211398e537ef2693206fffad01f3f255a Mon Sep 17 00:00:00 2001 From: Anton Gerasimov Date: Tue, 31 Jul 2018 18:08:07 +0200 Subject: [PATCH] kinetis: add support for S9KEAZ128 Signed-off-by: Anton Gerasimov --- cpu/kinetis/Makefile.features | 4 + cpu/kinetis/Makefile.include | 4 + cpu/kinetis/cpu.c | 2 + cpu/kinetis/fcfield.c | 22 + cpu/kinetis/include/cpu_conf.h | 2 + cpu/kinetis/include/cpu_conf_kinetis.h | 4 +- cpu/kinetis/include/cpu_conf_kinetis_ea.h | 45 + cpu/kinetis/include/mcg.h | 2 + cpu/kinetis/include/periph_cpu.h | 57 +- cpu/kinetis/include/vectors_kinetis.h | 8 + cpu/kinetis/include/vendor/SKEAZ1284.h | 6619 +++++++++++++++++ cpu/kinetis/include/vendor/system_SKEAZ1284.h | 227 + cpu/kinetis/isr_kinetis.c | 10 +- cpu/kinetis/kinetis-info.mk | 3 + cpu/kinetis/periph/gpio.c | 22 + cpu/kinetis/periph/ics.c | 203 + cpu/kinetis/periph/timer.c | 67 +- cpu/kinetis/periph/wdog.c | 15 +- cpu/kinetis/vectors.c | 35 + 19 files changed, 7336 insertions(+), 15 deletions(-) create mode 100644 cpu/kinetis/include/cpu_conf_kinetis_ea.h create mode 100644 cpu/kinetis/include/vendor/SKEAZ1284.h create mode 100644 cpu/kinetis/include/vendor/system_SKEAZ1284.h create mode 100644 cpu/kinetis/periph/ics.c diff --git a/cpu/kinetis/Makefile.features b/cpu/kinetis/Makefile.features index 8ebcde8bed..28c39717a7 100644 --- a/cpu/kinetis/Makefile.features +++ b/cpu/kinetis/Makefile.features @@ -2,6 +2,10 @@ FEATURES_PROVIDED += periph_cpuid FEATURES_PROVIDED += periph_hwrng FEATURES_PROVIDED += periph_gpio FEATURES_PROVIDED += periph_gpio_irq +ifeq (EA,$(KINETIS_SERIES)) +FEATURES_PROVIDED += periph_ics +else FEATURES_PROVIDED += periph_mcg +endif include $(RIOTCPU)/cortexm_common/Makefile.features diff --git a/cpu/kinetis/Makefile.include b/cpu/kinetis/Makefile.include index 59a0b948fd..a5f36b4ed0 100644 --- a/cpu/kinetis/Makefile.include +++ b/cpu/kinetis/Makefile.include @@ -37,7 +37,11 @@ export UNDEF += $(BINDIR)/cpu/fcfield.o USEMODULE += periph_common # select kinetis periph drivers +ifeq (EA,$(KINETIS_SERIES)) +USEMODULE += periph_ics +else USEMODULE += periph_mcg +endif USEMODULE += periph_wdog # Define a recipe to build the watchdog disable binary, used when flashing diff --git a/cpu/kinetis/cpu.c b/cpu/kinetis/cpu.c index f5785dd8b3..aff3326d2f 100644 --- a/cpu/kinetis/cpu.c +++ b/cpu/kinetis/cpu.c @@ -30,11 +30,13 @@ void cpu_init(void) { /* initialize the Cortex-M core */ cortexm_init(); +#ifdef SMC /* Clear LLS protection */ /* Clear VLPS, VLPW, VLPR protection */ /* Note: This register can only be written once after each reset, so we must * enable all power modes that we wish to use. */ SMC->PMPROT |= SMC_PMPROT_ALLS_MASK | SMC_PMPROT_AVLP_MASK; +#endif #ifdef MODULE_PERIPH_MCG /* initialize the CPU clocking provided by the MCG module */ kinetis_mcg_init(); diff --git a/cpu/kinetis/fcfield.c b/cpu/kinetis/fcfield.c index 43339a1c73..364ceb3531 100644 --- a/cpu/kinetis/fcfield.c +++ b/cpu/kinetis/fcfield.c @@ -31,6 +31,27 @@ #endif /* fcfield table */ +#ifdef KINETIS_SERIES_EA +__attribute__((weak, used, 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, /* reserved, offset: 0x8 */ + 0xff, /* reserved, offset: 0x9 */ + 0xff, /* reserved, offset: 0xa */ + 0xff, /* reserved, offset: 0xb */ + 0xff, /* reserved, offset: 0xc */ + 0xff, /* non-volatile flash protection register, offset: 0xd */ + 0xfe, /* non-volatile flash security register, offset: 0xe */ + 0xff, /* non-volatile flash nonvolatile register, offset: 0xf */ +}; +#else __attribute__((weak, used, section(".fcfield"))) const uint8_t flash_configuration_field[] = { 0xff, /* backdoor comparison key 3., offset: 0x0 */ @@ -50,3 +71,4 @@ const uint8_t flash_configuration_field[] = { 0xff, /* non-volatile eeram protection register, offset: 0xe */ 0xff, /* non-volatile d-flash protection register, offset: 0xf */ }; +#endif diff --git a/cpu/kinetis/include/cpu_conf.h b/cpu/kinetis/include/cpu_conf.h index c3391b19fe..6aefecdc1e 100644 --- a/cpu/kinetis/include/cpu_conf.h +++ b/cpu/kinetis/include/cpu_conf.h @@ -30,6 +30,8 @@ #include "cpu_conf_kinetis_v.h" #elif defined(KINETIS_SERIES_W) #include "cpu_conf_kinetis_w.h" +#elif defined(KINETIS_SERIES_EA) +#include "cpu_conf_kinetis_ea.h" #endif /* defined(KINETIS_SERIES_x) */ #ifndef MCU_MEM_MAP_VERSION diff --git a/cpu/kinetis/include/cpu_conf_kinetis.h b/cpu/kinetis/include/cpu_conf_kinetis.h index 6e5dc9cb6f..dfd3e171de 100644 --- a/cpu/kinetis/include/cpu_conf_kinetis.h +++ b/cpu/kinetis/include/cpu_conf_kinetis.h @@ -120,9 +120,11 @@ extern "C" /** Enable LPTMR clock gate */ #define LPTMR_CLKEN() (bit_set32(&SIM->SCGC5, SIM_SCGC5_LPTMR_SHIFT)) #endif -#ifdef SIM_SCGC6_PIT_SHIFT +#if defined(SIM_SCGC6_PIT_SHIFT) /** Enable PIT clock gate */ #define PIT_CLKEN() (bit_set32(&SIM->SCGC6, SIM_SCGC6_PIT_SHIFT)) +#elif defined(SIM_SCGC_PIT_SHIFT) +#define PIT_CLKEN() (bit_set32(&SIM->SCGC, SIM_SCGC_PIT_SHIFT)) #endif #ifdef SIM_SCGC6_RTC_SHIFT /** Enable RTC clock gate */ diff --git a/cpu/kinetis/include/cpu_conf_kinetis_ea.h b/cpu/kinetis/include/cpu_conf_kinetis_ea.h new file mode 100644 index 0000000000..d360bcc077 --- /dev/null +++ b/cpu/kinetis/include/cpu_conf_kinetis_ea.h @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2017 Eistec AB + * Copyright (C) 2018 HERE Deutschland 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_kinetis + * @brief CPU specific implementations for the NXP Kinetis EA series of + * Cortex-M MCUs + * @{ + * + * @file + * @brief Implementation specific CPU configuration options + * + * @author Joakim Nohlgård + * @author Anton Gerasimov + */ + +#ifndef CPU_CONF_KINETIS_EA_H +#define CPU_CONF_KINETIS_EA_H + +#if defined(KINETIS_CORE_Z) +#if (KINETIS_ROMSIZE == 128) +/* Kinetis KEAZ128 */ +#include "vendor/SKEAZ1284.h" + +#define KINETIS_SINGLE_UART_IRQ +#endif /* (KINETIS_ROMSIZE == y) */ +#endif /* (KINETIS_CORE_x) */ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* CPU_CONF_KINETIS_EA_H */ +/** @} */ diff --git a/cpu/kinetis/include/mcg.h b/cpu/kinetis/include/mcg.h index 241ed38f8a..b7089f60ac 100644 --- a/cpu/kinetis/include/mcg.h +++ b/cpu/kinetis/include/mcg.h @@ -7,6 +7,7 @@ * details. */ +#ifdef MODULE_PERIPH_MCG /* please doxygen by hiding dangling references */ /** * @defgroup cpu_kinetis_mcg Kinetis MCG * @ingroup cpu_kinetis @@ -116,6 +117,7 @@ * @author Johann Fischer * @author Joakim Nohlgård */ +#endif /* MODULE_PERIPH_MCG */ #ifndef MCG_H #define MCG_H diff --git a/cpu/kinetis/include/periph_cpu.h b/cpu/kinetis/include/periph_cpu.h index 8acb05a60b..6584314bc8 100644 --- a/cpu/kinetis/include/periph_cpu.h +++ b/cpu/kinetis/include/periph_cpu.h @@ -30,6 +30,26 @@ extern "C" { #endif +#ifdef PORT_PCR_MUX +# define KINETIS_HAVE_PCR +#endif + +#ifdef SIM_PINSEL_REG +# define KINETIS_HAVE_PINSEL +#endif + +#ifdef ADC_CFG1_MODE_MASK +# define KINETIS_HAVE_ADC_K +#endif + +#ifdef SPI_CTAR_CPHA_MASK +# define KINETIS_HAVE_MK_SPI +#endif + +#ifdef LPTMR_CSR_TEN_MASK +# define KINETIS_HAVE_LPTMR +#endif + /** * @name CPU specific gpio_t type definition * @{ @@ -145,6 +165,7 @@ typedef enum { /** @} */ #endif /* ndef DOXYGEN */ +#ifdef KINETIS_HAVE_PCR /** * @brief PORT control register bitmasks * @@ -165,18 +186,21 @@ typedef enum { GPIO_PCR_PD = (PORT_PCR_PE_MASK), /**< enable pull-down */ GPIO_PCR_PU = (PORT_PCR_PE_MASK | PORT_PCR_PS_MASK) /**< enable PU */ } gpio_pcr_t; +#endif /* KINETIS_HAVE_PCR */ #ifndef DOXYGEN /** * @name GPIO flank configuration values * @{ */ +#ifdef KINETIS_HAVE_PCR #define HAVE_GPIO_FLANK_T typedef enum { GPIO_RISING = PORT_PCR_IRQC(0x9), /**< emit interrupt on rising flank */ GPIO_FALLING = PORT_PCR_IRQC(0xa), /**< emit interrupt on falling flank */ GPIO_BOTH = PORT_PCR_IRQC(0xb), /**< emit interrupt on both flanks */ } gpio_flank_t; +#endif /* KINETIS_HAVE_PCR */ /** @} */ #endif /* ndef DOXYGEN */ @@ -202,6 +226,7 @@ enum { * @{ */ #define HAVE_ADC_RES_T +#ifdef KINETIS_HAVE_ADC_K typedef enum { ADC_RES_6BIT = (0xfe), /**< not supported */ ADC_RES_8BIT = ADC_CFG1_MODE(0), /**< ADC resolution: 8 bit */ @@ -210,6 +235,7 @@ typedef enum { ADC_RES_14BIT = (0xff), /**< ADC resolution: 14 bit */ ADC_RES_16BIT = ADC_CFG1_MODE(3) /**< ADC resolution: 16 bit */ } adc_res_t; +#endif /* KINETIS_HAVE_ADC_K */ /** @} */ #if defined(FTM_CnSC_MSB_MASK) @@ -260,6 +286,8 @@ typedef enum { * @name SPI mode bitmasks * @{ */ + +#ifdef KINETIS_HAVE_MK_SPI #define HAVE_SPI_MODE_T typedef enum { SPI_MODE_0 = 0, /**< CPOL=0, CPHA=0 */ @@ -268,6 +296,7 @@ typedef enum { SPI_MODE_3 = (SPI_CTAR_CPOL_MASK | SPI_CTAR_CPHA_MASK) /**< CPOL=1, CPHA=1 */ } spi_mode_t; /** @} */ +#endif /* KINETIS_HAVE_MK_SPI */ #endif /* ndef DOXYGEN */ /** @@ -329,6 +358,7 @@ typedef struct { uint8_t count_ch; } pit_conf_t; +#ifdef KINETIS_HAVE_LPTMR /** * @brief CPU specific timer LPTMR module configuration */ @@ -342,6 +372,7 @@ typedef struct { /** IRQn interrupt number */ uint8_t irqn; } lptmr_conf_t; +#endif /* KINETIS_HAVE_LPTMR */ #ifdef FTM_CnSC_MSB_MASK /** @@ -356,6 +387,11 @@ typedef struct { } chan[PWM_CHAN_MAX]; /**< logical channel configuration */ uint8_t chan_numof; /**< number of actually configured channels */ uint8_t ftm_num; /**< FTM number used */ +#ifdef KINETIS_HAVE_PINSEL + volatile uint32_t *pinsel; + uint32_t pinsel_mask; + uint32_t pinsel_val; +#endif } pwm_conf_t; #endif @@ -403,7 +439,14 @@ typedef struct { gpio_t pin_mosi; /**< MOSI pin used */ gpio_t pin_clk; /**< CLK pin used */ gpio_t pin_cs[SPI_HWCS_NUMOF]; /**< pins used for HW cs lines */ +#ifdef KINETIS_HAVE_PCR gpio_pcr_t pcr; /**< alternate pin function values */ +#endif /* KINETIS_HAVE_PCR */ +#ifdef KINETIS_HAVE_PINSEL + volatile uint32_t *pinsel; + uint32_t pinsel_mask; + uint32_t pinsel_val; +#endif uint32_t simmask; /**< bit in the SIM register */ } spi_conf_t; @@ -412,7 +455,9 @@ typedef struct { */ enum { TIMER_PIT, /**< PIT */ +#ifdef KINETIS_HAVE_LPTMR TIMER_LPTMR, /**< LPTMR */ +#endif /* KINETIS_HAVE_LPTMR */ }; /** @@ -421,8 +466,10 @@ enum { */ /** @brief Timers using PIT backend */ #define TIMER_PIT_DEV(x) (TIMER_DEV(0 + (x))) +#ifdef KINETIS_HAVE_LPTMR /** @brief Timers using LPTMR backend */ #define TIMER_LPTMR_DEV(x) (TIMER_DEV(PIT_NUMOF + (x))) +#endif /* KINETIS_HAVE_LPTMR */ /** @} */ /** @@ -441,8 +488,15 @@ typedef struct { uint32_t freq; /**< Module clock frequency, usually CLOCK_CORECLOCK or CLOCK_BUSCLOCK */ gpio_t pin_rx; /**< RX pin, GPIO_UNDEF disables RX */ gpio_t pin_tx; /**< TX pin */ +#ifdef KINETIS_HAVE_PCR uint32_t pcr_rx; /**< Pin configuration register bits for RX */ uint32_t pcr_tx; /**< Pin configuration register bits for TX */ +#endif +#ifdef KINETIS_HAVE_PINSEL + volatile uint32_t *pinsel; + uint32_t pinsel_mask; + uint32_t pinsel_val; +#endif IRQn_Type irqn; /**< IRQ number for this module */ volatile uint32_t *scgc_addr; /**< Clock enable register, in SIM module */ uint8_t scgc_bit; /**< Clock enable bit, within the register */ @@ -461,6 +515,7 @@ typedef struct { #endif #endif /* !defined(KINETIS_HAVE_PLL) */ +#ifdef MODULE_PERIPH_MCG /** * @brief Kinetis possible MCG modes */ @@ -707,7 +762,7 @@ typedef struct { uint8_t pll_vdiv; #endif /* KINETIS_HAVE_PLL */ } clock_config_t; - +#endif /* MODULE_PERIPH_MCG */ /** * @brief CPU internal function for initializing PORTs * diff --git a/cpu/kinetis/include/vectors_kinetis.h b/cpu/kinetis/include/vectors_kinetis.h index c14ca73356..929cdc9e93 100644 --- a/cpu/kinetis/include/vectors_kinetis.h +++ b/cpu/kinetis/include/vectors_kinetis.h @@ -49,6 +49,8 @@ void isr_can1_ored_message_buffer(void); /**< CAN1 OR'd message buffers interrup void isr_can1_rx_warning(void); /**< CAN1 Rx warning interrupt handler */ void isr_can1_tx_warning(void); /**< CAN1 Tx warning interrupt handler */ void isr_can1_wake_up(void); /**< CAN1 wake up interrupt handler */ +void isr_mscan_rx(void); /**< MSCAN RX interrupt handler */ +void isr_mscan_tx(void); /**< MSCAN TX/Err/Wake-up interrupt handler */ void isr_cmp0(void); /**< CMP0 interrupt handler */ void isr_cmp1(void); /**< CMP1 interrupt handler */ void isr_cmp2(void); /**< CMP2 interrupt handler */ @@ -147,17 +149,23 @@ void isr_tpm1(void); /**< TPM1 interrupt handler */ void isr_tpm2(void); /**< TPM2 interrupt handler */ void isr_trng0(void); /**< TRNG0 interrupt handler */ void isr_tsi0(void); /**< TSI0 interrupt handler */ +void isr_uart0(void); /**< UART0 unified interrupt handler */ void isr_uart0_err(void); /**< UART0 error interrupt handler */ void isr_uart0_lon(void); /**< UART0 LON interrupt handler */ void isr_uart0_rx_tx(void); /**< UART0 receive/transmit interrupt handler */ +void isr_uart1(void); /**< UART1 unified interrupt handler */ void isr_uart1_err(void); /**< UART1 error interrupt handler */ void isr_uart1_rx_tx(void); /**< UART1 receive/transmit interrupt handler */ +void isr_uart2(void); /**< UART2 unified interrupt handler */ void isr_uart2_err(void); /**< UART2 error interrupt handler */ void isr_uart2_rx_tx(void); /**< UART2 receive/transmit interrupt handler */ +void isr_uart3(void); /**< UART3 unified interrupt handler */ void isr_uart3_err(void); /**< UART3 error interrupt handler */ void isr_uart3_rx_tx(void); /**< UART3 receive/transmit interrupt handler */ +void isr_uart4(void); /**< UART4 unified interrupt handler */ void isr_uart4_err(void); /**< UART4 error interrupt handler */ void isr_uart4_rx_tx(void); /**< UART4 receive/transmit interrupt handler */ +void isr_uart5(void); /**< UART5 unified interrupt handler */ void isr_uart5_err(void); /**< UART5 error interrupt handler */ void isr_uart5_rx_tx(void); /**< UART5 receive/transmit interrupt handler */ void isr_usb0(void); /**< USB0 interrupt handler */ diff --git a/cpu/kinetis/include/vendor/SKEAZ1284.h b/cpu/kinetis/include/vendor/SKEAZ1284.h new file mode 100644 index 0000000000..9f075940cf --- /dev/null +++ b/cpu/kinetis/include/vendor/SKEAZ1284.h @@ -0,0 +1,6619 @@ +/* +** ################################################################### +** Compilers: Keil ARM C/C++ Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** GNU C Compiler - CodeSourcery Sourcery G++ +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manual: KEA128RM, Rev. 22, Jun 2014 +** Version: rev. 1.4, 2015-07-24 +** Build: b150730 +** +** Abstract: +** CMSIS Peripheral Access Layer for SKEAZ1284 +** +** Copyright (c) 1997 - 2015 Freescale Semiconductor, Inc. +** All rights reserved. +** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** +** o Redistributions of source code must retain the above copyright notice, this list +** of conditions and the following disclaimer. +** +** o Redistributions in binary form must reproduce the above copyright notice, this +** list of conditions and the following disclaimer in the documentation and/or +** other materials provided with the distribution. +** +** o Neither the name of Freescale Semiconductor, Inc. nor the names of its +** contributors may be used to endorse or promote products derived from this +** software without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2013-07-30) +** Initial version. +** - rev. 1.1 (2013-10-29) +** Definition of BITBAND macros updated to support peripherals with 32-bit acces disabled. +** - rev. 1.2 (2014-01-10) +** CAN - Corrected address of TSIDR1 register. +** CAN - Corrected name of MSCAN_TDLR bit DLC to TDLC. +** FTM0 - Added access macro for EXTTRIG register. +** NVIC - Registers access macros improved. +** SCB - Unused bits removed, mask, shift macros improved. +** Defines of interrupt vectors aligned to RM. +** - rev. 1.3 (2014-06-18) +** The declaration of clock configurations has been moved to separate header file system_MKE02Z2.h +** Module access macro {module}_BASES replaced by {module}_BASE_PTRS. +** I2C - Renamed status register S to S1 to match RM naming. +** Renamed interrupts: INT_PMC to INT_LVD_LVW, INT_ADC to ADC0,INT_WDOG to INT_Watchdog. +** - rev. 1.4 (2015-07-24) +** Correction of backward compatibility. +** +** ################################################################### +*/ + +/*! + * @file SKEAZ1284.h + * @version 1.4 + * @date 2015-07-24 + * @brief CMSIS Peripheral Access Layer for SKEAZ1284 + * + * CMSIS Peripheral Access Layer for SKEAZ1284 + */ + + +/* ---------------------------------------------------------------------------- + -- MCU activation + ---------------------------------------------------------------------------- */ + +/* Prevention from multiple including the same memory map */ +#if !defined(SKEAZ1284_H_) /* Check if memory map has not been already included */ +#define SKEAZ1284_H_ +#define MCU_SKEAZ1284 + +/* Check if another memory map has not been also included */ +#if (defined(MCU_ACTIVE)) + #error SKEAZ1284 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 0x0004u + + +/* ---------------------------------------------------------------------------- + -- Interrupt vector numbers + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Interrupt_vector_numbers Interrupt vector numbers + * @{ + */ + +/** Interrupt Number Definitions */ +#define NUMBER_OF_INT_VECTORS 48 /**< Number of interrupts in the Vector table */ + +typedef enum IRQn { + /* Core interrupts */ + NonMaskableInt_IRQn = -14, /**< Non Maskable Interrupt */ + HardFault_IRQn = -13, /**< Cortex-M0 SV Hard Fault Interrupt */ + SVCall_IRQn = -5, /**< Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /**< Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /**< Cortex-M0 System Tick Interrupt */ + + /* Device specific interrupts */ + Reserved16_IRQn = 0, /**< Reserved interrupt */ + Reserved17_IRQn = 1, /**< Reserved interrupt */ + Reserved18_IRQn = 2, /**< Reserved interrupt */ + Reserved19_IRQn = 3, /**< Reserved interrupt */ + Reserved20_IRQn = 4, /**< Reserved interrupt */ + FTMRE_IRQn = 5, /**< FTMRE command complete */ + LVD_LVW_IRQn = 6, /**< Low-voltage warning */ + IRQ_IRQn = 7, /**< External interrupt */ + I2C0_IRQn = 8, /**< I2C0 single interrupt vector for all sources */ + I2C1_IRQn = 9, /**< I2C1 single interrupt vector for all sources */ + SPI0_IRQn = 10, /**< SPI0 single interrupt vector for all sources */ + SPI1_IRQn = 11, /**< SPI1 single interrupt vector for all sources */ + UART0_IRQn = 12, /**< UART0 status and error */ + UART1_IRQn = 13, /**< UART1 status and error */ + UART2_IRQn = 14, /**< UART2 status and error */ + ADC0_IRQn = 15, /**< ADC conversion complete interrupt */ + ACMP0_IRQn = 16, /**< ACMP0 interrupt */ + FTM0_IRQn = 17, /**< FTM0 single interrupt vector for all sources */ + FTM1_IRQn = 18, /**< FTM1 single interrupt vector for all sources */ + FTM2_IRQn = 19, /**< FTM2 single interrupt vector for all sources */ + RTC_IRQn = 20, /**< RTC overflow */ + ACMP1_IRQn = 21, /**< ACMP1 interrupt */ + PIT0_IRQn = 22, /**< PIT CH0 overflow */ + PIT1_IRQn = 23, /**< PIT CH1 overflow */ + KBI0_IRQn = 24, /**< KBI0 interrupt */ + KBI1_IRQn = 25, /**< KBI1 interrupt */ + Reserved42_IRQn = 26, /**< Reserved interrupt */ + ICS_IRQn = 27, /**< Clock loss of lock */ + WDOG_EWM_IRQn = 28, /**< Watchdog timeout */ + PWT_IRQn = 29, /**< PWT interrupt */ + MSCAN_RX_IRQn = 30, /**< MSCAN Rx interrupt */ + MSCAN_TX_IRQn = 31 /**< MSCAN Tx, Err and Wake-up interrupt */ +} IRQn_Type; + +/*! + * @} + */ /* end of group Interrupt_vector_numbers */ + + +/* ---------------------------------------------------------------------------- + -- Cortex M0 Core Configuration + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup Cortex_Core_Configuration Cortex M0 Core Configuration + * @{ + */ + +#define __CM0PLUS_REV 0x0000 /**< Core revision r0p0 */ +#define __MPU_PRESENT 0 /**< Defines if an MPU is present or not */ +#define __VTOR_PRESENT 1 /**< Defines if an MPU is present or not */ +#define __NVIC_PRIO_BITS 2 /**< Number of priority bits implemented in the NVIC */ +#define __Vendor_SysTickConfig 0 /**< Vendor specific implementation of SysTickConfig is defined */ + +#include "core_cm0plus.h" /* Core Peripheral Access Layer */ +#include "system_SKEAZ1284.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 +#elif defined(__ghs__) /* GreenHills */ + #else + #error Not supported compiler type +#endif + +/* ---------------------------------------------------------------------------- + -- ACMP Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ACMP_Peripheral_Access_Layer ACMP Peripheral Access Layer + * @{ + */ + +/** ACMP - Register Layout Typedef */ +typedef struct { + __IO uint8_t CS; /**< ACMP Control and Status Register, offset: 0x0 */ + __IO uint8_t C0; /**< ACMP Control Register 0, offset: 0x1 */ + __IO uint8_t C1; /**< ACMP Control Register 1, offset: 0x2 */ + __IO uint8_t C2; /**< ACMP Control Register 2, offset: 0x3 */ +} ACMP_Type, *ACMP_MemMapPtr; + +/* ---------------------------------------------------------------------------- + -- ACMP - Register accessor macros + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ACMP_Register_Accessor_Macros ACMP - Register accessor macros + * @{ + */ + + +/* ACMP - Register accessors */ +#define ACMP_CS_REG(base) ((base)->CS) +#define ACMP_C0_REG(base) ((base)->C0) +#define ACMP_C1_REG(base) ((base)->C1) +#define ACMP_C2_REG(base) ((base)->C2) + +/*! + * @} + */ /* end of group ACMP_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- ACMP Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ACMP_Register_Masks ACMP Register Masks + * @{ + */ + +/* CS Bit Fields */ +#define ACMP_CS_ACMOD_MASK 0x3u +#define ACMP_CS_ACMOD_SHIFT 0 +#define ACMP_CS_ACMOD_WIDTH 2 +#define ACMP_CS_ACMOD(x) (((uint8_t)(((uint8_t)(x))<SC1) +#define ADC_SC2_REG(base) ((base)->SC2) +#define ADC_SC3_REG(base) ((base)->SC3) +#define ADC_SC4_REG(base) ((base)->SC4) +#define ADC_R_REG(base) ((base)->R) +#define ADC_CV_REG(base) ((base)->CV) +#define ADC_APCTL1_REG(base) ((base)->APCTL1) +#define ADC_SC5_REG(base) ((base)->SC5) + +/*! + * @} + */ /* 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_WIDTH 5 +#define ADC_SC1_ADCH(x) (((uint32_t)(((uint32_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_WIDTH 16 +#define CRC_DATAL_DATAL(x) (((uint16_t)(((uint16_t)(x))<PDOR) +#define FGPIO_PSOR_REG(base) ((base)->PSOR) +#define FGPIO_PCOR_REG(base) ((base)->PCOR) +#define FGPIO_PTOR_REG(base) ((base)->PTOR) +#define FGPIO_PDIR_REG(base) ((base)->PDIR) +#define FGPIO_PDDR_REG(base) ((base)->PDDR) +#define FGPIO_PIDR_REG(base) ((base)->PIDR) + +/*! + * @} + */ /* end of group FGPIO_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FGPIO Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FGPIO_Register_Masks FGPIO Register Masks + * @{ + */ + +/* PDOR Bit Fields */ +#define FGPIO_PDOR_PDO_MASK 0xFFFFFFFFu +#define FGPIO_PDOR_PDO_SHIFT 0 +#define FGPIO_PDOR_PDO_WIDTH 32 +#define FGPIO_PDOR_PDO(x) (((uint32_t)(((uint32_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_CnSC_COUNT 6 +#define FTM_CnV_REG(base,index) ((base)->CONTROLS[index].CnV) +#define FTM_CnV_COUNT 6 +#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_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_WIDTH 3 +#define FTM_SC_PS(x) (((uint32_t)(((uint32_t)(x))<FCCOBIX) +#define FTMRE_FSEC_REG(base) ((base)->FSEC) +#define FTMRE_FCLKDIV_REG(base) ((base)->FCLKDIV) +#define FTMRE_FSTAT_REG(base) ((base)->FSTAT) +#define FTMRE_FCNFG_REG(base) ((base)->FCNFG) +#define FTMRE_FCCOBLO_REG(base) ((base)->FCCOBLO) +#define FTMRE_FCCOBHI_REG(base) ((base)->FCCOBHI) +#define FTMRE_FPROT_REG(base) ((base)->FPROT) +#define FTMRE_FOPT_REG(base) ((base)->FOPT) + +/*! + * @} + */ /* end of group FTMRE_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- FTMRE Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup FTMRE_Register_Masks FTMRE Register Masks + * @{ + */ + +/* FCCOBIX Bit Fields */ +#define FTMRE_FCCOBIX_CCOBIX_MASK 0x7u +#define FTMRE_FCCOBIX_CCOBIX_SHIFT 0 +#define FTMRE_FCCOBIX_CCOBIX_WIDTH 3 +#define FTMRE_FCCOBIX_CCOBIX(x) (((uint8_t)(((uint8_t)(x))<PDOR) +#define GPIO_PSOR_REG(base) ((base)->PSOR) +#define GPIO_PCOR_REG(base) ((base)->PCOR) +#define GPIO_PTOR_REG(base) ((base)->PTOR) +#define GPIO_PDIR_REG(base) ((base)->PDIR) +#define GPIO_PDDR_REG(base) ((base)->PDDR) +#define GPIO_PIDR_REG(base) ((base)->PIDR) + +/*! + * @} + */ /* 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_WIDTH 32 +#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_S1_REG(base) ((base)->S1) +#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_WIDTH 7 +#define I2C_A1_AD(x) (((uint8_t)(((uint8_t)(x))<C1) +#define ICS_C2_REG(base) ((base)->C2) +#define ICS_C3_REG(base) ((base)->C3) +#define ICS_C4_REG(base) ((base)->C4) +#define ICS_S_REG(base) ((base)->S) + +/*! + * @} + */ /* end of group ICS_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- ICS Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ICS_Register_Masks ICS Register Masks + * @{ + */ + +/* C1 Bit Fields */ +#define ICS_C1_IREFSTEN_MASK 0x1u +#define ICS_C1_IREFSTEN_SHIFT 0 +#define ICS_C1_IREFSTEN_WIDTH 1 +#define ICS_C1_IREFSTEN(x) (((uint8_t)(((uint8_t)(x))<SC) + +/*! + * @} + */ /* end of group IRQ_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- IRQ Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup IRQ_Register_Masks IRQ Register Masks + * @{ + */ + +/* SC Bit Fields */ +#define IRQ_SC_IRQMOD_MASK 0x1u +#define IRQ_SC_IRQMOD_SHIFT 0 +#define IRQ_SC_IRQMOD_WIDTH 1 +#define IRQ_SC_IRQMOD(x) (((uint8_t)(((uint8_t)(x))<PE) +#define KBI_ES_REG(base) ((base)->ES) +#define KBI_SC_REG(base) ((base)->SC) +#define KBI_SP_REG(base) ((base)->SP) + +/*! + * @} + */ /* end of group KBI_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- KBI Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup KBI_Register_Masks KBI Register Masks + * @{ + */ + +/* PE Bit Fields */ +#define KBI_PE_KBIPE_MASK 0xFFFFFFFFu +#define KBI_PE_KBIPE_SHIFT 0 +#define KBI_PE_KBIPE_WIDTH 32 +#define KBI_PE_KBIPE(x) (((uint32_t)(((uint32_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_WIDTH 8 +#define MCM_PLASC_ASC(x) (((uint16_t)(((uint16_t)(x))<CANCTL0) +#define MSCAN_CANCTL1_REG(base) ((base)->CANCTL1) +#define MSCAN_CANBTR0_REG(base) ((base)->CANBTR0) +#define MSCAN_CANBTR1_REG(base) ((base)->CANBTR1) +#define MSCAN_CANRFLG_REG(base) ((base)->CANRFLG) +#define MSCAN_CANRIER_REG(base) ((base)->CANRIER) +#define MSCAN_CANTFLG_REG(base) ((base)->CANTFLG) +#define MSCAN_CANTIER_REG(base) ((base)->CANTIER) +#define MSCAN_CANTARQ_REG(base) ((base)->CANTARQ) +#define MSCAN_CANTAAK_REG(base) ((base)->CANTAAK) +#define MSCAN_CANTBSEL_REG(base) ((base)->CANTBSEL) +#define MSCAN_CANIDAC_REG(base) ((base)->CANIDAC) +#define MSCAN_CANMISC_REG(base) ((base)->CANMISC) +#define MSCAN_CANRXERR_REG(base) ((base)->CANRXERR) +#define MSCAN_CANTXERR_REG(base) ((base)->CANTXERR) +#define MSCAN_CANIDAR_BANK_1_REG(base,index) ((base)->CANIDAR_BANK_1[index]) +#define MSCAN_CANIDAR_BANK_1_COUNT 4 +#define MSCAN_CANIDMR_BANK_1_REG(base,index) ((base)->CANIDMR_BANK_1[index]) +#define MSCAN_CANIDMR_BANK_1_COUNT 4 +#define MSCAN_CANIDAR_BANK_2_REG(base,index) ((base)->CANIDAR_BANK_2[index]) +#define MSCAN_CANIDAR_BANK_2_COUNT 4 +#define MSCAN_CANIDMR_BANK_2_REG(base,index) ((base)->CANIDMR_BANK_2[index]) +#define MSCAN_CANIDMR_BANK_2_COUNT 4 +#define MSCAN_REIDR0_REG(base) ((base)->REIDR0) +#define MSCAN_RSIDR0_REG(base) ((base)->RSIDR0) +#define MSCAN_REIDR1_REG(base) ((base)->REIDR1) +#define MSCAN_RSIDR1_REG(base) ((base)->RSIDR1) +#define MSCAN_REIDR2_REG(base) ((base)->REIDR2) +#define MSCAN_REIDR3_REG(base) ((base)->REIDR3) +#define MSCAN_REDSR_REG(base,index) ((base)->REDSR[index]) +#define MSCAN_REDSR_COUNT 8 +#define MSCAN_RDLR_REG(base) ((base)->RDLR) +#define MSCAN_RTSRH_REG(base) ((base)->RTSRH) +#define MSCAN_RTSRL_REG(base) ((base)->RTSRL) +#define MSCAN_TEIDR0_REG(base) ((base)->TEIDR0) +#define MSCAN_TSIDR0_REG(base) ((base)->TSIDR0) +#define MSCAN_TEIDR1_REG(base) ((base)->TEIDR1) +#define MSCAN_TSIDR1_REG(base) ((base)->TSIDR1) +#define MSCAN_TEIDR2_REG(base) ((base)->TEIDR2) +#define MSCAN_TEIDR3_REG(base) ((base)->TEIDR3) +#define MSCAN_TEDSR_REG(base,index) ((base)->TEDSR[index]) +#define MSCAN_TEDSR_COUNT 8 +#define MSCAN_TDLR_REG(base) ((base)->TDLR) +#define MSCAN_TBPR_REG(base) ((base)->TBPR) +#define MSCAN_TTSRH_REG(base) ((base)->TTSRH) +#define MSCAN_TTSRL_REG(base) ((base)->TTSRL) + +/*! + * @} + */ /* end of group MSCAN_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- MSCAN Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup MSCAN_Register_Masks MSCAN Register Masks + * @{ + */ + +/* CANCTL0 Bit Fields */ +#define MSCAN_CANCTL0_INITRQ_MASK 0x1u +#define MSCAN_CANCTL0_INITRQ_SHIFT 0 +#define MSCAN_CANCTL0_INITRQ_WIDTH 1 +#define MSCAN_CANCTL0_INITRQ(x) (((uint8_t)(((uint8_t)(x))<BACKKEY0) +#define NV_BACKKEY1_REG(base) ((base)->BACKKEY1) +#define NV_BACKKEY2_REG(base) ((base)->BACKKEY2) +#define NV_BACKKEY3_REG(base) ((base)->BACKKEY3) +#define NV_BACKKEY4_REG(base) ((base)->BACKKEY4) +#define NV_BACKKEY5_REG(base) ((base)->BACKKEY5) +#define NV_BACKKEY6_REG(base) ((base)->BACKKEY6) +#define NV_BACKKEY7_REG(base) ((base)->BACKKEY7) +#define NV_FPROT_REG(base) ((base)->FPROT) +#define NV_FSEC_REG(base) ((base)->FSEC) +#define NV_FOPT_REG(base) ((base)->FOPT) + +/*! + * @} + */ /* end of group NV_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- NV Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup NV_Register_Masks NV Register Masks + * @{ + */ + +/* BACKKEY0 Bit Fields */ +#define NV_BACKKEY0_KEY_MASK 0xFFu +#define NV_BACKKEY0_KEY_SHIFT 0 +#define NV_BACKKEY0_KEY_WIDTH 8 +#define NV_BACKKEY0_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_OSCINIT_MASK 0x1u +#define OSC_CR_OSCINIT_SHIFT 0 +#define OSC_CR_OSCINIT_WIDTH 1 +#define OSC_CR_OSCINIT(x) (((uint8_t)(((uint8_t)(x))<MCR) +#define PIT_LDVAL_REG(base,index) ((base)->CHANNEL[index].LDVAL) +#define PIT_LDVAL_COUNT 2 +#define PIT_CVAL_REG(base,index) ((base)->CHANNEL[index].CVAL) +#define PIT_CVAL_COUNT 2 +#define PIT_TCTRL_REG(base,index) ((base)->CHANNEL[index].TCTRL) +#define PIT_TCTRL_COUNT 2 +#define PIT_TFLG_REG(base,index) ((base)->CHANNEL[index].TFLG) +#define PIT_TFLG_COUNT 2 + +/*! + * @} + */ /* 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_FRZ_WIDTH 1 +#define PIT_MCR_FRZ(x) (((uint32_t)(((uint32_t)(x))<SPMSC1) +#define PMC_SPMSC2_REG(base) ((base)->SPMSC2) + +/*! + * @} + */ /* end of group PMC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PMC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PMC_Register_Masks PMC Register Masks + * @{ + */ + +/* SPMSC1 Bit Fields */ +#define PMC_SPMSC1_BGBE_MASK 0x1u +#define PMC_SPMSC1_BGBE_SHIFT 0 +#define PMC_SPMSC1_BGBE_WIDTH 1 +#define PMC_SPMSC1_BGBE(x) (((uint8_t)(((uint8_t)(x))<IOFLT0) +#define PORT_IOFLT1_REG(base) ((base)->IOFLT1) +#define PORT_PUE0_REG(base) ((base)->PUE0) +#define PORT_PUE1_REG(base) ((base)->PUE1) +#define PORT_PUE2_REG(base) ((base)->PUE2) +#define PORT_HDRVE_REG(base) ((base)->HDRVE) + +/*! + * @} + */ /* end of group PORT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PORT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PORT_Register_Masks PORT Register Masks + * @{ + */ + +/* IOFLT0 Bit Fields */ +#define PORT_IOFLT0_FLTA_MASK 0x3u +#define PORT_IOFLT0_FLTA_SHIFT 0 +#define PORT_IOFLT0_FLTA_WIDTH 2 +#define PORT_IOFLT0_FLTA(x) (((uint32_t)(((uint32_t)(x))<R1) +#define PWT_R2_REG(base) ((base)->R2) + +/*! + * @} + */ /* end of group PWT_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- PWT Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup PWT_Register_Masks PWT Register Masks + * @{ + */ + +/* R1 Bit Fields */ +#define PWT_R1_PWTOV_MASK 0x1u +#define PWT_R1_PWTOV_SHIFT 0 +#define PWT_R1_PWTOV_WIDTH 1 +#define PWT_R1_PWTOV(x) (((uint32_t)(((uint32_t)(x))<ENTRY[index]) +#define ROM_ENTRY_COUNT 1 +#define ROM_TABLEMARK_REG(base) ((base)->TABLEMARK) +#define ROM_SYSACCESS_REG(base) ((base)->SYSACCESS) +#define ROM_PERIPHID4_REG(base) ((base)->PERIPHID4) +#define ROM_PERIPHID5_REG(base) ((base)->PERIPHID5) +#define ROM_PERIPHID6_REG(base) ((base)->PERIPHID6) +#define ROM_PERIPHID7_REG(base) ((base)->PERIPHID7) +#define ROM_PERIPHID0_REG(base) ((base)->PERIPHID0) +#define ROM_PERIPHID1_REG(base) ((base)->PERIPHID1) +#define ROM_PERIPHID2_REG(base) ((base)->PERIPHID2) +#define ROM_PERIPHID3_REG(base) ((base)->PERIPHID3) +#define ROM_COMPID_REG(base,index) ((base)->COMPID[index]) +#define ROM_COMPID_COUNT 4 + +/*! + * @} + */ /* end of group ROM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- ROM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup ROM_Register_Masks ROM Register Masks + * @{ + */ + +/* ENTRY Bit Fields */ +#define ROM_ENTRY_ENTRY_MASK 0xFFFFFFFFu +#define ROM_ENTRY_ENTRY_SHIFT 0 +#define ROM_ENTRY_ENTRY_WIDTH 32 +#define ROM_ENTRY_ENTRY(x) (((uint32_t)(((uint32_t)(x))<SC) +#define RTC_MOD_REG(base) ((base)->MOD) +#define RTC_CNT_REG(base) ((base)->CNT) + +/*! + * @} + */ /* end of group RTC_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- RTC Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup RTC_Register_Masks RTC Register Masks + * @{ + */ + +/* SC Bit Fields */ +#define RTC_SC_RTCO_MASK 0x10u +#define RTC_SC_RTCO_SHIFT 4 +#define RTC_SC_RTCO_WIDTH 1 +#define RTC_SC_RTCO(x) (((uint32_t)(((uint32_t)(x))<SRSID) +#define SIM_SOPT0_REG(base) ((base)->SOPT0) +#define SIM_SOPT1_REG(base) ((base)->SOPT1) +#define SIM_PINSEL_REG(base) ((base)->PINSEL) +#define SIM_PINSEL1_REG(base) ((base)->PINSEL1) +#define SIM_SCGC_REG(base) ((base)->SCGC) +#define SIM_UUIDL_REG(base) ((base)->UUIDL) +#define SIM_UUIDML_REG(base) ((base)->UUIDML) +#define SIM_UUIDMH_REG(base) ((base)->UUIDMH) +#define SIM_CLKDIV_REG(base) ((base)->CLKDIV) + +/*! + * @} + */ /* end of group SIM_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SIM Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SIM_Register_Masks SIM Register Masks + * @{ + */ + +/* SRSID Bit Fields */ +#define SIM_SRSID_LVD_MASK 0x2u +#define SIM_SRSID_LVD_SHIFT 1 +#define SIM_SRSID_LVD_WIDTH 1 +#define SIM_SRSID_LVD(x) (((uint32_t)(((uint32_t)(x))<C1) +#define SPI_C2_REG(base) ((base)->C2) +#define SPI_BR_REG(base) ((base)->BR) +#define SPI_S_REG(base) ((base)->S) +#define SPI_D_REG(base) ((base)->D) +#define SPI_M_REG(base) ((base)->M) + +/*! + * @} + */ /* end of group SPI_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- SPI Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup SPI_Register_Masks SPI Register Masks + * @{ + */ + +/* C1 Bit Fields */ +#define SPI_C1_LSBFE_MASK 0x1u +#define SPI_C1_LSBFE_SHIFT 0 +#define SPI_C1_LSBFE_WIDTH 1 +#define SPI_C1_LSBFE(x) (((uint8_t)(((uint8_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) + +/*! + * @} + */ /* 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_WIDTH 5 +#define UART_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))<CS1) +#define WDOG_CS2_REG(base) ((base)->CS2) +#define WDOG_CNT_REG(base) ((base)->CNT) +#define WDOG_CNTH_REG(base) ((base)->CNT8B.CNTH) +#define WDOG_CNTL_REG(base) ((base)->CNT8B.CNTL) +#define WDOG_TOVAL_REG(base) ((base)->TOVAL) +#define WDOG_TOVALH_REG(base) ((base)->TOVAL8B.TOVALH) +#define WDOG_TOVALL_REG(base) ((base)->TOVAL8B.TOVALL) +#define WDOG_WIN_REG(base) ((base)->WIN) +#define WDOG_WINH_REG(base) ((base)->WIN8B.WINH) +#define WDOG_WINL_REG(base) ((base)->WIN8B.WINL) + +/*! + * @} + */ /* end of group WDOG_Register_Accessor_Macros */ + + +/* ---------------------------------------------------------------------------- + -- WDOG Register Masks + ---------------------------------------------------------------------------- */ + +/*! + * @addtogroup WDOG_Register_Masks WDOG Register Masks + * @{ + */ + +/* CS1 Bit Fields */ +#define WDOG_CS1_STOP_MASK 0x1u +#define WDOG_CS1_STOP_SHIFT 0 +#define WDOG_CS1_STOP_WIDTH 1 +#define WDOG_CS1_STOP(x) (((uint8_t)(((uint8_t)(x))< + + +#ifndef DISABLE_WDOG + #define DISABLE_WDOG 1 +#endif + +#ifndef CLOCK_SETUP + #define CLOCK_SETUP 0 +#endif + +/* ICS mode constants */ + +#define ICS_MODE_FEI 0U +#define ICS_MODE_FEE 1U +#define ICS_MODE_FBI 2U +#define ICS_MODE_FBE 3U +#define ICS_MODE_BLPI 4U +#define ICS_MODE_BLPE 5U + +/* Predefined clock setups + 0 ... Internal Clock Source (ICS) in FLL Engaged Internal (FEI) mode + Multipurpose Clock Generator (ICS) in FEI mode. + Reference clock source for ICS module: FLL clock (internal reference) + Core clock = 24MHz + Bus clock = 24MHz + 1 ... Internal Clock Source (ICS) in FLL Engaged External (FEE) mode + Multipurpose Clock Generator (ICS) in FEE mode. + Reference clock source for ICS module: FLL clock (external reference) + Core clock = 40MHz + Bus clock = 20MHz + 2 ... Internal Clock Source (ICS) in Bypassed Low Power Internal (BLPI) mode + Multipurpose Clock Generator (ICS) in BLPI mode. + Reference clock source for ICS module: Internal clock + Core clock = 0.0375MHz + Bus clock = 0.0375MHz + 3 ... Internal Clock Source (ICS) in Bypassed Low Power External (BLPE) mode + Multipurpose Clock Generator (ICS) in BLPE mode. + Reference clock source for ICS module: External clock + Core clock = 8MHz + Bus clock = 8MHz + */ + +/* Define clock source values */ + +#define CPU_XTAL_CLK_HZ 8000000u /* Value of the external crystal or oscillator clock frequency in Hz */ +#define CPU_INT_CLK_HZ 37500u /* Value of the slow internal oscillator clock frequency in Hz */ + + +#if (CLOCK_SETUP == 0) + #define DEFAULT_SYSTEM_CLOCK 24000000u /* Default System clock value */ + #define ICS_MODE ICS_MODE_FEI /* Clock generator mode */ + /* ICS_C1: CLKS=0,RDIV=0,IREFS=1,IRCLKEN=0,IREFSTEN=0 */ + #define ICS_C1_VALUE 0x04U /* ICS_C1 */ + /* ICS_C2: BDIV=1,LP=0 */ + #define ICS_C2_VALUE 0x20U /* ICS_C2 */ + /* ICS_C4: LOLIE=0,CME=0,SCFTRIM=0 */ + #define ICS_C4_VALUE 0x00U /* ICS_C4 */ +/* OSC_CR: OSCEN=0,OSCSTEN=0,OSCOS=0,RANGE=0,HGO=0,OSCINIT=0 */ + #define OSC_CR_VALUE 0x00U /* OSC_CR */ +/* SIM_CLKDIV: OUTDIV1=0,OUTDIV2=0,OUTDIV3=0 */ + #define SIM_CLKDIV_VALUE 0x00U /* SIM_CLKDIV */ +#elif (CLOCK_SETUP == 1) + #define DEFAULT_SYSTEM_CLOCK 40000000u /* Default System clock value */ + #define ICS_MODE ICS_MODE_FEE /* Clock generator mode */ + /* ICS_C1: CLKS=0,RDIV=3,IREFS=0,IRCLKEN=0,IREFSTEN=0 */ + #define ICS_C1_VALUE 0x18U /* ICS_C1 */ + /* ICS_C2: BDIV=0,LP=0 */ + #define ICS_C2_VALUE 0x00U /* ICS_C2 */ + /* ICS_C4: LOLIE=0,CME=0,SCFTRIM=0 */ + #define ICS_C4_VALUE 0x00U /* ICS_C4 */ +/* OSC_CR: OSCEN=1,OSCSTEN=0,OSCOS=1,RANGE=1,HGO=0,OSCINIT=0 */ + #define OSC_CR_VALUE 0x94U /* OSC_CR */ +/* SIM_CLKDIV: OUTDIV1=0,OUTDIV2=1,OUTDIV3=0 */ + #define SIM_CLKDIV_VALUE 0x1000000U /* SIM_CLKDIV */ +#elif (CLOCK_SETUP == 2) + #define DEFAULT_SYSTEM_CLOCK 37500u /* Default System clock value */ + #define ICS_MODE ICS_MODE_BLPI /* Clock generator mode */ + /* ICS_C1: CLKS=1,RDIV=0,IREFS=1,IRCLKEN=1,IREFSTEN=0 */ + #define ICS_C1_VALUE 0x46U /* ICS_C1 */ + /* ICS_C2: BDIV=0,LP=1 */ + #define ICS_C2_VALUE 0x10U /* ICS_C2 */ + /* ICS_C4: LOLIE=0,CME=0,SCFTRIM=0 */ + #define ICS_C4_VALUE 0x00U /* ICS_C4 */ +/* OSC_CR: OSCEN=0,OSCSTEN=0,OSCOS=0,RANGE=0,HGO=0,OSCINIT=0 */ + #define OSC_CR_VALUE 0x00U /* OSC_CR */ +/* SIM_CLKDIV: OUTDIV1=0,OUTDIV2=0,OUTDIV3=0 */ + #define SIM_CLKDIV_VALUE 0x00U /* SIM_CLKDIV */ +#elif (CLOCK_SETUP == 3) + #define DEFAULT_SYSTEM_CLOCK 8000000u /* Default System clock value */ + #define ICS_MODE ICS_MODE_BLPE /* Clock generator mode */ + /* ICS_C1: CLKS=2,RDIV=3,IREFS=0,IRCLKEN=1,IREFSTEN=0 */ + #define ICS_C1_VALUE 0x9AU /* ICS_C1 */ + /* ICS_C2: BDIV=0,LP=1 */ + #define ICS_C2_VALUE 0x10U /* ICS_C2 */ + /* ICS_C4: LOLIE=0,CME=0,SCFTRIM=0 */ + #define ICS_C4_VALUE 0x00U /* ICS_C4 */ +/* OSC_CR: OSCEN=1,OSCSTEN=0,OSCOS=1,RANGE=1,HGO=0,OSCINIT=0 */ + #define OSC_CR_VALUE 0x94U /* OSC_CR */ +/* SIM_CLKDIV: OUTDIV1=0,OUTDIV2=0,OUTDIV3=0 */ + #define SIM_CLKDIV_VALUE 0x00U /* SIM_CLKDIV */ +#endif + + +/** + * @brief System clock frequency (core clock) + * + * The system clock frequency supplied to the SysTick timer and the processor + * core clock. This variable can be used by the user application to setup the + * SysTick timer or configure other parameters. It may also be used by debugger to + * query the frequency of the debug timer or configure the trace clock speed + * SystemCoreClock is initialized with a correct predefined value. + */ +extern uint32_t SystemCoreClock; + +/** + * @brief Setup the microcontroller system. + * + * Typically this function configures the oscillator (PLL) that is part of the + * microcontroller device. For systems with variable clock speed it also updates + * the variable SystemCoreClock. SystemInit is called from startup_device file. + */ +void SystemInit (void); + +/** + * @brief Updates the SystemCoreClock variable. + * + * It must be called whenever the core clock is changed during program + * execution. SystemCoreClockUpdate() evaluates the clock register settings and calculates + * the current core clock. + */ +void SystemCoreClockUpdate (void); + +#ifdef __cplusplus +} +#endif + +#endif /* #if !defined(SYSTEM_SKEAZ1284_H_) */ diff --git a/cpu/kinetis/isr_kinetis.c b/cpu/kinetis/isr_kinetis.c index 2d2429c077..3708e24ecc 100644 --- a/cpu/kinetis/isr_kinetis.c +++ b/cpu/kinetis/isr_kinetis.c @@ -195,17 +195,23 @@ WEAK_DEFAULT void isr_tpm1(void); WEAK_DEFAULT void isr_tpm2(void); WEAK_DEFAULT void isr_tsi0(void); WEAK_DEFAULT void isr_trng0(void); +WEAK_DEFAULT void isr_uart0(void); WEAK_DEFAULT void isr_uart0_err(void); WEAK_DEFAULT void isr_uart0_lon(void); WEAK_DEFAULT void isr_uart0_rx_tx(void); +WEAK_DEFAULT void isr_uart1(void); WEAK_DEFAULT void isr_uart1_err(void); WEAK_DEFAULT void isr_uart1_rx_tx(void); +WEAK_DEFAULT void isr_uart2(void); WEAK_DEFAULT void isr_uart2_err(void); WEAK_DEFAULT void isr_uart2_rx_tx(void); +WEAK_DEFAULT void isr_uart3(void); WEAK_DEFAULT void isr_uart3_err(void); WEAK_DEFAULT void isr_uart3_rx_tx(void); +WEAK_DEFAULT void isr_uart4(void); WEAK_DEFAULT void isr_uart4_err(void); WEAK_DEFAULT void isr_uart4_rx_tx(void); +WEAK_DEFAULT void isr_uart5(void); WEAK_DEFAULT void isr_uart5_err(void); WEAK_DEFAULT void isr_uart5_rx_tx(void); WEAK_DEFAULT void isr_usb0(void); @@ -213,6 +219,8 @@ WEAK_DEFAULT void isr_usbdcd(void); WEAK_DEFAULT void isr_usbhs(void); WEAK_DEFAULT void isr_usbhsdcd(void); WEAK_DEFAULT void isr_wdog_ewm(void); +WEAK_DEFAULT void isr_mscan_rx(void); +WEAK_DEFAULT void isr_mscan_tx(void); /* Empty interrupt vector padding to ensure that all sanity checks in the * linking stage are fulfilled. These will be placed in the area between the @@ -223,4 +231,4 @@ WEAK_DEFAULT void isr_wdog_ewm(void); * tables, or link the table from a different CPU, and catch many other mistakes. */ /* We subtract the expected number of used vectors, which are: The initial stack * pointer + the Cortex-M common IRQs + the Kinetis CPU specific IRQs */ -ISR_VECTOR(99) const isr_t vector_padding[(0x400 / sizeof(isr_t)) - 1 - CPU_NONISR_EXCEPTIONS - CPU_IRQ_NUMOF] = {0}; +ISR_VECTOR(99) const isr_t vector_padding[(0x400 / sizeof(isr_t)) - 1 - CPU_NONISR_EXCEPTIONS - CPU_IRQ_NUMOF] = { 0 }; diff --git a/cpu/kinetis/kinetis-info.mk b/cpu/kinetis/kinetis-info.mk index 51657377e5..aca8caec3b 100644 --- a/cpu/kinetis/kinetis-info.mk +++ b/cpu/kinetis/kinetis-info.mk @@ -122,6 +122,9 @@ else ifeq ($(KINETIS_SERIES),W) # TODO: KW35/36 $(error Unknown Kinetis W) endif +else ifeq ($(KINETIS_SERIES),EA) + KINETIS_RAMSIZE = $(KINETIS_ROMSIZE)/8 + KINETIS_SRAM_L_SIZE = $(KINETIS_RAMSIZE)/4 endif export KINETIS_RAMSIZE export KINETIS_SRAM_L_SIZE diff --git a/cpu/kinetis/periph/gpio.c b/cpu/kinetis/periph/gpio.c index c1ae258a99..2988efd0bc 100644 --- a/cpu/kinetis/periph/gpio.c +++ b/cpu/kinetis/periph/gpio.c @@ -32,6 +32,12 @@ #include "bit.h" #include "periph/gpio.h" +/* Single-port MCU*/ +#if !defined(PORTA_BASE) && defined(PORT_BASE) +# define PORTA_BASE PORT_BASE +# define PORTA PORT +#endif + #ifndef PORT_PCR_ODE_MASK /* For compatibility with Kinetis CPUs without open drain GPIOs (e.g. KW41Z) */ #define PORT_PCR_ODE_MASK 0 @@ -139,6 +145,7 @@ static inline int pin_num(gpio_t pin) } #ifdef MODULE_PERIPH_GPIO_IRQ + /** * @brief Get context for a specific pin */ @@ -175,19 +182,28 @@ static void write_map(int port, int pin, int ctx) static void ctx_clear(int port, int pin) { int ctx = get_ctx(port, pin); + write_map(port, pin, ctx); } #endif /* MODULE_PERIPH_GPIO_IRQ */ static inline void clk_en(gpio_t pin) { +#if defined(SIM_SCGC5_PORTA_SHIFT) bit_set32(&SIM->SCGC5, SIM_SCGC5_PORTA_SHIFT + port_num(pin)); +#else + /* In some cases GPIO is always clocked */ + (void) pin; +#endif + } int gpio_init(gpio_t pin, gpio_mode_t mode) { +#ifdef KINETIS_HAVE_PCR /* set pin to analog mode while configuring it */ gpio_init_port(pin, GPIO_AF_ANALOG); +#endif /* set pin direction */ if (mode & MODE_OUT) { @@ -197,8 +213,10 @@ int gpio_init(gpio_t pin, gpio_mode_t mode) gpio(pin)->PDDR &= ~(1 << pin_num(pin)); } +#ifdef KINETIS_HAVE_PCR /* enable GPIO function */ port(pin)->PCR[pin_num(pin)] = (GPIO_AF_GPIO | (mode & MODE_PCR_MASK)); +#endif return 0; } @@ -207,6 +225,7 @@ void gpio_init_port(gpio_t pin, uint32_t pcr) /* enable PORT clock in case it was not active before */ clk_en(pin); +#ifdef KINETIS_HAVE_PCR #ifdef MODULE_PERIPH_GPIO_IRQ /* if the given interrupt was previously configured as interrupt source, we * need to free its interrupt context. We to this only after we @@ -223,6 +242,9 @@ void gpio_init_port(gpio_t pin, uint32_t pcr) ctx_clear(port_num(pin), pin_num(pin)); } #endif /* MODULE_PERIPH_GPIO_IRQ */ +#else + (void) pcr; +#endif /* KINETIS_HAVE_PCR */ } int gpio_read(gpio_t pin) diff --git a/cpu/kinetis/periph/ics.c b/cpu/kinetis/periph/ics.c new file mode 100644 index 0000000000..4c3478f3f8 --- /dev/null +++ b/cpu/kinetis/periph/ics.c @@ -0,0 +1,203 @@ +/* +** ################################################################### +** Compilers: Keil ARM C/C++ Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** GNU C Compiler - CodeSourcery Sourcery G++ +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manual: KEA128RM, Rev. 22, Jun 2014 +** Version: rev. 1.4, 2015-07-24 +** Build: b150730 +** +** Abstract: +** Provides a system configuration function and a global variable that +** contains the system frequency. It configures the device and initializes +** the oscillator (PLL) that is part of the microcontroller device. +** +** Copyright (c) 2015 Freescale Semiconductor, Inc. +** All rights reserved. +** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** +** o Redistributions of source code must retain the above copyright notice, this list +** of conditions and the following disclaimer. +** +** o Redistributions in binary form must reproduce the above copyright notice, this +** list of conditions and the following disclaimer in the documentation and/or +** other materials provided with the distribution. +** +** o Neither the name of Freescale Semiconductor, Inc. nor the names of its +** contributors may be used to endorse or promote products derived from this +** software without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2013-07-30) +** Initial version. +** - rev. 1.1 (2013-10-29) +** Definition of BITBAND macros updated to support peripherals with 32-bit acces disabled. +** - rev. 1.2 (2014-01-10) +** CAN - Corrected address of TSIDR1 register. +** CAN - Corrected name of MSCAN_TDLR bit DLC to TDLC. +** FTM0 - Added access macro for EXTTRIG register. +** NVIC - Registers access macros improved. +** SCB - Unused bits removed, mask, shift macros improved. +** Defines of interrupt vectors aligned to RM. +** - rev. 1.3 (2014-06-18) +** The declaration of clock configurations has been moved to separate header file system_MKE02Z2.h +** Module access macro {module}_BASES replaced by {module}_BASE_PTRS. +** I2C - Renamed status register S to S1 to match RM naming. +** Renamed interrupts: INT_PMC to INT_LVD_LVW, INT_ADC to ADC0,INT_WDOG to INT_Watchdog. +** - rev. 1.4 (2015-07-24) +** Correction of backward compatibility. +** +** ################################################################### +*/ + +/** + * @defgroup cpu_kinetis_ics Kinetis ICS + * @ingroup cpu_kinetis + * @brief Implementation of the Kinetis internal clock source controller + * (ICS) driver + * + * @{ + * + * @file + * @brief ICS and watchdog initialization code + * + * Originates from NXP's examples (called system_SKEAZ1284.c there) + * + */ + +#include +#include "cpu.h" + + + +/* ---------------------------------------------------------------------------- + -- Core clock + ---------------------------------------------------------------------------- */ + +uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK; + +/* ---------------------------------------------------------------------------- + -- SystemInit() + ---------------------------------------------------------------------------- */ + +void SystemDisableWatchdog(void) +{ + /* WDOG->TOVAL: TOVAL=0xE803 */ + WDOG->TOVAL = WDOG_TOVAL_TOVAL(0xE803); /* Timeout value */ + /* WDOG->CS2: WIN=0,FLG=0,?=0,PRES=0,?=0,?=0,CLK=1 */ + WDOG->CS2 = WDOG_CS2_CLK(0x01); /* 1-kHz clock source */ + /* WDOG->CS1: EN=0,INT=0,UPDATE=1,TST=0,DBG=0,WAIT=1,STOP=1 */ + WDOG->CS1 = WDOG_CS1_UPDATE_MASK | + WDOG_CS1_TST(0x00) | + WDOG_CS1_WAIT_MASK | + WDOG_CS1_STOP_MASK; +} + +void SystemInit(void) +{ + +#if ((__FPU_PRESENT == 1) && (__FPU_USED == 1)) + SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10, CP11 Full Access */ +#endif /* ((__FPU_PRESENT == 1) && (__FPU_USED == 1)) */ + +#if (CLOCK_SETUP) + /* System clock initialization */ + + /* Set system prescalers and clock sources */ + SIM->CLKDIV = SIM_CLKDIV_VALUE; /* Set system prescalers */ + ICS->C2 = ((ICS->C2) & (uint32_t)(~(ICS_C2_BDIV_MASK))) | ((ICS_C2_VALUE) &(ICS_C2_BDIV_MASK)); /* Set system prescaler */ +#if (ICS_MODE == ICS_MODE_FEI || ICS_MODE == ICS_MODE_FBI || ICS_MODE == ICS_MODE_BLPI) + ICS->C1 = ICS_C1_VALUE; /* Set C1 (clock source selection, int. reference enable etc.) */ + ICS->C2 = ICS_C2_VALUE; /* Set C2 (ext. and int. reference clock selection) */ + ICS->C4 = ICS_C4_VALUE; /* Set C4 (loss of lock interrupt, clock monitor) */ + OSC->CR = OSC_CR_VALUE; /* Set OSC_CR (OSCERCLK disable) */ +#else /* ICS_MODE */ + /* Set ICS and OSC */ + ICS->C2 = ICS_C2_VALUE; /* Set C2 (ext. and int. reference clock selection) */ + OSC->CR = OSC_CR_VALUE; /* Set OSC_CR (OSCERCLK enable, range select) */ + ICS->C4 = ICS_C4_VALUE; /* Set C4 (loss of lock interrupt, clock monitor) */ + ICS->C1 = ICS_C1_VALUE; /* Set C1 (clock source selection, int. reference disable etc.) */ + if (((OSC_CR_VALUE) &OSC_CR_OSCEN_MASK) != 0U) { + while ((OSC->CR & OSC_CR_OSCINIT_MASK) == 0x00U) { /* Check that the oscillator is running */ + } + } +#endif /* ICS_MODE */ + + /* Common for all ICS modes */ + +#if (ICS_MODE == ICS_MODE_FEI || ICS_MODE == ICS_MODE_FEE) + while ((ICS->S & ICS_S_CLKST_MASK) != 0x00U) { /* Wait until output of FLL is selected */ + } +#elif (ICS_MODE == ICS_MODE_FBI || ICS_MODE == ICS_MODE_BLPI) + while ((ICS->S & ICS_S_CLKST_MASK) != 0x04U) { /* Wait until FLL bypassed, internal reference clock is selected */ + } +#elif (ICS_MODE == ICS_MODE_FBE || ICS_MODE == ICS_MODE_BLPE) + while ((ICS->S & ICS_S_CLKST_MASK) != 0x08U) { /* Wait until FLL bypassed, external reference clock is selected */ + } +#endif +#endif /* (CLOCK_SETUP) */ +} + +/* ---------------------------------------------------------------------------- + -- SystemCoreClockUpdate() + ---------------------------------------------------------------------------- */ + +void SystemCoreClockUpdate(void) +{ + + uint32_t ICSOUTClock; /* Variable to store output clock frequency of the ICS module */ + uint8_t Divider; + + if ((ICS->C1 & ICS_C1_CLKS_MASK) == 0x0u) { + /* Output of FLL is selected */ + if ((ICS->C1 & ICS_C1_IREFS_MASK) == 0x0u) { + /* External reference clock is selected */ + ICSOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives ICS clock */ + Divider = (uint8_t)(1u << ((ICS->C1 & ICS_C1_RDIV_MASK) >> ICS_C1_RDIV_SHIFT)); + ICSOUTClock = (ICSOUTClock / Divider); /* Calculate the divided FLL reference clock */ + if ((OSC->CR & OSC_CR_RANGE_MASK) != 0x0u) { + ICSOUTClock /= 32u; /* If high range is enabled, additional 32 divider is active */ + } + } + else { + ICSOUTClock = CPU_INT_CLK_HZ; /* The internal reference clock is selected */ + } + ICSOUTClock *= 1280u; /* Apply 1280 FLL multiplier */ + } + else if ((ICS->C1 & ICS_C1_CLKS_MASK) == 0x40u) { + /* Internal reference clock is selected */ + ICSOUTClock = CPU_INT_CLK_HZ; + } + else if ((ICS->C1 & ICS_C1_CLKS_MASK) == 0x80u) { + /* External reference clock is selected */ + ICSOUTClock = CPU_XTAL_CLK_HZ; + } + else { + /* Reserved value */ + return; + } + ICSOUTClock = ICSOUTClock >> ((ICS->C2 & ICS_C2_BDIV_MASK) >> ICS_C2_BDIV_SHIFT); + SystemCoreClock = (ICSOUTClock / (1u + ((SIM->CLKDIV & SIM_CLKDIV_OUTDIV1_MASK) >> SIM_CLKDIV_OUTDIV1_SHIFT))); + +} + +/** @} */ diff --git a/cpu/kinetis/periph/timer.c b/cpu/kinetis/periph/timer.c index 021c6bee3e..3c65d2a249 100644 --- a/cpu/kinetis/periph/timer.c +++ b/cpu/kinetis/periph/timer.c @@ -67,6 +67,7 @@ typedef struct { uint32_t ldval; } pit_t; +#ifdef KINETIS_HAVE_LPTMR /* LPTMR state */ typedef struct { timer_isr_ctx_t isr_ctx; @@ -74,21 +75,31 @@ typedef struct { uint32_t cmr; uint32_t running; } lptmr_t; +#endif static const pit_conf_t pit_config[PIT_NUMOF] = PIT_CONFIG; +#ifdef KINETIS_HAVE_LPTMR static const lptmr_conf_t lptmr_config[LPTMR_NUMOF] = LPTMR_CONFIG; +#endif static pit_t pit[PIT_NUMOF]; +#ifdef KINETIS_HAVE_LPTMR static lptmr_t lptmr[LPTMR_NUMOF]; +#endif /** * @brief Find out whether a given timer is a LPTMR or a PIT timer */ -static inline unsigned int _timer_variant(tim_t dev) { +static inline unsigned int _timer_variant(tim_t dev) +{ +#ifdef KINETIS_HAVE_LPTMR if ((unsigned int) dev >= PIT_NUMOF) { return TIMER_LPTMR; } - else { + else +#endif + { + (void) dev; return TIMER_PIT; } } @@ -96,21 +107,25 @@ static inline unsigned int _timer_variant(tim_t dev) { /** * @brief Find device index in the pit_config array */ -static inline unsigned int _pit_index(tim_t dev) { +static inline unsigned int _pit_index(tim_t dev) +{ return ((unsigned int)dev) - TIMER_DEV(0); } /** * @brief Get TIMER_x enum value from PIT device index */ -static inline tim_t _pit_tim_t(uint8_t dev) { +static inline tim_t _pit_tim_t(uint8_t dev) +{ return (tim_t)(((unsigned int)TIMER_DEV(0)) + dev); } +#ifdef KINETIS_HAVE_LPTMR /** * @brief Find device index in the lptmr_config array */ -static inline unsigned int _lptmr_index(tim_t dev) { +static inline unsigned int _lptmr_index(tim_t dev) +{ return ((unsigned int)dev) - TIMER_DEV(0) - PIT_NUMOF; } @@ -118,10 +133,12 @@ static inline unsigned int _lptmr_index(tim_t dev) { /** * @brief Get TIMER_x enum value from LPTMR device index */ -static inline tim_t _lptmr_tim_t(uint8_t dev) { +static inline tim_t _lptmr_tim_t(uint8_t dev) +{ return (tim_t)(((unsigned int)TIMER_DEV(0)) + PIT_NUMOF + dev); } #endif /* defined(LPTMR_ISR_0) || defined(LPTMR_ISR_1) */ +#endif /* KINETIS_HAVE_LPTMR */ /* ****** PIT module functions ****** */ @@ -209,6 +226,7 @@ static inline int pit_set_absolute(uint8_t dev, uint32_t target) unsigned int mask = irq_disable(); uint32_t now = pit[dev].count - PIT->CHANNEL[ch].CVAL; uint32_t offset = target - now; + /* Set new timeout */ PIT->CHANNEL[ch].TCTRL = 0; PIT->CHANNEL[ch].LDVAL = offset; @@ -228,6 +246,7 @@ static inline int pit_clear(uint8_t dev) uint8_t ch = pit_config[dev].count_ch; /* Disable IRQs to minimize the number of lost ticks */ unsigned int mask = irq_disable(); + /* Subtract if there was anything left on the counter */ pit[dev].count -= PIT->CHANNEL[ch].CVAL; /* No need to add PIT_MAX_VALUE + 1 to the counter because of modulo 2**32 */ @@ -247,18 +266,21 @@ static inline int pit_clear(uint8_t dev) static inline uint32_t pit_read(uint8_t dev) { uint8_t ch = pit_config[dev].count_ch; + return pit[dev].count - PIT->CHANNEL[ch].CVAL; } static inline void pit_start(uint8_t dev) { uint8_t ch = pit_config[dev].prescaler_ch; + PIT->CHANNEL[ch].TCTRL = PIT_TCTRL_TEN_MASK; } static inline void pit_stop(uint8_t dev) { uint8_t ch = pit_config[dev].prescaler_ch; + PIT->CHANNEL[ch].TCTRL = 0; } @@ -266,6 +288,7 @@ static inline void pit_irq_handler(tim_t dev) { uint8_t ch = pit_config[_pit_index(dev)].count_ch; pit_t *pit_ctx = &pit[_pit_index(dev)]; + if (!PIT->CHANNEL[ch].TFLG) { DEBUG("PIT%u!TFLG\n", (unsigned)dev); return; @@ -286,6 +309,7 @@ static inline void pit_irq_handler(tim_t dev) cortexm_isr_end(); } +#ifdef KINETIS_HAVE_LPTMR /* ****** LPTMR module functions ****** */ /* Forward declarations */ @@ -310,13 +334,15 @@ static inline void _lptmr_set_cb_config(uint8_t dev, timer_cb_t cb, void *arg) /** * @brief Compute the LPTMR prescaler setting, see reference manual for details */ -static inline int32_t _lptmr_compute_prescaler(uint8_t dev, uint32_t freq) { +static inline int32_t _lptmr_compute_prescaler(uint8_t dev, uint32_t freq) +{ uint32_t prescale = 0; + if ((freq > lptmr_config[dev].base_freq) || (freq == 0)) { /* Frequency out of range */ return -1; } - while (freq < lptmr_config[dev].base_freq){ + while (freq < lptmr_config[dev].base_freq) { ++prescale; freq <<= 1; } @@ -336,6 +362,7 @@ static inline int32_t _lptmr_compute_prescaler(uint8_t dev, uint32_t freq) { static inline int lptmr_init(uint8_t dev, uint32_t freq, timer_cb_t cb, void *arg) { int32_t prescale = _lptmr_compute_prescaler(dev, freq); + if (prescale < 0) { return -1; } @@ -373,6 +400,7 @@ static inline int lptmr_init(uint8_t dev, uint32_t freq, timer_cb_t cb, void *ar static inline uint16_t lptmr_read(uint8_t dev) { LPTMR_Type *hw = lptmr_config[dev].dev; + /* latch the current timer value into CNR */ hw->CNR = 0; return lptmr[dev].cnr + hw->CNR; @@ -386,6 +414,7 @@ static inline uint16_t lptmr_read(uint8_t dev) static inline void lptmr_reload_or_spin(uint8_t dev, uint16_t timeout) { LPTMR_Type *hw = lptmr_config[dev].dev; + /* Disable timer and set target, 1 to 2 ticks will be dropped by the * hardware during the disable-enable cycle */ /* Disable the timer interrupt first */ @@ -420,6 +449,7 @@ static inline int lptmr_set(uint8_t dev, uint16_t timeout) LPTMR_Type *hw = lptmr_config[dev].dev; /* Disable IRQs to minimize jitter */ unsigned int mask = irq_disable(); + lptmr[dev].running = 1; if (!(hw->CSR & LPTMR_CSR_TEN_MASK)) { /* Timer is stopped, only update target */ @@ -453,6 +483,7 @@ static inline int lptmr_set_absolute(uint8_t dev, uint16_t target) LPTMR_Type *hw = lptmr_config[dev].dev; /* Disable IRQs to minimize jitter */ unsigned int mask = irq_disable(); + lptmr[dev].running = 1; if (!(hw->CSR & LPTMR_CSR_TEN_MASK)) { /* Timer is stopped, only update target */ @@ -487,6 +518,7 @@ static inline int lptmr_clear(uint8_t dev) /* Disable IRQs to minimize jitter */ LPTMR_Type *hw = lptmr_config[dev].dev; unsigned int mask = irq_disable(); + if (!lptmr[dev].running) { /* Already clear */ irq_restore(mask); @@ -509,6 +541,7 @@ static inline int lptmr_clear(uint8_t dev) static inline void lptmr_start(uint8_t dev) { LPTMR_Type *hw = lptmr_config[dev].dev; + if (hw->CSR & LPTMR_CSR_TEN_MASK) { /* Timer is running */ return; @@ -539,6 +572,7 @@ static inline void lptmr_stop(uint8_t dev) /* Disable IRQs to avoid race with ISR */ unsigned int mask = irq_disable(); LPTMR_Type *hw = lptmr_config[dev].dev; + if (!(hw->CSR & LPTMR_CSR_TEN_MASK)) { /* Timer is already stopped */ return; @@ -582,6 +616,7 @@ static inline void lptmr_irq_handler(tim_t tim) } #endif /* defined(LPTMR_ISR_0) || defined(LPTMR_ISR_1) */ +#endif /* ****** Common timer API functions ****** */ int timer_init(tim_t dev, unsigned long freq, timer_cb_t cb, void *arg) @@ -594,8 +629,10 @@ int timer_init(tim_t dev, unsigned long freq, timer_cb_t cb, void *arg) switch (_timer_variant(dev)) { case TIMER_PIT: return pit_init(_pit_index(dev), freq, cb, arg); +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: return lptmr_init(_lptmr_index(dev), freq, cb, arg); +#endif default: return -1; } @@ -615,8 +652,10 @@ int timer_set(tim_t dev, int channel, unsigned int timeout) switch (_timer_variant(dev)) { case TIMER_PIT: return pit_set(_pit_index(dev), timeout); +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: return lptmr_set(_lptmr_index(dev), timeout); +#endif default: return -1; } @@ -636,8 +675,10 @@ int timer_set_absolute(tim_t dev, int channel, unsigned int target) switch (_timer_variant(dev)) { case TIMER_PIT: return pit_set_absolute(_pit_index(dev), target); +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: - return lptmr_set_absolute(_lptmr_index(dev), target);; + return lptmr_set_absolute(_lptmr_index(dev), target); +#endif default: return -1; } @@ -659,8 +700,10 @@ int timer_clear(tim_t dev, int channel) switch (_timer_variant(dev)) { case TIMER_PIT: return pit_clear(_pit_index(dev)); +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: return lptmr_clear(_lptmr_index(dev)); +#endif default: return -1; } @@ -678,8 +721,10 @@ unsigned int timer_read(tim_t dev) switch (_timer_variant(dev)) { case TIMER_PIT: return pit_read(_pit_index(dev)); +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: return lptmr_read(_lptmr_index(dev)); +#endif default: return 0; } @@ -696,9 +741,11 @@ void timer_start(tim_t dev) case TIMER_PIT: pit_start(_pit_index(dev)); return; +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: lptmr_start(_lptmr_index(dev)); return; +#endif default: return; } @@ -715,9 +762,11 @@ void timer_stop(tim_t dev) case TIMER_PIT: pit_stop(_pit_index(dev)); return; +#ifdef KINETIS_HAVE_LPTMR case TIMER_LPTMR: lptmr_stop(_lptmr_index(dev)); return; +#endif default: return; } diff --git a/cpu/kinetis/periph/wdog.c b/cpu/kinetis/periph/wdog.c index 816b5bd766..c15808bb70 100644 --- a/cpu/kinetis/periph/wdog.c +++ b/cpu/kinetis/periph/wdog.c @@ -27,13 +27,19 @@ #include "cpu_conf.h" #include "periph_conf.h" -#ifndef KINETIS_WDOG_ADVANCED /** * Attempts to determine the type of the WDOG, * using the WDOG_STCTRLH_CLKSRC_MASK field. */ +#ifndef KINETIS_WDOG_ADVANCED_MK #ifdef WDOG_STCTRLH_CLKSRC_MASK -#define KINETIS_WDOG_ADVANCED 1 +# define KINETIS_WDOG_ADVANCED_MK 1 +#endif +#endif + +#ifndef KINETIS_WDOG_ADVANCED_EA +#ifdef WDOG_CS1_STOP_MASK +# define KINETIS_WDOG_ADVANCED_EA 1 #endif #endif @@ -61,7 +67,7 @@ */ void wdog_disable(void) { -#if KINETIS_WDOG_ADVANCED +#if KINETIS_WDOG_ADVANCED_MK /* unlock and disable the WDOG */ WDOG->UNLOCK = (uint16_t)0xc520; WDOG->UNLOCK = (uint16_t)0xd928; @@ -69,6 +75,9 @@ void wdog_disable(void) | WDOG_STCTRLH_STOPEN_MASK | WDOG_STCTRLH_ALLOWUPDATE_MASK | WDOG_STCTRLH_CLKSRC_MASK); +#elif KINETIS_WDOG_ADVANCED_EA + extern void SystemDisableWatchdog(void); + SystemDisableWatchdog(); #else /* disable the COP WDOG */ SIM->COPC = (uint32_t)0x00u; diff --git a/cpu/kinetis/vectors.c b/cpu/kinetis/vectors.c index 08b449ea99..a60cb3554e 100644 --- a/cpu/kinetis/vectors.c +++ b/cpu/kinetis/vectors.c @@ -187,32 +187,56 @@ ISR_VECTOR(1) const isr_t vector_cpu[CPU_IRQ_NUMOF] = { [I2S0_Rx_IRQn ] = isr_i2s0_rx, /* I2S0 receive interrupt */ #endif #ifdef UART0 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART0_IRQn] = isr_uart0, /* UART0 interrupt */ +#else #ifdef UART_RPL_RPL_MASK [UART0_LON_IRQn ] = isr_uart0_lon, /* UART0 LON interrupt */ #endif [UART0_RX_TX_IRQn] = isr_uart0_rx_tx, /* UART0 Receive/Transmit interrupt */ [UART0_ERR_IRQn ] = isr_uart0_err, /* UART0 Error interrupt */ #endif +#endif #ifdef UART1 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART1_IRQn] = isr_uart1, /* UART1 interrupt */ +#else [UART1_RX_TX_IRQn] = isr_uart1_rx_tx, /* UART1 Receive/Transmit interrupt */ [UART1_ERR_IRQn ] = isr_uart1_err, /* UART1 Error interrupt */ #endif +#endif #ifdef UART2 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART2_IRQn] = isr_uart2, /* UART2 interrupt */ +#else [UART2_RX_TX_IRQn] = isr_uart2_rx_tx, /* UART2 Receive/Transmit interrupt */ [UART2_ERR_IRQn ] = isr_uart2_err, /* UART2 Error interrupt */ #endif +#endif #ifdef UART3 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART3_IRQn] = isr_uart3, /* UART3 interrupt */ +#else [UART3_RX_TX_IRQn] = isr_uart3_rx_tx, /* UART3 Receive/Transmit interrupt */ [UART3_ERR_IRQn ] = isr_uart3_err, /* UART3 Error interrupt */ #endif +#endif #ifdef UART4 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART4_IRQn] = isr_uart4, /* UART4 interrupt */ +#else [UART4_RX_TX_IRQn] = isr_uart4_rx_tx, /* UART4 Receive/Transmit interrupt */ [UART4_ERR_IRQn ] = isr_uart4_err, /* UART4 Error interrupt */ #endif +#endif #ifdef UART5 +#ifdef KINETIS_SINGLE_UART_IRQ + [UART5_IRQn] = isr_uart5, /* UART5 interrupt */ +#else [UART5_RX_TX_IRQn] = isr_uart5_rx_tx, /* UART5 Receive/Transmit interrupt */ [UART5_ERR_IRQn ] = isr_uart5_err, /* UART5 Error interrupt */ #endif +#endif #ifdef ADC0 [ADC0_IRQn ] = isr_adc0, /* ADC0 interrupt */ #endif @@ -251,11 +275,18 @@ ISR_VECTOR(1) const isr_t vector_cpu[CPU_IRQ_NUMOF] = { #endif #ifdef RTC [RTC_IRQn ] = isr_rtc, /* RTC interrupt */ +# ifndef KINETIS_SERIES_EA [RTC_Seconds_IRQn] = isr_rtc_seconds, /* RTC seconds interrupt */ +# endif #endif #ifdef PIT #ifdef KINETIS_CORE_Z +# ifdef KINETIS_SERIES_EA + [PIT0_IRQn ] = isr_pit0, /* PIT timer channel 0 interrupt */ + [PIT1_IRQn ] = isr_pit1, /* PIT timer channel 1 interrupt */ +# else [PIT_IRQn ] = isr_pit, /* PIT any channel interrupt */ +#endif #else [PIT0_IRQn ] = isr_pit0, /* PIT timer channel 0 interrupt */ [PIT1_IRQn ] = isr_pit1, /* PIT timer channel 1 interrupt */ @@ -324,6 +355,10 @@ ISR_VECTOR(1) const isr_t vector_cpu[CPU_IRQ_NUMOF] = { [CAN1_Rx_Warning_IRQn] = isr_can1_rx_warning, /* CAN1 Rx warning interrupt */ [CAN1_Wake_Up_IRQn] = isr_can1_wake_up, /* CAN1 wake up interrupt */ #endif +#ifdef MSCAN + [MSCAN_RX_IRQn] = isr_mscan_rx, /* MSCAN RX interrupt */ + [MSCAN_TX_IRQn] = isr_mscan_tx, /* MSCAN TX/Err/Wake-up interrupt */ +#endif #ifdef SDHC [SDHC_IRQn ] = isr_sdhc, /* SDHC interrupt */ #endif