summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-25 09:06:58 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-25 09:06:58 -0600
commitd95a14c353c187499be8a633f88525c8f61988d5 (patch)
treeaa56d35dd18bedb46db51b80a7cc7f73f469f1e2 /nuttx
parent7a45a69800188774ffa2988aab98832462fe7cdf (diff)
downloadpx4-nuttx-d95a14c353c187499be8a633f88525c8f61988d5.tar.gz
px4-nuttx-d95a14c353c187499be8a633f88525c8f61988d5.tar.bz2
px4-nuttx-d95a14c353c187499be8a633f88525c8f61988d5.zip
KL25Z: Fix some memory mapp and register definitions; no UART3-5
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/arm/include/kl/chip.h1
-rw-r--r--nuttx/arch/arm/src/kl/Kconfig21
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_memorymap.h105
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_sim.h478
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_uart.h366
-rw-r--r--nuttx/arch/arm/src/kl/kl_clockconfig.c2
-rw-r--r--nuttx/arch/arm/src/kl/kl_config.h75
-rw-r--r--nuttx/arch/arm/src/kl/kl_lowputc.c118
-rw-r--r--nuttx/arch/arm/src/kl/kl_serial.c232
10 files changed, 262 insertions, 1140 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 1fd2571a7..916e750fc 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4615,3 +4615,7 @@
Modify out PLL configuration so that it uses the values in
board.h; Fix PLL settings in board.h so that the correct core
and bus clock frequencies are generated. (2014-4-24).
+ * arm/src/kl/chip/kl_memorymap.h, kl_sim.h, andkl_uart.h: Correct some
+ register definitions (2014-4-25).
+ * arch/arm/src/kl/Kconfig, kl_lowputc.c, kl_serial.c, and kl_config.h:
+ No UART3-5 (2014-4-25).
diff --git a/nuttx/arch/arm/include/kl/chip.h b/nuttx/arch/arm/include/kl/chip.h
index 56bd0588c..d235dda57 100644
--- a/nuttx/arch/arm/include/kl/chip.h
+++ b/nuttx/arch/arm/include/kl/chip.h
@@ -63,7 +63,6 @@
# undef KL_NSDHC /* No SD host controller */
# define KL_NTOUCHIF 1 /* Xtrinsic touch sensing interface */
# define KL_NI2C 2 /* Two I2C modules */
-# undef KL_NISO7816 /* No UART with ISO-786 */
# define KL_NUART 3 /* Three UARTs */
# define KL_NSPI 2 /* Two SPI modules */
# undef KL_NCAN /* No CAN in 64-pin chips */
diff --git a/nuttx/arch/arm/src/kl/Kconfig b/nuttx/arch/arm/src/kl/Kconfig
index 3da807cf0..289387a29 100644
--- a/nuttx/arch/arm/src/kl/Kconfig
+++ b/nuttx/arch/arm/src/kl/Kconfig
@@ -57,27 +57,6 @@ config KL_UART2
---help---
Support UART2
-config KL_UART3
- bool "UART3"
- default n
- select ARCH_HAVE_UART3
- ---help---
- Support UART3
-
-config KL_UART4
- bool "UART4"
- default n
- select ARCH_HAVE_UART4
- ---help---
- Support UART4
-
-config KL_UART5
- bool "UART5"
- default n
- select ARCH_HAVE_UART5
- ---help---
- Support UART5
-
config KL_ENET
bool "Ethernet"
default n
diff --git a/nuttx/arch/arm/src/kl/chip/kl_memorymap.h b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
index 86529d85d..19e809310 100644
--- a/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
+++ b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
@@ -59,64 +59,38 @@
* K40P144M100SF2RM
*/
-# define KL_FLASH_BASE 0x00000000 /* –0x0fffffff Program flash and read-
+# define KL_FLASH_BASE 0x00000000 /* -0x0fffffff Program flash and read-
* only data (Includes exception
* vectors in first 1024 bytes) */
-# define KL_SRAML_BASE 0x18000000 /* –0x1fffffff SRAM_L: Lower SRAM
+# define KL_SRAML_BASE 0x18000000 /* -0x1fffffff SRAM_L: Lower SRAM
* (ICODE/DCODE) */
-# define KL_SRAMU_BASE 0x20000000 /* –0x200fffff SRAM_U: Upper SRAM bitband
+# define KL_SRAMU_BASE 0x20000000 /* -0x200fffff SRAM_U: Upper SRAM bitband
* region */
- /* 0x20100000 * –0x21ffffff Reserved */
-# define KL_SALIAS_BASE 0x22000000 /* –0x23ffffff Aliased to SRAM_U bitband */
- /* 0x24000000 * –0x3fffffff Reserved */
-# define KL_BRIDGE0_BASE 0x40000000 /* –0x4007ffff Bitband region for peripheral
- * bridge 0 (AIPS-Lite0) */
-# define KL_BRIDGE1_BASE 0x40080000 /* –0x400fffff Bitband region for peripheral
- * bridge 1 (AIPS-Lite1) */
-# define KL_GPIOBB_BASE 0x400ff000 /* –0x400fffff Bitband region for general
- * purpose input/output (GPIO) */
- /* 0x40100000 * –0x41ffffff Reserved */
-# define KL_PALIAS_BASE 0x42000000 /* –0x43ffffff Aliased to peripheral bridge
- * (AIPS-Lite) and general purpose
- * input/output (GPIO) bitband */
- /* 0x44000000 * –0x5fffffff Reserved */
-# define KL_FLEXBUS_WBBASE 0x60000000 /* –0x7fffffff FlexBus (External Memory -
- * Write-back) */
-# define KL_FLEXBUS_WTBASE 0x80000000 /* –0x9fffffff FlexBus (External Memory -
- * Write-through) */
-# define KL_FLEXBUS_NXBASE 0xa0000000 /* –0xdfffffff FlexBus (External Memory -
- * Non-executable) */
-# define KL_PERIPH_BASE 0xe0000000 /* –0xe00fffff Private peripherals */
- /* 0xe0100000 * –0xffffffff Reserved */
-
-/* Peripheral Bridge 0 Memory Map ***************************************************/
-
-# define KL_AIPS0_BASE 0x40000000 /* Peripheral bridge 0 (AIPS-Lite 0) */
-# define KL_XBAR_BASE 0x40004000 /* Crossbar switch */
+ /* 0x20100000 * -0x3fffffff Reserved */
+# define KIP_APS_BASE 0x40000000 /* -0x4007ffff AIPS Peripherals */
+ /* 0x40080000 * -0x400fffff Reserved */
+# define KL_GPIO_BASE 0x400ff000 /* -0x400fffff General purpose input/output (GPIO) */
+ /* 0x40100000 * -0x43ffffff Reserved */
+# define KL_BME_BASE 0x44000000 /* -0x5fffffff Bit Manipulation Engine (BME) access
+ * to AIPS Peripherals for slots 0-127 */
+ /* 0x60000000 * -0xdfffffff Reserved */
+# define KL_PERIPH_BASE 0xe0000000 /* -0xe00fffff Private peripherals */
+ /* 0xe0100000 * -0xefffffff Reserved */
+# define KL_MTB_BASE 0xf0000000 /* -0xffffffff Micro Trace Buffer (MTB) registers */
+
+/* API Memory Map *******************************************************************/
+
# define KL_DMAC_BASE 0x40008000 /* DMA controller */
-# define KL_DMADESC_BASE 0x40009000 /* DMA controller transfer control descriptors */
-# define KL_FLEXBUSC_BASE 0x4000c000 /* FlexBus controller */
-# define KL_MPU_BASE 0x4000d000 /* MPU */
-# define KL_FMC_BASE 0x4001f000 /* Flash memory controller */
+# define KL_AIPGPIO_BASE 0x4000f000 /* GPIO controller (aliased to 0x400f_000) */
# define KL_FTFL_BASE 0x40020000 /* Flash memory */
# define KL_DMAMUX0_BASE 0x40021000 /* DMA channel mutiplexer 0 */
-# define KL_CAN0_BASE 0x40024000 /* FlexCAN 0 */
-# define KL_SPI0_BASE 0x4002c000 /* SPI 0 */
-# define KL_SPI1_BASE 0x4002d000 /* SPI 1 */
-# define KL_I2S0_BASE 0x4002f000 /* I2S 0 */
-# define KL_CRC_BASE 0x40032000 /* CRC */
-# define KL_USBDCD_BASE 0x40035000 /* USB DCD */
-# define KL_PDB0_BASE 0x40036000 /* Programmable delay block */
# define KL_PIT_BASE 0x40037000 /* Periodic interrupt timers (PIT) */
-# define KL_FTM0_BASE 0x40038000 /* FlexTimer 0 */
-# define KL_FTM1_BASE 0x40039000 /* FlexTimer 1 */
+# define KL_TPM0_BASE 0x40038000 /* Timer/PWM (TPM) 0 */
+# define KL_TPM1_BASE 0x40039000 /* Timer/PWM (TPM) 1 */
# define KL_ADC0_BASE 0x4003b000 /* Analog-to-digital converter (ADC) 0 */
# define KL_RTC_BASE 0x4003d000 /* Real time clock */
-# define KL_VBATR_BASE 0x4003e000 /* VBAT register file */
+# define KL_DAC0_BASE 0x4003f000 /* Digital-to-analog convert (DAC) 0 */
# define KL_LPTMR_BASE 0x40040000 /* Low power timer */
-# define KL_SYSR_BASE 0x40041000 /* System register file */
-# define KL_DRYICE_BASE 0x40042000 /* DryIce */
-# define KL_DRYICESS_BASE 0x40043000 /* DryIce secure storage */
# define KL_TSI0_BASE 0x40045000 /* Touch sense interface */
# define KL_SIMLP_BASE 0x40047000 /* SIM low-power logic */
# define KL_SIM_BASE 0x40048000 /* System integration module (SIM) */
@@ -126,9 +100,6 @@
# define KL_PORTC_BASE 0x4004b000 /* Port C multiplexing control */
# define KL_PORTD_BASE 0x4004c000 /* Port D multiplexing control */
# define KL_PORTE_BASE 0x4004d000 /* Port E multiplexing control */
-# define KL_WDOG_BASE 0x40052000 /* Software watchdog */
-# define KL_EWM_BASE 0x40061000 /* External watchdog */
-# define KL_CMT_BASE 0x40062000 /* Carrier modulator timer (CMT) */
# define KL_MCG_BASE 0x40064000 /* Multi-purpose Clock Generator (MCG) */
# define KL_OSC_BASE 0x40065000 /* System oscillator (OSC) */
# define KL_I2C0_BASE 0x40066000 /* I2C 0 */
@@ -136,32 +107,16 @@
# define KL_UART0_BASE 0x4006a000 /* UART0 */
# define KL_UART1_BASE 0x4006b000 /* UART1 */
# define KL_UART2_BASE 0x4006c000 /* UART2 */
-# define KL_UART3_BASE 0x4006d000 /* UART3 */
# define KL_USB0_BASE 0x40072000 /* USB OTG FS/LS */
# define KL_CMP_BASE 0x40073000 /* Analog comparator (CMP) / 6-bit digital-to-analog converter (DAC) */
-# define KL_VREF_BASE 0x40074000 /* Voltage reference (VREF) */
+# define KL_SPI0_BASE 0x40076000 /* SPI 0 */
+# define KL_SPI1_BASE 0x40077000 /* SPI 1 */
# define KL_LLWU_BASE 0x4007c000 /* Low-leakage wakeup unit (LLWU) */
# define KL_PMC_BASE 0x4007d000 /* Power management controller (PMC) */
# define KL_SMC_BASE 0x4007e000 /* System Mode controller (SMC) */
-
-/* Peripheral Bridge 1 Memory Map ***************************************************/
-
-# define KL_AIPS1_BASE 0x40080000 /* Peripheral bridge 1 (AIPS-Lite 1) */
-# define KL_CAN1_BASE 0x400a4000 /* FlexCAN 1 */
-# define KL_SPI2_BASE 0x400ac000 /* SPI 2 */
-# define KL_SDHC_BASE 0x400b1000 /* SDHC */
-# define KL_FTM2_BASE 0x400b8000 /* FlexTimer 2 */
-# define KL_ADC1_BASE 0x400bb000 /* Analog-to-digital converter (ADC) 1 */
-# define KL_SLCD_BASE 0x400be000 /* Segment LCD */
-# define KL_DAC0_BASE 0x400cc000 /* 12-bit digital-to-analog converter (DAC) 0 */
-# define KL_DAC1_BASE 0x400cd000 /* 12-bit digital-to-analog converter (DAC) 1 */
-# define KL_UART4_BASE 0x400ea000 /* UART4 */
-# define KL_UART5_BASE 0x400eb000 /* UART5 */
-# define KL_XBARSS_BASE 0x400ff000 /* Not an AIPS-Lite slot. The 32-bit general
- * purpose input/output module that shares the
- * crossbar switch slave port with the AIPS-Lite
- * is accessed at this address. */
-# define KL_GPIO_BASE(n) (0x400ff000 + ((n) << 6))
+# define KL_RCM_BASE 0x4007f000 /* Reset Control Module (RCM) */
+ /* 0x400ff000 * GPIO Controller */
+# define KL_GPIOn_BASE(n) (0x400ff000 + ((n) << 6))
# define KL_GPIOA_BASE 0x400ff000 /* GPIO PORTA registers */
# define KL_GPIOB_BASE 0x400ff040 /* GPIO PORTB registers */
# define KL_GPIOC_BASE 0x400ff080 /* GPIO PORTC registers */
@@ -170,15 +125,7 @@
/* Private Peripheral Bus (PPB) Memory Map ******************************************/
-# define KL_ITM_BASE 0xe0000000 /* Instrumentation Trace Macrocell (ITM) */
-# define KL_DWT_BASE 0xe0001000 /* Data Watchpoint and Trace (DWT) */
-# define KL_FPB_BASE 0xe0002000 /* Flash Patch and Breakpoint (FPB) */
# define KL_SCS_BASE 0xe000e000 /* System Control Space (SCS) (for NVIC) */
-# define KL_TPIU_BASE 0xe0040000 /* Trace Port Interface Unit (TPIU) */
-# define KL_ETM_BASE 0xe0041000 /* Embedded Trace Macrocell (ETM) */
-# define KL_ETB_BASE 0xe0042000 /* Embedded Trace Buffer (ETB) */
-# define KL_TFUN_BASE 0xe0043000 /* Embedded Trace Funnel */
-# define KL_MCM_BASE 0xe0080000 /* Miscellaneous Control Module (including ETB Almost Full) */
# define KL_ROMTAB_BASE 0xe00ff000 /* ROM Table - allows auto-detection of debug components */
/************************************************************************************
diff --git a/nuttx/arch/arm/src/kl/chip/kl_sim.h b/nuttx/arch/arm/src/kl/chip/kl_sim.h
index 0d2650978..64d1b809b 100644
--- a/nuttx/arch/arm/src/kl/chip/kl_sim.h
+++ b/nuttx/arch/arm/src/kl/chip/kl_sim.h
@@ -50,28 +50,30 @@
/* Register Offsets *****************************************************************/
+/* Relative to KL_SIMLP_BASE */
+
#define KL_SIM_SOPT1_OFFSET 0x0000 /* System Options Register 1 */
+#define KL_SIM_SOPT1CFG_OFFSET 0x0004 /* SOPT1 Configuration Register */
+
+/* Relative to KL_SIM_BASE */
+
#define KL_SIM_SOPT2_OFFSET 0x0004 /* System Options Register 2 */
#define KL_SIM_SOPT4_OFFSET 0x000c /* System Options Register 4 */
#define KL_SIM_SOPT5_OFFSET 0x0010 /* System Options Register 5 */
-#define KL_SIM_SOPT6_OFFSET 0x0014 /* System Options Register 6 */
#define KL_SIM_SOPT7_OFFSET 0x0018 /* System Options Register 7 */
#define KL_SIM_SDID_OFFSET 0x0024 /* System Device Identification Register */
-#define KL_SIM_SCGC1_OFFSET 0x0028 /* System Clock Gating Control Register 1 */
-#define KL_SIM_SCGC2_OFFSET 0x002c /* System Clock Gating Control Register 2 */
-#define KL_SIM_SCGC3_OFFSET 0x0030 /* System Clock Gating Control Register 3 */
#define KL_SIM_SCGC4_OFFSET 0x0034 /* System Clock Gating Control Register 4 */
#define KL_SIM_SCGC5_OFFSET 0x0038 /* System Clock Gating Control Register 5 */
#define KL_SIM_SCGC6_OFFSET 0x003c /* System Clock Gating Control Register 6 */
#define KL_SIM_SCGC7_OFFSET 0x0040 /* System Clock Gating Control Register 7 */
#define KL_SIM_CLKDIV1_OFFSET 0x0044 /* System Clock Divider Register 1 */
-#define KL_SIM_CLKDIV2_OFFSET 0x0048 /* System Clock Divider Register 2 */
#define KL_SIM_FCFG1_OFFSET 0x004c /* Flash Configuration Register 1 */
#define KL_SIM_FCFG2_OFFSET 0x0050 /* Flash Configuration Register 2 */
-#define KL_SIM_UIDH_OFFSET 0x0054 /* Unique Identification Register High */
#define KL_SIM_UIDMH_OFFSET 0x0058 /* Unique Identification Register Mid-High */
#define KL_SIM_UIDML_OFFSET 0x005c /* Unique Identification Register Mid Low */
#define KL_SIM_UIDL_OFFSET 0x0060 /* Unique Identification Register Low */
+#define KL_SIM_COPC_OFFSET 0x0100 /* COP Control Register */
+#define KL_SIM_SRVCOP_OFFSET 0x0104 /* Service COP Register */
/* Register Addresses ***************************************************************/
/* NOTE: The SIM_SOPT1 register is located at a different base address than the
@@ -79,103 +81,91 @@
*/
#define KL_SIM_SOPT1 (KL_SIMLP_BASE+KL_SIM_SOPT1_OFFSET)
+#define KL_SIM_SOPT1CFG (KL_SIMLP_BASE+KL_SIM_SOPT1CFG_OFFSET)
+
#define KL_SIM_SOPT2 (KL_SIM_BASE+KL_SIM_SOPT2_OFFSET)
#define KL_SIM_SOPT4 (KL_SIM_BASE+KL_SIM_SOPT4_OFFSET)
#define KL_SIM_SOPT5 (KL_SIM_BASE+KL_SIM_SOPT5_OFFSET)
-#define KL_SIM_SOPT6 (KL_SIM_BASE+KL_SIM_SOPT6_OFFSET)
#define KL_SIM_SOPT7 (KL_SIM_BASE+KL_SIM_SOPT7_OFFSET)
#define KL_SIM_SDID (KL_SIM_BASE+KL_SIM_SDID_OFFSET)
-#define KL_SIM_SCGC1 (KL_SIM_BASE+KL_SIM_SCGC1_OFFSET)
-#define KL_SIM_SCGC2 (KL_SIM_BASE+KL_SIM_SCGC2_OFFSET)
-#define KL_SIM_SCGC3 (KL_SIM_BASE+KL_SIM_SCGC3_OFFSET)
#define KL_SIM_SCGC4 (KL_SIM_BASE+KL_SIM_SCGC4_OFFSET)
#define KL_SIM_SCGC5 (KL_SIM_BASE+KL_SIM_SCGC5_OFFSET)
#define KL_SIM_SCGC6 (KL_SIM_BASE+KL_SIM_SCGC6_OFFSET)
#define KL_SIM_SCGC7 (KL_SIM_BASE+KL_SIM_SCGC7_OFFSET)
#define KL_SIM_CLKDIV1 (KL_SIM_BASE+KL_SIM_CLKDIV1_OFFSET)
-#define KL_SIM_CLKDIV2 (KL_SIM_BASE+KL_SIM_CLKDIV2_OFFSET)
#define KL_SIM_FCFG1 (KL_SIM_BASE+KL_SIM_FCFG1_OFFSET)
#define KL_SIM_FCFG2 (KL_SIM_BASE+KL_SIM_FCFG2_OFFSET)
-#define KL_SIM_UIDH (KL_SIM_BASE+KL_SIM_UIDH_OFFSET)
#define KL_SIM_UIDMH (KL_SIM_BASE+KL_SIM_UIDMH_OFFSET)
#define KL_SIM_UIDML (KL_SIM_BASE+KL_SIM_UIDML_OFFSET)
#define KL_SIM_UIDL (KL_SIM_BASE+KL_SIM_UIDL_OFFSET)
+#define KL_SIM_COPC (KL_SIM_BASE+KL_SIM_COPC_OFFSET)
+#define KL_SIM_SRVCOP (KL_SIM_BASE+KL_SIM_SRVCOP_OFFSET)
/* Register Bit Definitions *********************************************************/
/* System Options Register 1 */
/* Bits 0-17: Reserved */
-#define SIM_SOPT1_OSC32KSEL (3 << 18) /* Bit 18-19: 32K oscillator clock select */
- /* Bits 20-22: Reserved */
-#define SIM_SOPT1_MS (1 << 23) /* Bit 23: EzPort chip select pin state */
- /* Bits 24-29: Reserved */
-#define SIM_SOPT1_USBSTBY (1 << 30) /* Bit 30: USB voltage regulator in standby mode */
+#define SIM_SOPT1_OSC32KSEL_SHIFT (18) /* Bit 18-19: 32K oscillator clock select */
+#define SIM_SOPT1_OSC32KSEL_MASK (3 << SIM_SOPT1_OSC32KSEL_SHIFT)
+# define SIM_SOPT1_OSC32KSEL_SYS (1 << SIM_SOPT1_OSC32KSEL_SHIFT) /* System oscillator (OSC32KCLK) */
+# define SIM_SOPT1_OSC32KSEL_RTC (2 << SIM_SOPT1_OSC32KSEL_SHIFT) /* RTC_CLKIN */
+# define SIM_SOPT1_OSC32KSEL_LPO (3 << SIM_SOPT1_OSC32KSEL_SHIFT) /* LPO 1kHz */
+ /* Bits 20-28: Reserved */
+#define SIM_SOPT1_USBSTBY (1 << 29) /* Bit 29: USB voltage regulator in
+ * standby mode (VLPR and VLPW modes) */
+#define SIM_SOPT1_USBSSTBY (1 << 30) /* Bit 30: USB voltage regulator in standb
+ * mode (Stop, VLPS, LLS and VLLS modes) */
#define SIM_SOPT1_USBREGEN (1 << 31) /* Bit 31: USB voltage regulator enable */
+/* SOPT1 Configuration Register */
+
+#define SIM_SOPT1CFG_URWE (1 << 24) /* Bit 24: USB voltage regulator enable write enable */
+#define SIM_SOPT1CFG_UVSWE (1 << 25) /* Bit 25: USB voltage regulator VLP standby write enable */
+#define SIM_SOPT1CFG_USSWE (1 << 26) /* Bit 26: USB voltage regulator stop standby write enable */
+
+/* To be provided */
+
/* System Options Register 2 */
-#define SIM_SOPT2_MCGCLKSEL (1 << 0) /* Bit 0: MCG clock select */
- /* Bits 1-7: Reserved */
-#define SIM_SOPT2_FBSL_SHIFT (8) /* Bits 8-9: FlexBus security level */
-#define SIM_SOPT2_FBSL_MASK (3 << SIM_SOPT2_FBSL_SHIFT)
-# define SIM_SOPT2_FBSL_NONE (0 << SIM_SOPT2_FBSL_SHIFT) /* All off-chip accesses disallowed */
-# define SIM_SOPT2_FBSL_DATA (2 << SIM_SOPT2_FBSL_SHIFT) /* Off-chip data accesses are allowed */
-# define SIM_SOPT2_FBSL_ALL (3 << SIM_SOPT2_FBSL_SHIFT) /* All Off-chip accesses allowed */
- /* Bit 10: Reserved */
+ /* Bits 0-3: Reserved */
+#define SIM_SOPT2_RTCCLKOUTSEL (1 << 4) /* Bit 0: MCG clock select */
+#define SIM_SOPT2_CLKOUTSEL_SHIFT (5) /* Bits 5-7: RTC clock out select */
+#define SIM_SOPT2_CLKOUTSEL_MASK (3 << SIM_SOPT2_CLKOUTSEL_SHIFT)
+# define SIM_SOPT2_CLKOUTSEL_BUSCLK (2 << SIM_SOPT2_CLKOUTSEL_SHIFT) /* Bus clock */
+# define SIM_SOPT2_CLKOUTSEL_LPO (3 << SIM_SOPT2_CLKOUTSEL_SHIFT) /* LPO clock (1 kHz) */
+# define SIM_SOPT2_CLKOUTSEL_MCGIRCLK (4 << SIM_SOPT2_CLKOUTSEL_SHIFT) /* MCGIRCLK */
+# define SIM_SOPT2_CLKOUTSEL_OSCERCLK (6 << SIM_SOPT2_CLKOUTSEL_SHIFT) /* OSCERCLK */
#define SIM_SOPT2_CMTUARTPAD (1 << 11) /* Bit 11: CMT/UART pad drive strength */
#define SIM_SOPT2_TRACECLKSEL (1 << 12) /* Bit 12: Debug trace clock select */
/* Bits 13-15: Reserved */
#define SIM_SOPT2_PLLFLLSEL (1 << 16) /* Bit 16: PLL/FLL clock select */
/* Bit 17: Reserved */
#define SIM_SOPT2_USBSRC (1 << 18) /* Bit 18: USB clock source select */
- /* Bit 19: Reserved */
-#ifdef KL_K60
-# define SIM_SOPT2_TIMESRC (1 << 20) /* Bit 20: IEEE 1588 timestamp clock source select (K60) */
-#endif
- /* Bits 12-23: Reserved */
+ /* Bits 19-23: Reserved */
#define SIM_SOPT2_TPMSRC_SHIFT (24) /* Bits 24-25: I2S master clock source select */
#define SIM_SOPT2_TPMSRC_MASK (3 << SIM_SOPT2_TPMSRC_SHIFT)
# define SIM_SOPT2_TPMSRC_CLKDIS (0 << SIM_SOPT2_TPMSRC_SHIFT) /* Core/system clock / I2S fractional divider*/
-# define SIM_SOPT2_TPMSRC_MCGCLK (1 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGPLLCLK/MCGFLLCLK clock/ I2S fractional divider */
+# define SIM_SOPT2_TPMSRC_MCGCLK (1 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGFLLCLK clock or MCGPLLCLK/2 */
# define SIM_SOPT2_TPMSRC_OCSERCLK (2 << SIM_SOPT2_TPMSRC_SHIFT) /* OSCERCLK clock */
-# define SIM_SOPT2_TPMSRC_MCGIRCLK (3 << SIM_SOPT2_TPMSRC_SHIFT) /* External bypass clock (I2S0_CLKIN) */
+# define SIM_SOPT2_TPMSRC_MCGIRCLK (3 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGIRCLK clock */
#define SIM_SOPT2_UART0SRC_SHIFT (26) /* Bits 26-27: UART0 clock source select */
#define SIM_SOPT2_UART0SRC_MASK (3 << SIM_SOPT2_UART0SRC_SHIFT)
-#define SIM_SOPT2_UART0SRC_DIS (0 << SIM_SOPT2_UART0SRC_SHIFT)
-#define SIM_SOPT2_UART0SRC_MCGCLK (1 << SIM_SOPT2_UART0SRC_SHIFT)
-#define SIM_SOPT2_UART0SRC_OSCERCLK (2 << SIM_SOPT2_UART0SRC_SHIFT)
-#define SIM_SOPT2_UART0SRC_MCGIRCLK (3 << SIM_SOPT2_UART0SRC_SHIFT)
-#define SIM_SOPT2_SDHCSRC_SHIFT (28) /* Bits 28-29: SDHC clock source select*/
-#define SIM_SOPT2_SDHCSRC_MASK (3 << SIM_SOPT2_SDHCSRC_SHIFT)
-# define SIM_SOPT2_SDHCSRC_CORE (0 << SIM_SOPT2_SDHCSRC_SHIFT) /* Core/system clock */
-# define SIM_SOPT2_SDHCSRC_MCGCLK (1 << SIM_SOPT2_SDHCSRC_SHIFT) /* MCGPLLCLK/MCGFLLCLK clock */
-# define SIM_SOPT2_SDHCSRC_OCSERCLK (2 << SIM_SOPT2_SDHCSRC_SHIFT) /* OSCERCLK clock */
-# define SIM_SOPT2_SDHCSRC_EXTBYP (3 << SIM_SOPT2_SDHCSRC_SHIFT) /* External bypass clock (SDHC0_CLKIN) */ /* Bits 30-31: Reserved */
+# define SIM_SOPT2_UART0SRC_DIS (0 << SIM_SOPT2_UART0SRC_SHIFT) /* Clock disabled */
+# define SIM_SOPT2_UART0SRC_MCGCLK (1 << SIM_SOPT2_UART0SRC_SHIFT) /* MCGFLLCLK clock or MCGPLLCLK/2 clock */
+# define SIM_SOPT2_UART0SRC_OSCERCLK (2 << SIM_SOPT2_UART0SRC_SHIFT) /* OSCERCLK clock */
+# define SIM_SOPT2_UART0SRC_MCGIRCLK (3 << SIM_SOPT2_UART0SRC_SHIFT) /* MCGIRCLK clock */
+ /* Bits 28-31: Reserved */
/* System Options Register 4 */
-#define SIM_SOPT4_FTM0FLT0 (1 << 0) /* Bit 0: FTM0 Fault 0 Select */
-#define SIM_SOPT4_FTM0FLT1 (1 << 1) /* Bit 1: FTM0 Fault 1 Select */
-#define SIM_SOPT4_FTM0FLT2 (1 << 2) /* Bit 2: FTM0 Fault 2 Select */
- /* Bit 3: Reserved */
-#define SIM_SOPT4_FTM1FLT0 (1 << 4) /* Bit 4: FTM1 Fault 0 Select */
- /* Bits 5-7: Reserved */
-#define SIM_SOPT4_FTM2FLT0 (1 << 8) /* Bit 8: FTM2 Fault 0 Select */
- /* Bits 9-17: Reserved */
-#define SIM_SOPT4_FTM1CH0SRC_SHIFT (18) /* Bits 18-19: FTM1 channel 0 input capture source select */
-#define SIM_SOPT4_FTM1CH0SRC_MASK (3 << SIM_SOPT4_FTM1CH0SRC_SHIFT)
-# define SIM_SOPT4_FTM1CH0SRC_CH0 (0 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* FTM1_CH0 signal */
-# define SIM_SOPT4_FTM1CH0SRC_CMP0 (1 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* CMP0 output */
-# define SIM_SOPT4_FTM1CH0SRC_CMP1 (2 << SIM_SOPT4_FTM1CH0SRC_SHIFT) /* CMP1 output */
-#define SIM_SOPT4_FTM2CH0SRC_SHIFT (20) /* Bits 20-21: FTM2 channel 0 input capture source select */
-#define SIM_SOPT4_FTM2CH0SRC_MASK (3 << SIM_SOPT4_FTM2CH0SRC_SHIFT)
-# define SIM_SOPT4_FTM2CH0SRC_CH0 (0 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* FTM2_CH0 signal */
-# define SIM_SOPT4_FTM2CH0SRC_CMP0 (1 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* CMP0 output */
-# define SIM_SOPT4_FTM2CH0SRC_CMP1 (2 << SIM_SOPT4_FTM2CH0SRC_SHIFT) /* CMP1 output */
- /* Bits 22-23: Reserved */
-#define SIM_SOPT4_FTM0CLKSEL (1 << 24) /* Bit 24: FlexTimer 0 External Clock Pin Select */
-#define SIM_SOPT4_FTM1CLKSEL (1 << 25) /* Bit 25: FTM1 External Clock Pin Select */
-#define SIM_SOPT4_FTM2CLKSEL (1 << 26) /* Bit 26: FlexTimer 2 External Clock Pin Select */
+ /* Bits 0-17: Reserved */
+#define SIM_SOPT4_TPM1CH0SRC (1 << 18) /* Bit 18: TPM1 channel 0 input capture source select */
+ /* Bit 19: Reserved */
+#define SIM_SOPT4_TPM2CH0SRC (1 << 20) /* Bit 20: TPM2 channel 0 input capture source select */
+ /* Bits 21-23: Reserved */
+#define SIM_SOPT4_TPM0CLKSEL (1 << 24) /* Bit 24: TPM0CLKSEL */
+#define SIM_SOPT4_TPM1CLKSEL (1 << 25) /* Bit 25: TPM1 External Clock Pin Select */
+#define SIM_SOPT4_TPM2CLKSEL (1 << 26) /* Bit 26: TPM2 External Clock Pin Select */
/* Bits 27-31: Reserved */
/* System Options Register 5 */
@@ -183,164 +173,100 @@
#define SIM_SOPT5_UART0TXSRC_SHIFT (0) /* Bits 0-1: UART 0 transmit data source select */
#define SIM_SOPT5_UART0TXSRC_MASK (3 << SIM_SOPT5_UART0TXSRC_SHIFT)
# define SIM_SOPT5_UART0TXSRC_TX (0 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX pin */
-# define SIM_SOPT5_UART0TXSRC_FTM1 (1 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with FTM1 ch0 output */
-# define SIM_SOPT5_UART0TXSRC_FTM2 (2 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with FTM2 ch0 output */
-#define SIM_SOPT5_UART0RXSRC_SHIFT (2) /* Bits 2-3: UART 0 receive data source select */
-#define SIM_SOPT5_UART0RXSRC_MASK (3 << SIM_SOPT5_UART0RXSRC_SHIFT)
-# define SIM_SOPT5_UART0RXSRC_RX (0 << SIM_SOPT5_UART0RXSRC_SHIFT) /* UART0_RX pin */
-# define SIM_SOPT5_UART0RXSRC_CMP0 (1 << SIM_SOPT5_UART0RXSRC_SHIFT) /* CMP0 */
-# define SIM_SOPT5_UART0RXSRC_CMP1 (2 << SIM_SOPT5_UART0RXSRC_SHIFT) /* CMP1 */
+# define SIM_SOPT5_UART0TXSRC_TPM1 (1 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with TPM1 ch0 output */
+# define SIM_SOPT5_UART0TXSRC_TPM2 (2 << SIM_SOPT5_UART0TXSRC_SHIFT) /* UART0_TX modulated with TPM2 ch0 output */
+#define SIM_SOPT5_UART0RXSRC (1 << 2) /* Bit 2: UART 0 receive data source select */
+ /* Bit 3: Reserved */
#define SIM_SOPT5_UART1TXSRC_SHIFT (4) /* Bits 4-5: UART 1 transmit data source select */
#define SIM_SOPT5_UART1TXSRC_MASK (3 << SIM_SOPT5_UART1TXSRC_SHIFT)
# define SIM_SOPT5_UART1TXSRC_TX (0 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX pin */
-# define SIM_SOPT5_UART1TXSRC_FTM1 (1 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with FTM1 ch0 output */
-# define SIM_SOPT5_UART1TXSRC_FTM2 (2 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with FTM2 ch0 output */
-#define SIM_SOPT5_UART1RXSRC_SHIFT (6) /* Bits 6-7: UART 1 receive data source select */
-#define SIM_SOPT5_UART1RXSRC_MASK (3 << SIM_SOPT5_UART1RXSRC_SHIFT)
-# define SIM_SOPT5_UART1RXSRC_RX (0 << SIM_SOPT5_UART1RXSRC_SHIFT) /* UART1_RX pin */
-# define SIM_SOPT5_UART1RXSRC_CMP0 (1 << SIM_SOPT5_UART1RXSRC_SHIFT) /* CMP0 */
-# define SIM_SOPT5_UART1RXSRC_CMP1 (2 << SIM_SOPT5_UART1RXSRC_SHIFT) /* CMP1 */
- /* Bits 8-31: Reserved */
-/* System Options Register 6 */
- /* Bits 0-23: Reserved */
-#define SIM_SOPT6_RSTFLTSEL_SHIFT (24) /* Bits 24-28: Reset pin filter select */
-#define SIM_SOPT6_RSTFLTSEL_MASK (31 << SIM_SOPT6_RSTFLTSEL_SHIFT)
-# define SIM_SOPT6_RSTFLTSEL(n) (((n)-1) << SIM_SOPT6_RSTFLTSEL_SHIFT) /* Bux clock filter count n, n=1..32 */
-#define SIM_SOPT6_RSTFLTEN_SHIFT (29) /* Bits 29-31: Reset pin filter enable */
-#define SIM_SOPT6_RSTFLTEN_MASK (7 << SIM_SOPT6_RSTFLTEN_SHIFT)
-#define SIM_SOPT6_RSTFLTEN_DISABLED (0 << SIM_SOPT6_RSTFLTEN_SHIFT) /* All filtering disabled */
-# define SIM_SOPT6_RSTFLTEN_BUSCLK1 (1 << SIM_SOPT6_RSTFLTEN_SHIFT) /* Bus clock filter enabled (normal); LPO clock filter enabled (stop) */
-# define SIM_SOPT6_RSTFLTEN_LPO1 (2 << SIM_SOPT6_RSTFLTEN_SHIFT) /* LPO clock filter enabled */
-# define SIM_SOPT6_RSTFLTEN_BUSCLK2 (3 << SIM_SOPT6_RSTFLTEN_SHIFT) /* Bus clock filter enabled (normal); All filtering disabled (stop) */
-# define SIM_SOPT6_RSTFLTEN_LPO2 (4 << SIM_SOPT6_RSTFLTEN_SHIFT) /* PO clock filter enabled (normal); All filtering disabled (stop) */
-
+# define SIM_SOPT5_UART1TXSRC_TPM1 (1 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with TPM1 ch0 output */
+# define SIM_SOPT5_UART1TXSRC_TPM2 (2 << SIM_SOPT5_UART1TXSRC_SHIFT) /* UART1_TX modulated with TPM2 ch0 output */
+#define SIM_SOPT5_UART1RXSRC (1 << 6) /* Bit 6: UART 1 receive data source select */
+#define SIM_SOPT5_UART0ODE (1 << 16) /* Bit 16: UART0 Open Drain Enable */
+#define SIM_SOPT5_UART1ODE (1 << 17) /* Bit 17: UART1 Open Drain Enable */
+#define SIM_SOPT5_UART2ODE (1 << 18) /* Bit 18: UART2 Open Drain Enable */
+ /* Bits 20-31: Reserved */
/* System Options Register 7 */
#define SIM_SOPT7_ADC0TRGSEL_SHIFT (0) /* Bits 0-3: ADC0 trigger select */
#define SIM_SOPT7_ADC0TRGSEL_MASK (15 << SIM_SOPT7_ADC0TRGSEL_SHIFT)
-# define SIM_SOPT7_ADC0TRGSEL_PDB (0 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PDB external trigger (PDB0_EXTRG) */
-# define SIM_SOPT7_ADC0TRGSEL_CMP0 (1 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 0 output */
-# define SIM_SOPT7_ADC0TRGSEL_CMP1 (2 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 1 output */
-# define SIM_SOPT7_ADC0TRGSEL_CMP2 (3 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* High speed comparator 2 output */
+# define SIM_SOPT7_ADC0TRGSEL_EXT (0 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* External trigger pin input (EXTRG_IN)*/
+# define SIM_SOPT7_ADC0TRGSEL_CMP0 (1 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* CMP0 output */
# define SIM_SOPT7_ADC0TRGSEL_PIT0 (4 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 0 */
# define SIM_SOPT7_ADC0TRGSEL_PIT1 (5 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 1 */
-# define SIM_SOPT7_ADC0TRGSEL_PIT2 (6 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 2 */
-# define SIM_SOPT7_ADC0TRGSEL_PIT3 (7 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* PIT trigger 3 */
-# define SIM_SOPT7_ADC0TRGSEL_FTM0 (8 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM0 trigger */
-# define SIM_SOPT7_ADC0TRGSEL_FTM1 (9 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM1 trigger */
-# define SIM_SOPT7_ADC0TRGSEL_FTM2 (10 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* FTM2 trigger */
+# define SIM_SOPT7_ADC0TRGSEL_TPM0 (8 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* TPM0 overflow */
+# define SIM_SOPT7_ADC0TRGSEL_TPM1 (9 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* TPM1 overflow */
+# define SIM_SOPT7_ADC0TRGSEL_TPM2 (10 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* TPM2 overflow */
# define SIM_SOPT7_ADC0TRGSEL_ALARM (12 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* RTC alarm */
# define SIM_SOPT7_ADC0TRGSEL_SECS (13 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* RTC seconds */
-# define SIM_SOPT7_ADC0TRGSEL_LPTMR (14 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* Low-power timer trigger */
+# define SIM_SOPT7_ADC0TRGSEL_LPTMR (14 << SIM_SOPT7_ADC0TRGSEL_SHIFT) /* LPTMR0 trigger */
#define SIM_SOPT7_ADC0PRETRGSEL (1 << 4) /* Bit 4: ADC0 pretrigger select */
/* Bits 5-6: Reserved */
#define SIM_SOPT7_ADC0ALTTRGEN (1 << 7) /* Bit 7: ADC0 alternate trigger enable */
-#define SIM_SOPT7_ADC1TRGSEL_SHIFT (8) /* Bits 8-11: ADC1 trigger select */
-#define SIM_SOPT7_ADC1TRGSEL_MASK (15 << SIM_SOPT7_ADC1TRGSEL_SHIFT)
-# define SIM_SOPT7_ADC1TRGSEL_PDB (0 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PDB external trigger (PDB0_EXTRG) */
-# define SIM_SOPT7_ADC1TRGSEL_CMP0 (1 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 0 output */
-# define SIM_SOPT7_ADC1TRGSEL_CMP1 (2 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 1 output */
-# define SIM_SOPT7_ADC1TRGSEL_CMP2 (3 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* High speed comparator 2 output */
-# define SIM_SOPT7_ADC1TRGSEL_PIT0 (4 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 0 */
-# define SIM_SOPT7_ADC1TRGSEL_PIT1 (5 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 1 */
-# define SIM_SOPT7_ADC1TRGSEL_PIT2 (6 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 2 */
-# define SIM_SOPT7_ADC1TRGSEL_PIT3 (7 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* PIT trigger 3 */
-# define SIM_SOPT7_ADC1TRGSEL_FTM0 (8 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM0 trigger */
-# define SIM_SOPT7_ADC1TRGSEL_FTM1 (9 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM1 trigger */
-# define SIM_SOPT7_ADC1TRGSEL_FTM2 (10 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* FTM2 trigger */
-# define SIM_SOPT7_ADC1TRGSEL_ALARM (12 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* RTC alarm */
-# define SIM_SOPT7_ADC1TRGSEL_SECS (13 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* RTC seconds */
-# define SIM_SOPT7_ADC1TRGSEL_LPTMR (14 << SIM_SOPT7_ADC1TRGSEL_SHIFT) /* Low-power timer trigger */
-#define SIM_SOPT7_ADC1PRETRGSEL (1 << 12) /* Bit 12: ADC1 pre-trigger select */
- /* Bits 13-14: Reserved */
-#define SIM_SOPT7_ADC1ALTTRGEN (1 << 15) /* Bit 15: ADC1 alternate trigger enable */
- /* Bits 16-31: Reserved */
+ /* Bits 8-31: Reserved */
/* System Device Identification Register */
#define SIM_SDID_PINID_SHIFT (0) /* Bits 0-3: Pincount identification */
#define SIM_SDID_PINID_MASK (15 << SIM_SDID_PINID_SHIFT)
+# define SIM_SDID_PINID_16PIN (0 << SIM_SDID_PINID_SHIFT) /* 16-pin */
+# define SIM_SDID_PINID_24PIN (1 << SIM_SDID_PINID_SHIFT) /* 24-pin */
# define SIM_SDID_PINID_32PIN (2 << SIM_SDID_PINID_SHIFT) /* 32-pin */
# define SIM_SDID_PINID_48PIN (4 << SIM_SDID_PINID_SHIFT) /* 48-pin */
# define SIM_SDID_PINID_64PIN (5 << SIM_SDID_PINID_SHIFT) /* 64-pin */
# define SIM_SDID_PINID_80PIN (6 << SIM_SDID_PINID_SHIFT) /* 80-pin */
-# define SIM_SDID_PINID_81PIN (7 << SIM_SDID_PINID_SHIFT) /* 81-pin */
# define SIM_SDID_PINID_100PIN (8 << SIM_SDID_PINID_SHIFT) /* 100-pin */
-# define SIM_SDID_PINID_121PIN (9 << SIM_SDID_PINID_SHIFT) /* 121-pin */
-# define SIM_SDID_PINID_144PIN (10 << SIM_SDID_PINID_SHIFT) /* 144-pin */
-# define SIM_SDID_PINID_196PIN (12 << SIM_SDID_PINID_SHIFT) /* 196-pin */
-# define SIM_SDID_PINID_256PIN (14 << SIM_SDID_PINID_SHIFT) /* 256-pin */
-#define SIM_SDID_FAMID_SHIFT (4) /* Bits 4-6: Kinetis family identification */
-#define SIM_SDID_FAMID_MASK (7 << SIM_SDID_FAMID_SHIFT)
-# define SIM_SDID_FAMID_K10 (0 << SIM_SDID_FAMID_SHIFT) /* K10 */
-# define SIM_SDID_FAMID_K20 (1 << SIM_SDID_FAMID_SHIFT)) /* K20 */
-# define SIM_SDID_FAMID_K30 (2 << SIM_SDID_FAMID_SHIFT)) /* K30 */
-# define SIM_SDID_FAMID_K40 (3 << SIM_SDID_FAMID_SHIFT)) /* K40 */
-# define SIM_SDID_FAMID_K60 (4 << SIM_SDID_FAMID_SHIFT)) /* K60 */
-# define SIM_SDID_FAMID_K70 (5 << SIM_SDID_FAMID_SHIFT)) /* K70 */
-# define SIM_SDID_FAMID_K50 (6 << SIM_SDID_FAMID_SHIFT)) /* K50 and K52 */
-# define SIM_SDID_FAMID_K51 (7 << SIM_SDID_FAMID_SHIFT)) /* K51 and K53 */
- /* Bits 7-11: Reserved */
+ /* Bits 406: Reserved */
+#define SIM_SDID_DIEID_SHIFT (7) /* Bits 7-1: Device die number */
+#define SIM_SDID_DIEID_MASK (15 << SIM_SDID_DIEID_SHIFT)
#define SIM_SDID_REVID_SHIFT (12) /* Bits 12-15: Device revision number */
#define SIM_SDID_REVID_MASK (15 << SIM_SDID_REVID_SHIFT)
- /* Bits 16-31: Reserved */
-/* System Clock Gating Control Register 1 */
- /* Bits 0-9: Reserved */
-#define SIM_SCGC1_UART4 (1 << 10) /* Bit 10: UART4 Clock Gate Control */
-#define SIM_SCGC1_UART5 (1 << 11) /* Bit 11: UART5 Clock Gate Control */
- /* Bits 12-31: Reserved */
-/* System Clock Gating Control Register 2 */
-
-#if defined(KL_NENET) && KL_NENET > 0
-# define SIM_SCGC2_ENET (1 << 0) /* Bit 0: ENET Clock Gate Control (K60) */
-#endif
- /* Bits 1-11: Reserved */
-#define SIM_SCGC2_DAC0 (1 << 12) /* Bit 12: DAC0 Clock Gate Control */
-#define SIM_SCGC2_DAC1 (1 << 13) /* Bit 13: DAC1 Clock Gate Control */
- /* Bits 14-31: Reserved */
-/* System Clock Gating Control Register 3 */
-
-#if defined(KL_NRNG) && KL_NRNG > 0
-# define SIM_SCGC3_RNGB (1 << 0) /* Bit 0: RNGB Clock Gate Control (K60) */
-#endif
- /* Bits 1-3: Reserved */
-#define SIM_SCGC3_FLEXCAN1 (1 << 4) /* Bit 4: FlexCAN1 Clock Gate Control */
- /* Bits 5-11: Reserved */
-#define SIM_SCGC3_SPI2 (1 << 12) /* Bit 12: SPI2 Clock Gate Control */
- /* Bits 13-16: Reserved */
-#define SIM_SCGC3_SDHC (1 << 17) /* Bit 17: SDHC Clock Gate Control */
- /* Bits 18-23: Reserved */
-#define SIM_SCGC3_FTM2 (1 << 24) /* Bit 24: FTM2 Clock Gate Control */
- /* Bits 25-26: Reserved */
-#define SIM_SCGC3_ADC1 (1 << 27) /* Bit 27: ADC1 Clock Gate Control */
- /* Bits 28-29: Reserved */
-#if defined(KL_NSLCD) && KL_NSLCD > 0
-# define SIM_SCGC3_SLCD (1 << 30) /* Bit 30: Segment LCD Clock Gate Control (K40) */
-#endif
- /* Bit 31: Reserved */
+#define SIM_SDID_SRAMSIZE_SHIFT (16) /* Bits 16-19: System SRAM Size */
+#define SIM_SDID_SRAMSIZE_MASK (15 << SIM_SDID_SRAMSIZE_SHIFT)
+# define SIM_SDID_SRAMSIZE_p5KB (0 << SIM_SDID_SRAMSIZE_SHIFT) /* 0.5 KB */
+# define SIM_SDID_SRAMSIZE_1KB (1 << SIM_SDID_SRAMSIZE_SHIFT) /* 1 KB */
+# define SIM_SDID_SRAMSIZE_2KB (2 << SIM_SDID_SRAMSIZE_SHIFT) /* 2 KB */
+# define SIM_SDID_SRAMSIZE_4KB (3 << SIM_SDID_SRAMSIZE_SHIFT) /* 4 KB */
+# define SIM_SDID_SRAMSIZE_8KB (4 << SIM_SDID_SRAMSIZE_SHIFT) /* 8 KB */
+# define SIM_SDID_SRAMSIZE_16KB (5 << SIM_SDID_SRAMSIZE_SHIFT) /* 16 KB */
+# define SIM_SDID_SRAMSIZE_32KB (6 << SIM_SDID_SRAMSIZE_SHIFT) /* 32 KB */
+# define SIM_SDID_SRAMSIZE_64KB (7 << SIM_SDID_SRAMSIZE_SHIFT) /* 64 KB */
+#define SIM_SDID_SERIESID_SHIFT (10) /* Bits 20-23: Kinetis Series ID */
+#define SIM_SDID_SERIESID_MASK (15 << SIM_SDID_SERIESID_SHIFT)
+# define SIM_SDID_SERIESID_KL (1 << SIM_SDID_SERIESID_SHIFT) /* KL family */
+#define SIM_SDID_SUBFAMID_SHIFT (24) /* Bits 24-27: Kinetis Sub-Family ID */
+#define SIM_SDID_SUBFAMID_MASK (15 << SIM_SDID_SUBFAMID_SHIFT)
+# define SIM_SDID_SUBFAMID_KLX2 (2 << SIM_SDID_SUBFAMID_SHIFT) /* KLx2 Subfamily (low end) */
+# define SIM_SDID_SUBFAMID_KLX4 (4 << SIM_SDID_SUBFAMID_SHIFT) /* KLx4 Subfamily (basic analog) */
+# define SIM_SDID_SUBFAMID_KLX5 (5 << SIM_SDID_SUBFAMID_SHIFT) /* KLx5 Subfamily (advanced analog) */
+# define SIM_SDID_SUBFAMID_KLX6 (6 << SIM_SDID_SUBFAMID_SHIFT) /* KL3x KLx6 Subfamily (advanced analog with I2S) */
+#define SIM_SDID_FAMID_SHIFT (28) /* Bits 28-31: Kinetis family ID */
+#define SIM_SDID_FAMID_MASK (15 << SIM_SDID_FAMID_SHIFT)
+# define SIM_SDID_FAMID_KL0 (0 << SIM_SDID_FAMID_SHIFT) /* KL0x Family (low end) */
+# define SIM_SDID_FAMID_KL1 (1 << SIM_SDID_FAMID_SHIFT) /* KL1x Family (basic) */
+# define SIM_SDID_FAMID_KL2 (2 << SIM_SDID_FAMID_SHIFT) /* KL2x Family (USB) */
+# define SIM_SDID_FAMID_KL3 (3 << SIM_SDID_FAMID_SHIFT) /* KL3x Family (Segment LCD) */
+# define SIM_SDID_FAMID_KL4 (4 << SIM_SDID_FAMID_SHIFT) /* KL4x Family (USB and Segment LCD) */
+
/* System Clock Gating Control Register 4 */
- /* Bit 0: Reserved */
-#define SIM_SCGC4_EWM (1 << 1) /* Bit 1: EWM Clock Gate Control */
-#define SIM_SCGC4_CMT (1 << 2) /* Bit 2: CMT Clock Gate Control */
- /* Bits 3-5: Reserved */
+ /* Bits 0-5: Reserved */
#define SIM_SCGC4_I2C0 (1 << 6) /* Bit 6: I2C0 Clock Gate Control */
#define SIM_SCGC4_I2C1 (1 << 7) /* Bit 7: I2C1 Clock Gate Control */
-
+ /* Bits 8-9: Reserved */
#define SIM_SCGC4_UART0 (1 << 10) /* Bit 10: UART0 Clock Gate Control */
#define SIM_SCGC4_UART1 (1 << 11) /* Bit 11: UART1 Clock Gate Control */
#define SIM_SCGC4_UART2 (1 << 12) /* Bit 12: UART2 Clock Gate Control */
-#define SIM_SCGC4_UART3 (1 << 13) /* Bit 13: UART3 Clock Gate Control */
- /* Bits 14-17: Reserved */
+ /* Bits 13-17: Reserved */
#define SIM_SCGC4_USBOTG (1 << 18) /* Bit 18: USB Clock Gate Control */
#define SIM_SCGC4_CMP (1 << 19) /* Bit 19: Comparator Clock Gate Control */
-#define SIM_SCGC4_VREF (1 << 20) /* Bit 20: VREF Clock Gate Control */
- /* Bits 21-17: Reserved */
-#define SIM_SCGC4_LLWU (1 << 28) /* Bit 28: LLWU Clock Gate Control */
- /* Bits 29-31: Reserved */
+ /* Bits 20-21: Reserved */
+#define SIM_SCGC4_SPI10 (1 << 22) /* Bit 22: SPI0 Clock Gate Control */
+#define SIM_SCGC4_SPI1 (1 << 23) /* Bit 23: SPI1 Clock Gate Control */
+ /* Bits 24-31: Reserved */
/* System Clock Gating Control Register 5 */
#define SIM_SCGC5_LPTIMER (1 << 0) /* Bit 0: Low Power Timer Clock Gate Control */
-#define SIM_SCGC5_REGFILE (1 << 1) /* Bit 1: Register File Clock Gate Control */
- /* Bits 2-4: Reserved */
+ /* Bits 1-4: Reserved */
#define SIM_SCGC5_TSI (1 << 5) /* Bit 5: TSI Clock Gate Control */
/* Bits 6-8: Reserved */
#define SIM_SCGC5_PORTA (1 << 9) /* Bit 9: Port A Clock Gate Control */
@@ -353,36 +279,26 @@
#define SIM_SCGC6_FTFL (1 << 0) /* Bit 0: Flash Memory Clock Gate Control */
#define SIM_SCGC6_DMAMUX (1 << 1) /* Bit 1: DMA Mux Clock Gate Control */
- /* Bits 2-3: Reserved */
-#define SIM_SCGC6_FLEXCAN0 (1 << 4) /* Bit 4: FlexCAN0 Clock Gate Control */
- /* Bits 5-11: Reserved */
-#define SIM_SCGC6_SPI0 (1 << 12) /* Bit 12: SPI0 Clock Gate Control */
-#define SIM_SCGC6_SPI1 (1 << 13) /* Bit 13: SPI1 Clock Gate Control */
- /* Bit 14: Reserved */
-#define SIM_SCGC6_I2S (1 << 15) /* Bit 15: I2S Clock Gate Control */
- /* Bits 16-17: Reserved */
-#define SIM_SCGC6_CRC (1 << 18) /* Bit 18: CRC Clock Gate Control */
- /* Bits 19-20: Reserved */
-#define SIM_SCGC6_USBDCD (1 << 21) /* Bit 21: USB DCD Clock Gate Control */
-#define SIM_SCGC6_PDB (1 << 22) /* Bit 22: PDB Clock Gate Control */
+ /* Bits 2-22: Reserved */
#define SIM_SCGC6_PIT (1 << 23) /* Bit 23: PIT Clock Gate Control */
-#define SIM_SCGC6_FTM0 (1 << 24) /* Bit 24: FTM0 Clock Gate Control */
-#define SIM_SCGC6_FTM1 (1 << 25) /* Bit 25: FTM1 Clock Gate Control */
- /* Bit 26: Reserved */
+#define SIM_SCGC6_TPM0 (1 << 24) /* Bit 24: TPM0 Clock Gate Control */
+#define SIM_SCGC6_TPM1 (1 << 25) /* Bit 25: TPM1 Clock Gate Control */
+#define SIM_SCGC6_TPM6 (1 << 26) /* Bit 25: TPM2 Clock Gate Control */
#define SIM_SCGC6_ADC0 (1 << 27) /* Bit 27: ADC0 Clock Gate Control */
/* Bit 28: Reserved */
#define SIM_SCGC6_RTC (1 << 29) /* Bit 29: RTC Clock Gate Control */
- /* Bits 30-31: Reserved */
+ /* Bit 30: Reserved */
+#define SIM_SCGC6_DAC0 (1 << 31) /* Bit 29: DAC0 Clock Gate Control */
+
/* System Clock Gating Control Register 7 */
-#define SIM_SCGC7_FLEXBUS (1 << 0) /* Bit 0: FlexBus Clock Gate Control */
-#define SIM_SCGC7_DMA (1 << 1) /* Bit 1: DMA Clock Gate Control */
-#define SIM_SCGC7_MPU (1 << 2) /* Bit 2: MPU Clock Gate Control */
- /* Bits 3-31: Reserved */
+ /* Bits 0-7: Reserved */
+#define SIM_SCGC7_DMA (1 << 8) /* Bit 8: DMA Clock Gate Control */
+ /* Bits 9-31: Reserved */
/* System Clock Divider Register 1 */
/* Bits 0-15: Reserved */
-#define SIM_CLKDIV1_OUTDIV4_SHIFT (16) /* Bits 16-19: Clock 4 output divider value */
-#define SIM_CLKDIV1_OUTDIV4_MASK (15 << SIM_CLKDIV1_OUTDIV4_SHIFT)
+#define SIM_CLKDIV1_OUTDIV4_SHIFT (16) /* Bits 16-18: Clock 4 output divider value */
+#define SIM_CLKDIV1_OUTDIV4_MASK (7 << SIM_CLKDIV1_OUTDIV4_SHIFT)
# define SIM_CLKDIV1_OUTDIV4(n) (((n)-1) << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by n, n=1..16 */
# define SIM_CLKDIV1_OUTDIV4_1 (0 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 1 */
# define SIM_CLKDIV1_OUTDIV4_2 (1 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 2 */
@@ -392,52 +308,7 @@
# define SIM_CLKDIV1_OUTDIV4_6 (5 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 6 */
# define SIM_CLKDIV1_OUTDIV4_7 (6 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 7 */
# define SIM_CLKDIV1_OUTDIV4_8 (7 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 8 */
-# define SIM_CLKDIV1_OUTDIV4_9 (8 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 9 */
-# define SIM_CLKDIV1_OUTDIV4_10 (9 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 10 */
-# define SIM_CLKDIV1_OUTDIV4_11 (10 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 11 */
-# define SIM_CLKDIV1_OUTDIV4_12 (11 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 12 */
-# define SIM_CLKDIV1_OUTDIV4_13 (12 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 13 */
-# define SIM_CLKDIV1_OUTDIV4_14 (13 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 14 */
-# define SIM_CLKDIV1_OUTDIV4_15 (14 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 15 */
-# define SIM_CLKDIV1_OUTDIV4_16 (15 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 16 */
-#define SIM_CLKDIV1_OUTDIV3_SHIFT (20) /* Bits 20-23: Clock 3 output divider value */
-#define SIM_CLKDIV1_OUTDIV3_MASK (15 << SIM_CLKDIV1_OUTDIV3_SHIFT)
-# define SIM_CLKDIV1_OUTDIV3(n) (((n)-1) << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by n, n=1..16 */
-# define SIM_CLKDIV1_OUTDIV3_1 (0 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 1 */
-# define SIM_CLKDIV1_OUTDIV3_2 (1 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 2 */
-# define SIM_CLKDIV1_OUTDIV3_3 (2 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 3 */
-# define SIM_CLKDIV1_OUTDIV3_4 (3 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 4 */
-# define SIM_CLKDIV1_OUTDIV3_5 (4 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 5 */
-# define SIM_CLKDIV1_OUTDIV3_6 (5 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 6 */
-# define SIM_CLKDIV1_OUTDIV3_7 (6 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 7 */
-# define SIM_CLKDIV1_OUTDIV3_8 (7 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 8 */
-# define SIM_CLKDIV1_OUTDIV3_9 (8 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 9 */
-# define SIM_CLKDIV1_OUTDIV3_10 (9 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 10 */
-# define SIM_CLKDIV1_OUTDIV3_11 (10 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 11 */
-# define SIM_CLKDIV1_OUTDIV3_12 (11 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 12 */
-# define SIM_CLKDIV1_OUTDIV3_13 (12 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 13 */
-# define SIM_CLKDIV1_OUTDIV3_14 (13 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 14 */
-# define SIM_CLKDIV1_OUTDIV3_15 (14 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 15 */
-# define SIM_CLKDIV1_OUTDIV3_16 (15 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 16 */
-#define SIM_CLKDIV1_OUTDIV2_SHIFT (24) /* Bits 24-27: Clock 2 output divider value */
-#define SIM_CLKDIV1_OUTDIV2_MASK (15 << SIM_CLKDIV1_OUTDIV2_SHIFT)
-# define SIM_CLKDIV1_OUTDIV2(n) (((n)-1) << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by n, n=1..16 */
-# define SIM_CLKDIV1_OUTDIV2_1 (0 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 1 */
-# define SIM_CLKDIV1_OUTDIV2_2 (1 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 2 */
-# define SIM_CLKDIV1_OUTDIV2_3 (2 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 3 */
-# define SIM_CLKDIV1_OUTDIV2_4 (3 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 4 */
-# define SIM_CLKDIV1_OUTDIV2_5 (4 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 5 */
-# define SIM_CLKDIV1_OUTDIV2_6 (5 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 6 */
-# define SIM_CLKDIV1_OUTDIV2_7 (6 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 7 */
-# define SIM_CLKDIV1_OUTDIV2_8 (7 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 8 */
-# define SIM_CLKDIV1_OUTDIV2_9 (8 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 9 */
-# define SIM_CLKDIV1_OUTDIV2_10 (9 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 10 */
-# define SIM_CLKDIV1_OUTDIV2_11 (10 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 11 */
-# define SIM_CLKDIV1_OUTDIV2_12 (11 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 12 */
-# define SIM_CLKDIV1_OUTDIV2_13 (12 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 13 */
-# define SIM_CLKDIV1_OUTDIV2_14 (13 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 14 */
-# define SIM_CLKDIV1_OUTDIV2_15 (14 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 15 */
-# define SIM_CLKDIV1_OUTDIV2_16 (15 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 16 */
+ /* Bits 19-27: Reserved */
#define SIM_CLKDIV1_OUTDIV1_SHIFT (28) /* Bits 28-31: Clock 1 output divider value */
#define SIM_CLKDIV1_OUTDIV1_MASK (15 << SIM_CLKDIV1_OUTDIV1_SHIFT)
# define SIM_CLKDIV1_OUTDIV1(n) (((n)-1) << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by n, n=1..16 */
@@ -458,76 +329,53 @@
# define SIM_CLKDIV1_OUTDIV1_15 (14 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 15 */
# define SIM_CLKDIV1_OUTDIV1_16 (15 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 16 */
-/* System Clock Divider Register 2 */
-
-#define SIM_CLKDIV2_USBFRAC (1 << 0) /* Bit 0: USB clock divider fraction */
-#define SIM_CLKDIV2_USBDIV_SHIFT (1) /* Bits 1-3: USB clock divider divisor */
-#define SIM_CLKDIV2_USBDIV_MASK (7 << SIM_CLKDIV2_USBDIV_SHIFT)
- /* Bits 4-7: Reserved */
-#define SIM_CLKDIV2_I2SFRAC_SHIFT (8) /* Bits 8-15: I2S clock divider fraction */
-#define SIM_CLKDIV2_I2SFRAC_MASK (0xff << SIM_CLKDIV2_I2SFRAC_SHIFT)
- /* Bits 16-19: Reserved */
-#define SIM_CLKDIV2_I2SDIV_SHIFT (20) /* Bits 20-31: I2S clock divider value */
-#define SIM_CLKDIV2_I2SDIV_MASK (0xfff << SIM_CLKDIV2_I2SDIV_SHIFT)
-
/* Flash Configuration Register 1 */
- /* Bits 0-7: Reserved */
-#define SIM_FCFG1_DEPART_SHIFT (8) /* Bits 8-11: FlexNVM partition */
-#define SIM_FCFG1_DEPART_MASK (15 << SIM_FCFG1_DEPART_SHIFT)
- /* Bits 12-15: Reserved */
-#define SIM_FCFG1_EESIZE_SHIFT (16) /* Bits 16-19: EEPROM size*/
-#define SIM_FCFG1_EESIZE_MASK (15 << SIM_FCFG1_EESIZE_SHIFT)
-# define SIM_FCFG1_EESIZE_4KB (2 << SIM_FCFG1_EESIZE_SHIFT) /* 4 KB */
-# define SIM_FCFG1_EESIZE_2KB (3 << SIM_FCFG1_EESIZE_SHIFT) /* 2 KB */
-# define SIM_FCFG1_EESIZE_1KB (4 << SIM_FCFG1_EESIZE_SHIFT) /* 1 KB */
-# define SIM_FCFG1_EESIZE_512B (5 << SIM_FCFG1_EESIZE_SHIFT) /* 512 Bytes */
-# define SIM_FCFG1_EESIZE_256B (6 << SIM_FCFG1_EESIZE_SHIFT) /* 256 Bytes */
-# define SIM_FCFG1_EESIZE_128B (7 << SIM_FCFG1_EESIZE_SHIFT) /* 128 Bytes */
-# define SIM_FCFG1_EESIZE_64B (8 << SIM_FCFG1_EESIZE_SHIFT) /* 64 Bytes */
-# define SIM_FCFG1_EESIZE_32B (9 << SIM_FCFG1_EESIZE_SHIFT) /* 32 Bytes */
-# define SIM_FCFG1_EESIZE_NONE (15 << SIM_FCFG1_EESIZE_SHIFT) /* 0 Bytes */
- /* Bits 20-23: Reserved */
-#ifdef KL_K40
-#define SIM_FCFG1_PFSIZE_SHIFT (24) /* Bits 24-27: Program flash size (K40) */
-#define SIM_FCFG1_PFSIZE_MASK (15 << SIM_FCFG1_PFSIZE_SHIFT)
-# define SIM_FCFG1_PFSIZE_128KB (7 << SIM_FCFG1_PFSIZE_SHIFT) /* 128KB program flash, 4KB protection region */
-# define SIM_FCFG1_PFSIZE_256KB (9 << SIM_FCFG1_PFSIZE_SHIFT) /* 256KB program flash, 8KB protection region */
-# define SIM_FCFG1_PFSIZE_512KB (11 << SIM_FCFG1_PFSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
-# define SIM_FCFG1_PFSIZE_512KB2 (15 << SIM_FCFG1_PFSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
-#define SIM_FCFG1_NVMSIZE_SHIFT (28) /* Bits 28-31: FlexNVM size (K40)*/
-#define SIM_FCFG1_NVMSIZE_MASK (15 << SIM_FCFG1_NVMSIZE_SHIFT)
-# define SIM_FCFG1_NVMSIZE_NONE (0 << SIM_FCFG1_NVMSIZE_SHIFT) /* 0KB FlexNVM */
-# define SIM_FCFG1_NVMSIZE_128KB (7 << SIM_FCFG1_NVMSIZE_SHIFT) /* 128KB FlexNVM, 16KB protection region */
-# define SIM_FCFG1_NVMSIZE_256KB (9 << SIM_FCFG1_NVMSIZE_SHIFT) /* 256KB FlexNVM, 32KB protection region */
-# define SIM_FCFG1_NVMSIZE_256KB2 (15 << SIM_FCFG1_NVMSIZE_SHIFT) /* 256KB FlexNVM, 32KB protection region */
-#endif
-
-#ifdef KL_K60
-#define SIM_FCFG1_FSIZE_SHIFT (24) /* Bits 24-31: Flash size (K60)*/
-#define SIM_FCFG1_FSIZE_MASK (0xff << SIM_FCFG1_FSIZE_SHIFT)
-# define SIM_FCFG1_FSIZE_32KB (2 << SIM_FCFG1_FSIZE_SHIFT) /* 32KB program flash, 1KB protection region */
-# define SIM_FCFG1_FSIZE_64KB (4 << SIM_FCFG1_FSIZE_SHIFT) /* 64KB program flash, 2KB protection region */
-# define SIM_FCFG1_FSIZE_128KB (6 << SIM_FCFG1_FSIZE_SHIFT) /* 128KB program flash, 4KB protection region */
-# define SIM_FCFG1_FSIZE_256KB (8 << SIM_FCFG1_FSIZE_SHIFT) /* 256KB program flash, 8KB protection region */
-# define SIM_FCFG1_FSIZE_512KB (12 << SIM_FCFG1_FSIZE_SHIFT) /* 512KB program flash, 16KB protection region */
-#endif
+#define SIM_FCFG1_FLASHDIS (1 << 0) /* Bit 0: Flash Disable */
+#define SIM_FCFG1_FLASHDOZE (1 << 1) /* Bit 1: Flash Doze */
+ /* Bits 2-23: Reserved */
+#define SIM_FCFG1_PFSIZE_SHIFT (24) /* Bits 24-27: Program flash size */
+#define SIM_FCFG1_PFSIZE_MASK (15 << SIM_FCFG1_PFSIZE_SHIFT)
+# define SIM_FCFG1_PFSIZE_8KB (0 << SIM_FCFG1_PFSIZE_SHIFT) /* 8 KB of program flash memory,
+ * 0.25 KB protection region */
+# define SIM_FCFG1_PFSIZE_16KB (1 << SIM_FCFG1_PFSIZE_SHIFT) /* 16 KB of program flash memory,
+ * 0.5 KB protection region */
+# define SIM_FCFG1_PFSIZE_32KB (3 << SIM_FCFG1_PFSIZE_SHIFT) /* 32 KB of program flash memory,
+ * 1 KB protection region */
+# define SIM_FCFG1_PFSIZE_64KB (5 << SIM_FCFG1_PFSIZE_SHIFT) /* 64 KB of program flash memory,
+ * 2 KB protection region */
+# define SIM_FCFG1_PFSIZE_128KB (7 << SIM_FCFG1_PFSIZE_SHIFT) /* 128 KB of program flash memory,
+ * 4 KB protection region */
+# define SIM_FCFG1_PFSIZE_256KB (9 << SIM_FCFG1_PFSIZE_SHIFT) /* 256 KB of program flash memory,
+ * 8 KB protection region */
+ /* Bits 28-31: Reserved */
/* Flash Configuration Register 2 */
/* Bits 0-15: Reserved */
-#define SIM_FCFG2_MAXADDR1_SHIFT (16) /* Bits 16-21: Max address block 1 */
-#define SIM_FCFG2_MAXADDR1_MASK (nn << SIM_FCFG2_MAXADDR1_SHIFT)
- /* Bit 22: Reserved */
-#define SIM_FCFG2_PFLSH (1 << 23) /* Bit 23: Program flash */
-#define SIM_FCFG2_MAXADDR0_SHIFT (24) /* Bits 24-29: Max address block 0 */
-#define SIM_FCFG2_MAXADDR0_MASK (nn << SIM_FCFG2_MAXADDR0_SHIFT)
- /* Bit 30: Reserved */
-#define SIM_FCFG2_SWAPPFLSH (1 << 31) /* Bit 31: Swap program flash */
+#define SIM_FCFG2_MAXADDR0_SHIFT (24) /* Bits 24-30: Max address block */
+#define SIM_FCFG2_MAXADDR0_MASK (0x7f << SIM_FCFG2_MAXADDR0_SHIFT)
+ /* Bit 31: Reserved */
-/* Unique Identification Register High. 32-bit Unique Identification. */
+/* Unique Identification Register High. 16-bit Unique Identification. */
/* Unique Identification Register Mid-High. 32-bit Unique Identification. */
/* Unique Identification Register Mid Low. 32-bit Unique Identification. */
/* Unique Identification Register Low. 32-bit Unique Identification. */
+/* COP Control Register */
+
+#define SIM_COPC_COPW (1 << 0) /* Bit 2: COP windowed mode */
+#define SIM_COPC_COPCLKS (1 << 1) /* Bit 1: COP Clock Select */
+#define SIM_COPC_COPT_SHIFT (2) /* Bits 2-3: COP Watchdog Timeout */
+#define SIM_COPC_COPT_MASK (3 << SIM_COPC_COPT_SHIFT)
+# define SIM_COPC_COPT_DISABLED (0 << SIM_COPC_COPT_SHIFT) /* COP disabled */
+# define SIM_COPC_COPT_TO13 (1 << SIM_COPC_COPT_SHIFT) /* COP timeout after 2^5 LPO cycles or
+ * 2^13 bus clock cycles */
+# define SIM_COPC_COPT_TO16 (2 << SIM_COPC_COPT_SHIFT) /* COP timeout after 2^8 LPO cycles or
+ * 2^16 bus clock cycles */
+# define SIM_COPC_COPT_TO18 (3 << SIM_COPC_COPT_SHIFT) /* COP timeout after 2^10 LPO cycles or
+ * 2^18 bus clock cycles */
+
+/* Service COP Register. 8-bit value. */
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/kl/chip/kl_uart.h b/nuttx/arch/arm/src/kl/chip/kl_uart.h
index e04e9fd99..40ee713ca 100644
--- a/nuttx/arch/arm/src/kl/chip/kl_uart.h
+++ b/nuttx/arch/arm/src/kl/chip/kl_uart.h
@@ -58,33 +58,14 @@
#define KL_UART_S2_OFFSET 0x0005 /* UART Status Register 2 */
#define KL_UART_C3_OFFSET 0x0006 /* UART Control Register 3 */
#define KL_UART_D_OFFSET 0x0007 /* UART Data Register */
-#define KL_UART_MA1_OFFSET 0x0008 /* UART Match Address Registers 1 */
-#define KL_UART_MA2_OFFSET 0x0009 /* UART Match Address Registers 2 */
+#define KL_UART_MA1_OFFSET 0x0008 /* UART Match Address Registers 1 (UART0)*/
+#define KL_UART_MA2_OFFSET 0x0009 /* UART Match Address Registers 2 (UART0)*/
#define KL_UART_C4_OFFSET 0x000a /* UART Control Register 4 */
-#define KL_UART_C5_OFFSET 0x000b /* UART Control Register 5 */
-#define KL_UART_ED_OFFSET 0x000c /* UART Extended Data Register */
-#define KL_UART_MODEM_OFFSET 0x000d /* UART Modem Register */
-#define KL_UART_IR_OFFSET 0x000e /* UART Infrared Register */
-#define KL_UART_PFIFO_OFFSET 0x0010 /* UART FIFO Parameters */
-#define KL_UART_CFIFO_OFFSET 0x0011 /* UART FIFO Control Register */
-#define KL_UART_SFIFO_OFFSET 0x0012 /* UART FIFO Status Register */
-#define KL_UART_TWFIFO_OFFSET 0x0013 /* UART FIFO Transmit Watermark */
-#define KL_UART_TCFIFO_OFFSET 0x0014 /* UART FIFO Transmit Count */
-#define KL_UART_RWFIFO_OFFSET 0x0015 /* UART FIFO Receive Watermark */
-#define KL_UART_RCFIFO_OFFSET 0x0016 /* UART FIFO Receive Count */
-#define KL_UART_C7816_OFFSET 0x0017 /* UART 7816 Control Register */
-#define KL_UART_IE7816_OFFSET 0x0018 /* UART 7816 Interrupt Enable Register */
-#define KL_UART_IS7816_OFFSET 0x0019 /* UART 7816 Interrupt Status Register */
-#define KL_UART_WP7816T0_OFFSET 0x001a /* UART 7816 Wait Parameter Register */
-#define KL_UART_WP7816T1_OFFSET 0x001b /* UART 7816 Wait Parameter Register */
-#define KL_UART_WN7816_OFFSET 0x001c /* UART 7816 Wait N Register */
-#define KL_UART_WF7816_OFFSET 0x001d /* UART 7816 Wait FD Register */
-#define KL_UART_ET7816_OFFSET 0x001e /* UART 7816 Error Threshold Register */
-#define KL_UART_TL7816_OFFSET 0x001f /* UART 7816 Transmit Length Register */
+#define KL_UART_C5_OFFSET 0x000b /* UART Control Register 5 (UART0) */
/* Register Addresses ***************************************************************/
-#if (KL_NISO7816+KL_NUART) > 0
+#if (KL_NUART) > 0
# define KL_UART0_BDH (KL_UART0_BASE+KL_UART_BDH_OFFSET)
# define KL_UART0_BDL (KL_UART0_BASE+KL_UART_BDL_OFFSET)
# define KL_UART0_C1 (KL_UART0_BASE+KL_UART_C1_OFFSET)
@@ -97,28 +78,9 @@
# define KL_UART0_MA2 (KL_UART0_BASE+KL_UART_MA2_OFFSET)
# define KL_UART0_C4 (KL_UART0_BASE+KL_UART_C4_OFFSET)
# define KL_UART0_C5 (KL_UART0_BASE+KL_UART_C5_OFFSET)
-# define KL_UART0_ED (KL_UART0_BASE+KL_UART_ED_OFFSET)
-# define KL_UART0_MODEM (KL_UART0_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART0_IR (KL_UART0_BASE+KL_UART_IR_OFFSET)
-# define KL_UART0_PFIFO (KL_UART0_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART0_CFIFO (KL_UART0_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART0_SFIFO (KL_UART0_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART0_TWFIFO (KL_UART0_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART0_TCFIFO (KL_UART0_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART0_RWFIFO (KL_UART0_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART0_RCFIFO (KL_UART0_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART0_C7816 (KL_UART0_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART0_IE7816 (KL_UART0_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART0_IS7816 (KL_UART0_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART0_WP7816T0 (KL_UART0_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART0_WP7816T1 (KL_UART0_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART0_WN7816 (KL_UART0_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART0_WF7816 (KL_UART0_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART0_ET7816 (KL_UART0_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART0_TL7816 (KL_UART0_BASE+KL_UART_TL7816_OFFSET)
#endif
-#if (KL_NISO7816+KL_NUART) > 1
+#if (KL_NUART) > 1
# define KL_UART1_BDH (KL_UART1_BASE+KL_UART_BDH_OFFSET)
# define KL_UART1_BDL (KL_UART1_BASE+KL_UART_BDL_OFFSET)
# define KL_UART1_C1 (KL_UART1_BASE+KL_UART_C1_OFFSET)
@@ -127,32 +89,10 @@
# define KL_UART1_S2 (KL_UART1_BASE+KL_UART_S2_OFFSET)
# define KL_UART1_C3 (KL_UART1_BASE+KL_UART_C3_OFFSET)
# define KL_UART1_D (KL_UART1_BASE+KL_UART_D_OFFSET)
-# define KL_UART1_MA1 (KL_UART1_BASE+KL_UART_MA1_OFFSET)
-# define KL_UART1_MA2 (KL_UART1_BASE+KL_UART_MA2_OFFSET)
# define KL_UART1_C4 (KL_UART1_BASE+KL_UART_C4_OFFSET)
-# define KL_UART1_C5 (KL_UART1_BASE+KL_UART_C5_OFFSET)
-# define KL_UART1_ED (KL_UART1_BASE+KL_UART_ED_OFFSET)
-# define KL_UART1_MODEM (KL_UART1_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART1_IR (KL_UART1_BASE+KL_UART_IR_OFFSET)
-# define KL_UART1_PFIFO (KL_UART1_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART1_CFIFO (KL_UART1_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART1_SFIFO (KL_UART1_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART1_TWFIFO (KL_UART1_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART1_TCFIFO (KL_UART1_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART1_RWFIFO (KL_UART1_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART1_RCFIFO (KL_UART1_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART1_C7816 (KL_UART1_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART1_IE7816 (KL_UART1_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART1_IS7816 (KL_UART1_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART1_WP7816T0 (KL_UART1_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART1_WP7816T1 (KL_UART1_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART1_WN7816 (KL_UART1_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART1_WF7816 (KL_UART1_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART1_ET7816 (KL_UART1_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART1_TL7816 (KL_UART1_BASE+KL_UART_TL7816_OFFSET)
#endif
-#if (KL_NISO7816+KL_NUART) > 2
+#if (KL_NUART) > 2
# define KL_UART2_BDH (KL_UART2_BASE+KL_UART_BDH_OFFSET)
# define KL_UART2_BDL (KL_UART2_BASE+KL_UART_BDL_OFFSET)
# define KL_UART2_C1 (KL_UART2_BASE+KL_UART_C1_OFFSET)
@@ -161,131 +101,7 @@
# define KL_UART2_S2 (KL_UART2_BASE+KL_UART_S2_OFFSET)
# define KL_UART2_C3 (KL_UART2_BASE+KL_UART_C3_OFFSET)
# define KL_UART2_D (KL_UART2_BASE+KL_UART_D_OFFSET)
-# define KL_UART2_MA1 (KL_UART2_BASE+KL_UART_MA1_OFFSET)
-# define KL_UART2_MA2 (KL_UART2_BASE+KL_UART_MA2_OFFSET)
# define KL_UART2_C4 (KL_UART2_BASE+KL_UART_C4_OFFSET)
-# define KL_UART2_C5 (KL_UART2_BASE+KL_UART_C5_OFFSET)
-# define KL_UART2_ED (KL_UART2_BASE+KL_UART_ED_OFFSET)
-# define KL_UART2_MODEM (KL_UART2_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART2_IR (KL_UART2_BASE+KL_UART_IR_OFFSET)
-# define KL_UART2_PFIFO (KL_UART2_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART2_CFIFO (KL_UART2_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART2_SFIFO (KL_UART2_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART2_TWFIFO (KL_UART2_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART2_TCFIFO (KL_UART2_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART2_RWFIFO (KL_UART2_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART2_RCFIFO (KL_UART2_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART2_C7816 (KL_UART2_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART2_IE7816 (KL_UART2_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART2_IS7816 (KL_UART2_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART2_WP7816T0 (KL_UART2_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART2_WP7816T1 (KL_UART2_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART2_WN7816 (KL_UART2_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART2_WF7816 (KL_UART2_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART2_ET7816 (KL_UART2_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART2_TL7816 (KL_UART2_BASE+KL_UART_TL7816_OFFSET)
-#endif
-
-#if (KL_NISO7816+KL_NUART) > 3
-# define KL_UART3_BDH (KL_UART3_BASE+KL_UART_BDH_OFFSET)
-# define KL_UART3_BDL (KL_UART3_BASE+KL_UART_BDL_OFFSET)
-# define KL_UART3_C1 (KL_UART3_BASE+KL_UART_C1_OFFSET)
-# define KL_UART3_C2 (KL_UART3_BASE+KL_UART_C2_OFFSET)
-# define KL_UART3_S1 (KL_UART3_BASE+KL_UART_S1_OFFSET)
-# define KL_UART3_S2 (KL_UART3_BASE+KL_UART_S2_OFFSET)
-# define KL_UART3_C3 (KL_UART3_BASE+KL_UART_C3_OFFSET)
-# define KL_UART3_D (KL_UART3_BASE+KL_UART_D_OFFSET)
-# define KL_UART3_MA1 (KL_UART3_BASE+KL_UART_MA1_OFFSET)
-# define KL_UART3_MA2 (KL_UART3_BASE+KL_UART_MA2_OFFSET)
-# define KL_UART3_C4 (KL_UART3_BASE+KL_UART_C4_OFFSET)
-# define KL_UART3_C5 (KL_UART3_BASE+KL_UART_C5_OFFSET)
-# define KL_UART3_ED (KL_UART3_BASE+KL_UART_ED_OFFSET)
-# define KL_UART3_MODEM (KL_UART3_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART3_IR (KL_UART3_BASE+KL_UART_IR_OFFSET)
-# define KL_UART3_PFIFO (KL_UART3_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART3_CFIFO (KL_UART3_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART3_SFIFO (KL_UART3_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART3_TWFIFO (KL_UART3_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART3_TCFIFO (KL_UART3_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART3_RWFIFO (KL_UART3_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART3_RCFIFO (KL_UART3_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART3_C7816 (KL_UART3_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART3_IE7816 (KL_UART3_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART3_IS7816 (KL_UART3_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART3_WP7816T0 (KL_UART3_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART3_WP7816T1 (KL_UART3_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART3_WN7816 (KL_UART3_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART3_WF7816 (KL_UART3_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART3_ET7816 (KL_UART3_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART3_TL7816 (KL_UART3_BASE+KL_UART_TL7816_OFFSET)
-#endif
-
-#if (KL_NISO7816+KL_NUART) > 4
-# define KL_UART4_BDH (KL_UART4_BASE+KL_UART_BDH_OFFSET)
-# define KL_UART4_BDL (KL_UART4_BASE+KL_UART_BDL_OFFSET)
-# define KL_UART4_C1 (KL_UART4_BASE+KL_UART_C1_OFFSET)
-# define KL_UART4_C2 (KL_UART4_BASE+KL_UART_C2_OFFSET)
-# define KL_UART4_S1 (KL_UART4_BASE+KL_UART_S1_OFFSET)
-# define KL_UART4_S2 (KL_UART4_BASE+KL_UART_S2_OFFSET)
-# define KL_UART4_C3 (KL_UART4_BASE+KL_UART_C3_OFFSET)
-# define KL_UART4_D (KL_UART4_BASE+KL_UART_D_OFFSET)
-# define KL_UART4_MA1 (KL_UART4_BASE+KL_UART_MA1_OFFSET)
-# define KL_UART4_MA2 (KL_UART4_BASE+KL_UART_MA2_OFFSET)
-# define KL_UART4_C4 (KL_UART4_BASE+KL_UART_C4_OFFSET)
-# define KL_UART4_C5 (KL_UART4_BASE+KL_UART_C5_OFFSET)
-# define KL_UART4_ED (KL_UART4_BASE+KL_UART_ED_OFFSET)
-# define KL_UART4_MODEM (KL_UART4_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART4_IR (KL_UART4_BASE+KL_UART_IR_OFFSET)
-# define KL_UART4_PFIFO (KL_UART4_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART4_CFIFO (KL_UART4_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART4_SFIFO (KL_UART4_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART4_TWFIFO (KL_UART4_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART4_TCFIFO (KL_UART4_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART4_RWFIFO (KL_UART4_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART4_RCFIFO (KL_UART4_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART4_C7816 (KL_UART4_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART4_IE7816 (KL_UART4_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART4_IS7816 (KL_UART4_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART4_WP7816T0 (KL_UART4_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART4_WP7816T1 (KL_UART4_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART4_WN7816 (KL_UART4_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART4_WF7816 (KL_UART4_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART4_ET7816 (KL_UART4_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART4_TL7816 (KL_UART4_BASE+KL_UART_TL7816_OFFSET)
-#endif
-
-#if (KL_NISO7816+KL_NUART) > 5
-# define KL_UART5_BDH (KL_UART5_BASE+KL_UART_BDH_OFFSET)
-# define KL_UART5_BDL (KL_UART5_BASE+KL_UART_BDL_OFFSET)
-# define KL_UART5_C1 (KL_UART5_BASE+KL_UART_C1_OFFSET)
-# define KL_UART5_C2 (KL_UART5_BASE+KL_UART_C2_OFFSET)
-# define KL_UART5_S1 (KL_UART5_BASE+KL_UART_S1_OFFSET)
-# define KL_UART5_S2 (KL_UART5_BASE+KL_UART_S2_OFFSET)
-# define KL_UART5_C3 (KL_UART5_BASE+KL_UART_C3_OFFSET)
-# define KL_UART5_D (KL_UART5_BASE+KL_UART_D_OFFSET)
-# define KL_UART5_MA1 (KL_UART5_BASE+KL_UART_MA1_OFFSET)
-# define KL_UART5_MA2 (KL_UART5_BASE+KL_UART_MA2_OFFSET)
-# define KL_UART5_C4 (KL_UART5_BASE+KL_UART_C4_OFFSET)
-# define KL_UART5_C5 (KL_UART5_BASE+KL_UART_C5_OFFSET)
-# define KL_UART5_ED (KL_UART5_BASE+KL_UART_ED_OFFSET)
-# define KL_UART5_MODEM (KL_UART5_BASE+KL_UART_MODEM_OFFSET)
-# define KL_UART5_IR (KL_UART5_BASE+KL_UART_IR_OFFSET)
-# define KL_UART5_PFIFO (KL_UART5_BASE+KL_UART_PFIFO_OFFSET)
-# define KL_UART5_CFIFO (KL_UART5_BASE+KL_UART_CFIFO_OFFSET)
-# define KL_UART5_SFIFO (KL_UART5_BASE+KL_UART_SFIFO_OFFSET)
-# define KL_UART5_TWFIFO (KL_UART5_BASE+KL_UART_TWFIFO_OFFSET)
-# define KL_UART5_TCFIFO (KL_UART5_BASE+KL_UART_TCFIFO_OFFSET)
-# define KL_UART5_RWFIFO (KL_UART5_BASE+KL_UART_RWFIFO_OFFSET)
-# define KL_UART5_RCFIFO (KL_UART5_BASE+KL_UART_RCFIFO_OFFSET)
-# define KL_UART5_C7816 (KL_UART5_BASE+KL_UART_C7816_OFFSET)
-# define KL_UART5_IE7816 (KL_UART5_BASE+KL_UART_IE7816_OFFSET)
-# define KL_UART5_IS7816 (KL_UART5_BASE+KL_UART_IS7816_OFFSET)
-# define KL_UART5_WP7816T0 (KL_UART5_BASE+KL_UART_WP7816T0_OFFSET)
-# define KL_UART5_WP7816T1 (KL_UART5_BASE+KL_UART_WP7816T1_OFFSET)
-# define KL_UART5_WN7816 (KL_UART5_BASE+KL_UART_WN7816_OFFSET)
-# define KL_UART5_WF7816 (KL_UART5_BASE+KL_UART_WF7816_OFFSET)
-# define KL_UART5_ET7816 (KL_UART5_BASE+KL_UART_ET7816_OFFSET)
-# define KL_UART5_TL7816 (KL_UART5_BASE+KL_UART_TL7816_OFFSET)
#endif
/* Register Bit Definitions *********************************************************/
@@ -293,22 +109,17 @@
#define UART_BDH_SBR_SHIFT (0) /* Bits 0-4: MS Bits 8-13 of the UART Baud Rate Bits */
#define UART_BDH_SBR_MASK (31 << UART_BDH_SBR_SHIFT)
- /* Bit 5: Reserved */
+# define UART_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))<<UART_BDH_SBR_SHIFT))&UART_BDH_SBR_MASK)
+#define UART_BDH_SBNS (1 << 5) /* Bit 5: Stop Bit Number Select */
#define UART_BDH_RXEDGIE (1 << 6) /* Bit 6: RxD Input Active Edge Interrupt Enable */
#define UART_BDH_LBKDIE (1 << 7) /* Bit 7: LIN Break Detect Interrupt Enable */
-/* BDH Bit Fields */
-#define UARTLP_BDH_SBR_MASK 0x1Fu
-#define UARTLP_BDH_SBR_SHIFT 0
-#define UARTLP_BDH_SBR(x) (((uint8_t)(((uint8_t)(x))<<UARTLP_BDH_SBR_SHIFT))&UARTLP_BDH_SBR_MASK)
-
-/* BDL Bit Fields */
-#define UARTLP_BDL_SBR_MASK 0xFFu
-#define UARTLP_BDL_SBR_SHIFT 0
-#define UARTLP_BDL_SBR(x) (((uint8_t)(((uint8_t)(x))<<UARTLP_BDL_SBR_SHIFT))&UARTLP_BDL_SBR_MASK)
-
/* UART Baud Rate Register Low. Bits 0-7 of the UART baud rate bits. */
+#define UART_BDL_SBR_MASK 0xffu
+#define UART_BDL_SBR_SHIFT 0
+# define UART_BDL_SBR(x) (((uint8_t)(((uint8_t)(x))<<UART_BDL_SBR_SHIFT))&UART_BDL_SBR_MASK)
+
/* UART Control Register 1 */
#define UART_C1_PT (1 << 0) /* Bit 0: Parity Type */
@@ -317,7 +128,8 @@
#define UART_C1_WAKE (1 << 3) /* Bit 3: Receiver Wakeup Method Select */
#define UART_C1_M (1 << 4) /* Bit 4: 9-bit or 8-bit Mode Select */
#define UART_C1_RSRC (1 << 5) /* Bit 5: Receiver Source Select */
-#define UART_C1_UARTSWAI (1 << 6) /* Bit 6: UART Stops in Wait Mode */
+#define UART_C1_DOZEEN (1 << 6) /* Bit 6: Doze Enable (UART0) */
+#define UART_C1_UARTSWAI (1 << 6) /* Bit 6: UART Stops in Wait Mode (UART1 and 2) */
#define UART_C1_LOOPS (1 << 7) /* Bit 7: Loop Mode Select */
/* UART Control Register 2 */
@@ -350,7 +162,7 @@
#define UART_S2_BRK13 (1 << 2) /* Bit 2: Break Transmit Character Length */
#define UART_S2_RWUID (1 << 3) /* Bit 3: Receive Wakeup Idle Detect */
#define UART_S2_RXINV (1 << 4) /* Bit 4: Receive Data Inversion */
-#define UART_S2_MSBF (1 << 5) /* Bit 5: Most Significant Bit First */
+#define UART_S2_MSBF (1 << 5) /* Bit 5: Most Significant Bit First (UART0) */
#define UART_S2_RXEDGIF (1 << 6) /* Bit 6: RxD Pin Active Edge Interrupt Flag */
#define UART_S2_LBKDIF (1 << 7) /* Bit 7: LIN Break Detect Interrupt Flag */
@@ -362,149 +174,37 @@
#define UART_C3_ORIE (1 << 3) /* Bit 3: Overrun Error Interrupt Enable */
#define UART_C3_TXINV (1 << 4) /* Bit 4: Transmit Data Inversion */
#define UART_C3_TXDIR (1 << 5) /* Bit 5: Transmitter Pin Data Direction in Single-Wire mode */
+#define UART_C3_R9 (1 << 6) /* Bit 6: Receive Bit 9 (UART0) */
#define UART_C3_T8 (1 << 6) /* Bit 6: Transmit Bit 8 */
-#define UART_C3_R8 (1 << 7) /* Bit 7: Received Bit 8 */
+#define UART_C3_T9 (1 << 7) /* Bit 7: Transmit Bit 9 (UART0) */
+#define UART_C3_R8 (1 << 7) /* Bit 7: Receive Bit 8 */
/* UART Data Register: 8-bit data register. */
/* UART Match Address Registers 1 & 2: 8-bit address registers */
-/* UART Control Register 4 */
+/* UART Control Register 4 (UART0) */
-#define UART_C4_BRFA_SHIFT (0) /* Bits 0-4: Baud Rate Fine Adjust */
-#define UART_C4_BRFA_MASK (31 << UART_C4_BRFA_SHIFT)
+#define UART_C4_OSR_SHIFT (0) /* Bits 0-4: Over Sampling Ratio */
+#define UART_C4_OSR_MASK (0x1f << UART_C4_OSR_SHIFT)
#define UART_C4_M10 (1 << 5) /* Bit 5: 10-bit Mode select */
#define UART_C4_MAEN2 (1 << 6) /* Bit 6: Match Address Mode Enable 2 */
#define UART_C4_MAEN1 (1 << 7) /* Bit 7: Match Address Mode Enable 1 */
-/* UART Control Register 5 */
+/* UART Control Register 4 (UART1 and 2) */
/* Bit 0-4: Reserved */
-#define UART_C5_RDMAS (1 << 5) /* Bit 5: Receiver Full DMA Select */
+#define UART_C4_RDMAS (1 << 5) /* Bit 5: This field is reserved */
+ /* Bit 6: Reserved */
+#define UART_C4_TDMAS (1 << 7) /* Bit 7: Transmitter DMA Select */
+
+/* UART Control Register 5 (UART0) */
+
+#define UART_C5_RESYNCDIS (1 << 0) /* Bit 0: Resynchronization Disable */
+#define UART_C5_BOTHEDGE (1 << 1) /* Bit 1: Both Edge Sampling */
+ /* Bit 2-4: Reserved */
+#define UART_C5_RDMAE (1 << 5) /* Bit 5: Receiver Full DMA Enable */
/* Bit 6: Reserved */
-#define UART_C5_TDMAS (1 << 7) /* Bit 7: Transmitter DMA Select */
-
-/* UART Extended Data Register */
-
- /* Bit 0-5: Reserved */
-#define UART_ED_PARITYE (1 << 6) /* Bit 6: The current received dataword contained
- * in D and C3[R8] was received with a parity error */
-#define UART_ED_NOISY (1 << 7) /* Bit 7: The current received dataword contained
- * in D and C3[R8] was received with noise */
-
-/* UART Modem Register */
-
-#define UART_MODEM_TXCTSE (1 << 0) /* Bit 0: Transmitter clear-to-send enable */
-#define UART_MODEM_TXRTSE (1 << 1) /* Bit 1: Transmitter request-to-send enable */
-#define UART_MODEM_TXRTSPOL (1 << 2) /* Bit 2: Transmitter request-to-send polarity */
-#define UART_MODEM_RXRTSE (1 << 3) /* Bit 3: Receiver request-to-send enable */
- /* Bits 4-7: Reserved */
-
-/* UART Infrared Register */
-
-#define UART_IR_TNP_SHIFT (0) /* Bits 0-1: Transmitter narrow pulse */
-#define UART_IR_TNP_MASK (3 << UART_IR_TNP_SHIFT)
-# define UART_IR_TNP_316THS (0 << UART_IR_TNP_SHIFT) /* 3/16 */
-# define UART_IR_TNP_16TH (1 << UART_IR_TNP_SHIFT) /* 1/16 */
-# define UART_IR_TNP_32ND (2 << UART_IR_TNP_SHIFT) /* 1/32 */
-# define UART_IR_TNP_4TH (3 << UART_IR_TNP_SHIFT) /* 1/4 */
-#define UART_IR_IREN (1 << 2) /* Bit 2: Infrared enable */
- /* Bits 3-7: Reserved */
-
-/* UART FIFO Parameters */
-
-#define UART_PFIFO_RXFIFOSIZE_SHIFT (0) /* Bits 0-2: Receive FIFO. Buffer Depth */
-#define UART_PFIFO_RXFIFOSIZE_MASK (7 << UART_PFIFO_RXFIFOSIZE_SHIFT)
-# define UART_PFIFO_RXFIFOSIZE_1 (0 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 1 */
-# define UART_PFIFO_RXFIFOSIZE_4 (1 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 4 */
-# define UART_PFIFO_RXFIFOSIZE_8 (2 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 8 */
-# define UART_PFIFO_RXFIFOSIZE_16 (3 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 16 */
-# define UART_PFIFO_RXFIFOSIZE_32 (4 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 32 */
-# define UART_PFIFO_RXFIFOSIZE_64 (5 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 64 */
-# define UART_PFIFO_RXFIFOSIZE_128 (6 << UART_PFIFO_RXFIFOSIZE_SHIFT) /* 128 */
-#define UART_PFIFO_RXFE (1 << 3) /* Bit 3: Receive FIFO Enable */
-#define UART_PFIFO_TXFIFOSIZE_SHIFT (4) /* Bits 4-6: Transmit FIFO. Buffer Depth */
-#define UART_PFIFO_TXFIFOSIZE_MASK (7 << UART_PFIFO_TXFIFOSIZE_SHIFT)
-# define UART_PFIFO_TXFIFOSIZE_1 (0 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 1 */
-# define UART_PFIFO_TXFIFOSIZE_4 (1 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 4 */
-# define UART_PFIFO_TXFIFOSIZE_8 (2 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 8 */
-# define UART_PFIFO_TXFIFOSIZE_16 (3 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 16 */
-# define UART_PFIFO_TXFIFOSIZE_32 (4 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 32 */
-# define UART_PFIFO_TXFIFOSIZE_64 (5 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 64 */
-# define UART_PFIFO_TXFIFOSIZE_128 (6 << UART_PFIFO_TXFIFOSIZE_SHIFT) /* 128 */
-#define UART_PFIFO_TXFE (1 << 7) /* Bit 7: Transmit FIFO Enable */
-
-/* UART FIFO Control Register */
-
-#define UART_CFIFO_RXUFE (1 << 0) /* Bit 0: Receive FIFO Underflow Interrupt Enable */
-#define UART_CFIFO_TXOFE (1 << 1) /* Bit 1: Transmit FIFO Overflow Interrupt Enable */
- /* Bits 2-5: Reserved */
-#define UART_CFIFO_RXFLUSH (1 << 6) /* Bit 6: Receive FIFO/Buffer Flush */
-#define UART_CFIFO_TXFLUSH (1 << 7) /* Bit 7: Transmit FIFO/Buffer Flush */
-
-/* UART FIFO Status Register */
-
-#define UART_SFIFO_RXUF (1 << 0) /* Bit 0: Receiver Buffer Underflow Flag */
-#define UART_SFIFO_TXOF (1 << 1) /* Bit 1: Transmitter Buffer Overflow Flag */
- /* Bits 2-5: Reserved */
-#define UART_SFIFO_RXEMPT (1 << 6) /* Bit 6: Receive Buffer/FIFO Empty */
-#define UART_SFIFO_TXEMPT (1 << 7) /* Bit 7: Transmit Buffer/FIFO Empty */
-
-/* UART FIFO Transmit Watermark. 8-bit watermark value. */
-/* UART FIFO Transmit Count. 8-bit count value */
-/* UART FIFO Receive Watermark. 8-bit watermark value. */
-/* UART FIFO Receive Count. 8-bit count value */
-
-/* UART 7816 Control Register */
-
-#define UART_C7816_ISO7816E (1 << 0) /* Bit 0: ISO-7816 Functionality Enabled */
-#define UART_C7816_TTYPE (1 << 1) /* Bit 1: Transfer Type */
-#define UART_C7816_INIT (1 << 2) /* Bit 2: Detect Initial Character */
-#define UART_C7816_ANACK (1 << 3) /* Bit 3: Generate NACK on Error */
-#define UART_C7816_ONACK (1 << 4) /* Bit 4: Generate NACK on Overflow */
- /* Bits 5-7: Reserved */
-
-/* UART 7816 Interrupt Enable Register */
-
-#define UART_IE7816_RXTE (1 << 0) /* Bit 0: Receive Threshold Exceeded Interrupt Enable */
-#define UART_IE7816_TXTE (1 << 1) /* Bit 1: Transmit Threshold Exceeded Interrupt Enable */
-#define UART_IE7816_GTVE (1 << 2) /* Bit 2: Guard Timer Violated Interrupt Enable */
- /* Bit 3: Reserved */
-#define UART_IE7816_INITDE (1 << 4) /* Bit 4: Initial Character Detected Interrupt Enable */
-#define UART_IE7816_BWTE (1 << 5) /* Bit 5: Block Wait Timer Interrupt Enable */
-#define UART_IE7816_CWTE (1 << 6) /* Bit 6: Character Wait Timer Interrupt Enable */
-#define UART_IE7816_WTE (1 << 7) /* Bit 7: Wait Timer Interrupt Enable */
-
-/* UART 7816 Interrupt Status Register */
-
-#define UART_IS7816_RXT (1 << 0) /* Bit 0: Receive Threshold Exceeded Interrupt */
-#define UART_IS7816_TXT (1 << 1) /* Bit 1: Transmit Threshold Exceeded Interrupt */
-#define UART_IS7816_GTV (1 << 2) /* Bit 2: Guard Timer Violated Interrupt */
- /* Bit 3: Reserved */
-#define UART_IS7816_INITD (1 << 4) /* Bit 4: Initial Character Detected Interrupt */
-#define UART_IS7816_BWT (1 << 5) /* Bit 5: Block Wait Timer Interrupt */
-#define UART_IS7816_CWT (1 << 6) /* Bit 6: Character Wait Timer Interrupt */
-#define UART_IS7816_WT (1 << 7) /* Bit 7: Wait Timer Interrupt */
-
-/* UART 7816 Wait Parameter Register. 8-bit Wait Timer Interrupt value. */
-
-/* UART 7816 Wait Parameter Register */
-
-#define UART_WP7816T1_BWI_SHIFT (0) /* Bit 0-3: Block Wait Time Integer(C7816[TTYPE] = 1) */
-#define UART_WP7816T1_BWI_MASK (15 << UART_WP7816T1_BWI_SHIFT)
-#define UART_WP7816T1_CWI_SHIFT (4) /* Bits 4-7: Character Wait Time Integer (C7816[TTYPE] = 1) */
-#define UART_WP7816T1_CWI_MASK (15 << UART_WP7816T1_CWI_SHIFT)
-
-/* UART 7816 Wait N Register. 8-bit Guard Band value. */
-/* UART 7816 Wait FD Register. 8-bit FD Multiplier value. */
-
-/* UART 7816 Error Threshold Register */
-
-#define UART_ET7816_RXTHRESH_SHIFT (0) /* Bit 0-3: Receive NACK Threshold */
-#define UART_ET7816_RXTHRESH_MASK (15 << UART_ET7816_RXTHRESHOLD_SHIFT)
-#define UART_ET7816_TXTHRESH_SHIFT (4) /* Bits 4-7: Transmit NACK Threshold */
-#define UART_ET7816_TXTHRESH_MASK (15 << UART_ET7816_TXTHRESHOLD_MASK)
-
-/* UART 7816 Transmit Length Register. 8-bit Transmit Length value */
+#define UART_C5_TDMAE (1 << 7) /* Bit 7: Transmitter DMA Enable */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/kl/kl_clockconfig.c b/nuttx/arch/arm/src/kl/kl_clockconfig.c
index d996383d7..b28c20ac2 100644
--- a/nuttx/arch/arm/src/kl/kl_clockconfig.c
+++ b/nuttx/arch/arm/src/kl/kl_clockconfig.c
@@ -116,7 +116,7 @@ void kl_pllconfig(void)
/* System oscillator drives 32 kHz clock for various peripherals (OSC32KSEL=0) */
regval32 = getreg32(KL_SIM_SOPT1);
- regval32 &= ~(SIM_SOPT1_OSC32KSEL);
+ regval32 &= ~(SIM_SOPT1_OSC32KSEL_MASK);
putreg32(regval32, KL_SIM_SOPT1);
/* Select PLL as a clock source for various peripherals (PLLFLLSEL=1)
diff --git a/nuttx/arch/arm/src/kl/kl_config.h b/nuttx/arch/arm/src/kl/kl_config.h
index a85b9b9c8..a76075d68 100644
--- a/nuttx/arch/arm/src/kl/kl_config.h
+++ b/nuttx/arch/arm/src/kl/kl_config.h
@@ -50,27 +50,13 @@
************************************************************************************/
/* Configuration *********************************************************************/
-/* Make that no unsupport UARTs are enabled */
-#ifndef KL_NISO7816
-# define KL_NISO7816 0
-#endif
-
-#if (KL_NISO7816 + KL_NUART) < 6
-# undef CONFIG_KL_UART5
-# if (KL_NISO7816 + KL_NUART) < 5
-# undef CONFIG_KL_UART4
-# if (KL_NISO7816 + KL_NUART) < 4
-# undef CONFIG_KL_UART3
-# if (KL_NISO7816 + KL_NUART) < 3
-# undef CONFIG_KL_UART2
-# if (KL_NISO7816 + KL_NUART) < 2
-# undef CONFIG_KL_UART1
-# if (KL_NISO7816 + KL_NUART) < 1
-# undef CONFIG_KL_UART0
-# endif
-# endif
-# endif
+#if (KL_NUART) < 3
+# undef CONFIG_KL_UART2
+# if (KL_NUART) < 2
+# undef CONFIG_KL_UART1
+# if (KL_NUART) < 1
+# undef CONFIG_KL_UART0
# endif
# endif
#endif
@@ -78,9 +64,7 @@
/* Are any UARTs enabled? */
#undef HAVE_UART_DEVICE
-#if defined(CONFIG_KL_UART0) || defined(CONFIG_KL_UART1) || \
- defined(CONFIG_KL_UART2) || defined(CONFIG_KL_UART3) || \
- defined(CONFIG_KL_UART5)
+#if defined(CONFIG_KL_UART0) || defined(CONFIG_KL_UART1) || defined(CONFIG_KL_UART2)
# define HAVE_UART_DEVICE 1
#endif
@@ -91,52 +75,19 @@
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_KL_UART0)
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_KL_UART1)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_KL_UART2)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
-# define HAVE_SERIAL_CONSOLE 1
-#elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(CONFIG_KL_UART3)
-# undef CONFIG_UART0_SERIAL_CONSOLE
-# undef CONFIG_UART1_SERIAL_CONSOLE
-# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
-# define HAVE_SERIAL_CONSOLE 1
-#elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_KL_UART4)
-# undef CONFIG_UART0_SERIAL_CONSOLE
-# undef CONFIG_UART1_SERIAL_CONSOLE
-# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
-# define HAVE_SERIAL_CONSOLE 1
-#elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_KL_UART5)
-# undef CONFIG_UART0_SERIAL_CONSOLE
-# undef CONFIG_UART1_SERIAL_CONSOLE
-# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
# define HAVE_SERIAL_CONSOLE 1
#else
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
-# undef CONFIG_UART3_SERIAL_CONSOLE
-# undef CONFIG_UART4_SERIAL_CONSOLE
-# undef CONFIG_UART5_SERIAL_CONSOLE
# undef HAVE_SERIAL_CONSOLE
#endif
@@ -145,9 +96,6 @@
# undef CONFIG_UART0_FLOWCONTROL
# undef CONFIG_UART1_FLOWCONTROL
# undef CONFIG_UART2_FLOWCONTROL
-# undef CONFIG_UART3_FLOWCONTROL
-# undef CONFIG_UART4_FLOWCONTROL
-# undef CONFIG_UART5_FLOWCONTROL
/* UART FIFO support is not fully implemented.
*
@@ -174,15 +122,6 @@
#ifndef CONFIG_KL_UART2PRIO
# define CONFIG_KL_UART2PRIO NVIC_SYSH_PRIORITY_DEFAULT
#endif
-#ifndef CONFIG_KL_UART3PRIO
-# define CONFIG_KL_UART3PRIO NVIC_SYSH_PRIORITY_DEFAULT
-#endif
-#ifndef CONFIG_KL_UART4PRIO
-# define CONFIG_KL_UART4PRIO NVIC_SYSH_PRIORITY_DEFAULT
-#endif
-#ifndef CONFIG_KL_UART5PRIO
-# define CONFIG_KL_UART5PRIO NVIC_SYSH_PRIORITY_DEFAULT
-#endif
/* Ethernet controller configuration */
diff --git a/nuttx/arch/arm/src/kl/kl_lowputc.c b/nuttx/arch/arm/src/kl/kl_lowputc.c
index 9f589ad1c..d9d3604e1 100644
--- a/nuttx/arch/arm/src/kl/kl_lowputc.c
+++ b/nuttx/arch/arm/src/kl/kl_lowputc.c
@@ -81,6 +81,8 @@
# define CONSOLE_PARITY CONFIG_UART2_PARITY
#endif
+#define OVER_SAMPLE 16
+
/**************************************************************************
* Private Types
**************************************************************************/
@@ -173,9 +175,11 @@ void kl_lowsetup(void)
uint32_t regval;
uint8_t regval8;
- //regval = getreg32(KL_SIM_SOPT2);
- //regval |= SIM_SOPT2_PLLFLLSEL | SIM_SOPT2_UART0SRC_MCGCLK ;
- //putreg32(regval, KL_SIM_SOPT2);
+#if 0
+ regval = getreg32(KL_SIM_SOPT2);
+ regval |= SIM_SOPT2_PLLFLLSEL | SIM_SOPT2_UART0SRC_MCGCLK ;
+ putreg32(regval, KL_SIM_SOPT2);
+#endif
regval = getreg32(KL_SIM_SCGC5);
regval |= SIM_SCGC5_PORTA;
@@ -197,25 +201,26 @@ void kl_lowsetup(void)
putreg32((PORT_PCR_MUX_ALT2), KL_PORTA_PCR2);
/* Disable UART before changing registers */
+
putreg8(0, KL_UART0_C2);
putreg8(0, KL_UART0_C1);
putreg8(0, KL_UART0_C3);
putreg8(0, KL_UART0_S2);
- // Set the baud rate divisor
- #define CORE_CLOCK 48000000
- #define OVER_SAMPLE 16
- uint16_t divisor = (CORE_CLOCK / OVER_SAMPLE) / CONSOLE_BAUD;
+ /* Set the baud rate divisor */
+
+ uint16_t divisor = (CONSOLE_FREQ / OVER_SAMPLE) / CONSOLE_BAUD;
regval8 = OVER_SAMPLE - 1;
putreg8(regval8, KL_UART0_C4);
- regval8 = (divisor >> 8) & UARTLP_BDH_SBR_MASK;
+ regval8 = (divisor >> 8) & UART_BDH_SBR_MASK;
putreg8(regval8, KL_UART0_BDH);
- regval8 = (divisor & UARTLP_BDL_SBR_MASK);
+ regval8 = (divisor & UART_BDL_SBR_MASK);
putreg8(regval8, KL_UART0_BDL);
/* Enable UART before changing registers */
+
regval8 = getreg8(KL_UART0_C2);
regval8 |= (UART_C2_RE | UART_C2_TE);
putreg8(regval8, KL_UART0_C2);
@@ -224,11 +229,11 @@ void kl_lowsetup(void)
* when the serial driver is opened.
*/
-//#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
-// kl_uartconfigure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ,
-// CONSOLE_PARITY, CONSOLE_BITS);
-//#endif
+ kl_uartconfigure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ,
+ CONSOLE_PARITY, CONSOLE_BITS);
+#endif
}
/******************************************************************************
@@ -246,9 +251,9 @@ void kl_uartreset(uintptr_t uart_base)
/* Just disable the transmitter and receiver */
- regval = getreg8(uart_base+KL_UART_C2_OFFSET);
- regval &= ~(UART_C2_RE|UART_C2_TE);
- putreg8(regval, uart_base+KL_UART_C2_OFFSET);
+ regval = getreg8(uart_base + KL_UART_C2_OFFSET);
+ regval &= ~(UART_C2_RE | UART_C2_TE);
+ putreg8(regval, uart_base + KL_UART_C2_OFFSET);
}
#endif
@@ -265,7 +270,6 @@ void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
unsigned int parity, unsigned int nbits)
{
uint32_t sbr;
- uint32_t brfa;
uint32_t tmp;
uint8_t regval;
#ifdef CONFIG_KL_UARTFIFOS
@@ -286,7 +290,7 @@ void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
if (parity == 1)
{
- regval |= (UART_C1_PE|UART_C1_PT); /* Enable + odd parity type */
+ regval |= (UART_C1_PE | UART_C1_PT); /* Enable + odd parity type */
}
/* Check for even parity */
@@ -317,7 +321,7 @@ void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
DEBUGASSERT(nbits == 8);
}
- putreg8(regval, uart_base+KL_UART_C1_OFFSET);
+ putreg8(regval, uart_base + KL_UART_C1_OFFSET);
/* Calculate baud settings (truncating) */
@@ -328,85 +332,19 @@ void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
* register.
*/
- regval = getreg8(uart_base+KL_UART_BDH_OFFSET) & UART_BDH_SBR_MASK;
+ regval = getreg8(uart_base + KL_UART_BDH_OFFSET) & UART_BDH_SBR_MASK;
tmp = sbr >> 8;
regval |= (((uint8_t)tmp) << UART_BDH_SBR_SHIFT) & UART_BDH_SBR_MASK;
- putreg8(regval, uart_base+KL_UART_BDH_OFFSET);
+ putreg8(regval, uart_base + KL_UART_BDH_OFFSET);
regval = sbr & 0xff;
- putreg8(regval, uart_base+KL_UART_BDL_OFFSET);
-
- /* Calculate a fractional divider to get closer to the requested baud.
- * The fractional divider, BRFA, is a 5 bit fractional value that is
- * logically added to the SBR:
- *
- * UART baud rate = clock / (16 × (SBR + BRFD))
- *
- * The BRFA the remainder. This will be a non-negative value since the SBR
- * was calculated by truncation.
- */
-
- tmp = clock - (sbr * (baud << 4));
- brfa = (tmp << 5) / (baud << 4);
-
- /* Set the BRFA field (retaining other bits in the UARTx_C4 register) */
-
- regval = getreg8(uart_base+KL_UART_C4_OFFSET) & UART_C4_BRFA_MASK;
- regval |= ((uint8_t)brfa << UART_C4_BRFA_SHIFT) & UART_C4_BRFA_MASK;
- putreg8(regval, uart_base+KL_UART_C4_OFFSET);
-
- /* Set the FIFO watermarks.
- *
- * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs
- * (1-deep). There appears to be no way to know when the FIFO is not
- * full (other than reading the FIFO length and comparing the FIFO count).
- * Hence, the FIFOs are not used in this implementation and, as a result
- * TDRE indeed mean that the single output buffer is available.
- *
- * Performance on UART0 could be improved by enabling the FIFO and by
- * redesigning all of the FIFO status logic.
- */
-
-#ifdef CONFIG_KL_UARTFIFOS
- depth = g_sizemap[(regval & UART_PFIFO_RXFIFOSIZE_MASK) >> UART_PFIFO_RXFIFOSIZE_SHIFT];
- if (depth > 1)
- {
- depth = (3 * depth) >> 2;
- }
- putreg8(depth , uart_base+KL_UART_RWFIFO_OFFSET);
-
- depth = g_sizemap[(regval & UART_PFIFO_TXFIFOSIZE_MASK) >> UART_PFIFO_TXFIFOSIZE_SHIFT];
- if (depth > 3)
- {
- depth = (depth >> 2);
- }
- putreg8(depth, uart_base+KL_UART_TWFIFO_OFFSET);
-
- /* Enable RX and TX FIFOs */
-
- putreg8(UART_PFIFO_RXFE | UART_PFIFO_TXFE, uart_base+KL_UART_PFIFO_OFFSET);
-#else
- /* Otherwise, disable the FIFOs. Then the FIFOs are disable, the effective
- * FIFO depth is 1. So set the watermarks as follows:
- *
- * TWFIFO[TXWATER] = 0: TDRE will be set when the number of queued bytes
- * (1 in this case) is less than or equal to 0.
- * RWFIFO[RXWATER] = 1: RDRF will be set when the number of queued bytes
- * (1 in this case) is greater than or equal to 1.
- *
- * Set the watermarks to one/zero and disable the FIFOs
- */
-
- putreg8(1, uart_base+KL_UART_RWFIFO_OFFSET);
- putreg8(0, uart_base+KL_UART_TWFIFO_OFFSET);
- putreg8(0, uart_base+KL_UART_PFIFO_OFFSET);
-#endif
+ putreg8(regval, uart_base + KL_UART_BDL_OFFSET);
/* Now we can (re-)enable the transmitter and receiver */
- regval = getreg8(uart_base+KL_UART_C2_OFFSET);
+ regval = getreg8(uart_base + KL_UART_C2_OFFSET);
regval |= (UART_C2_RE | UART_C2_TE);
- putreg8(regval, uart_base+KL_UART_C2_OFFSET);
+ putreg8(regval, uart_base + KL_UART_C2_OFFSET);
}
#endif
diff --git a/nuttx/arch/arm/src/kl/kl_serial.c b/nuttx/arch/arm/src/kl/kl_serial.c
index b523965ea..3aa5a9ad9 100644
--- a/nuttx/arch/arm/src/kl/kl_serial.c
+++ b/nuttx/arch/arm/src/kl/kl_serial.c
@@ -99,17 +99,6 @@
# define CONSOLE_DEV g_uart2port /* UART2 is console */
# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_UART3_SERIAL_CONSOLE)
-# define CONSOLE_DEV g_uart3port /* UART3 is console */
-# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */
-# define UART3_ASSIGNED 1
-#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
-# define CONSOLE_DEV g_uart4port /* UART4 is console */
-# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
-# define CONSOLE_DEV g_uart5port /* UART5 is console */
-# define TTYS5_DEV g_uart5port /* UART5 is ttyS0 */
#else
# undef CONSOLE_DEV /* No console */
# if defined(CONFIG_KL_UART0)
@@ -121,15 +110,6 @@
# elif defined(CONFIG_KL_UART2)
# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
# define UART2_ASSIGNED 1
-# elif defined(CONFIG_KL_UART3)
-# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */
-# define UART3_ASSIGNED 1
-# elif defined(CONFIG_KL_UART4)
-# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */
-# define UART4_ASSIGNED 1
-# elif defined(CONFIG_KL_UART5)
-# define TTYS0_DEV g_uart5port /* UART5 is ttyS0 */
-# define UART5_ASSIGNED 1
# endif
#endif
@@ -144,15 +124,6 @@
#elif defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
-# define TTYS1_DEV g_uart3port /* UART3 is ttyS1 */
-# define UART3_ASSIGNED 1
-#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
-# define TTYS1_DEV g_uart4port /* UART4 is ttyS1 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
-# define TTYS1_DEV g_uart5port /* UART5 is ttyS1 */
-# define UART5_ASSIGNED 1
#endif
/* Pick ttys2. This could be one of UART1-5. It can't be UART0 because that
@@ -166,15 +137,6 @@
#elif defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
-# define TTYS2_DEV g_uart3port /* UART3 is ttyS2 */
-# define UART3_ASSIGNED 1
-#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
-# define TTYS2_DEV g_uart4port /* UART4 is ttyS2 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
-# define TTYS2_DEV g_uart5port /* UART5 is ttyS2 */
-# define UART5_ASSIGNED 1
#endif
/* Pick ttys3. This could be one of UART2-5. It can't be UART0-1 because
@@ -185,44 +147,6 @@
#if defined(CONFIG_KL_UART2) && !defined(UART2_ASSIGNED)
# define TTYS3_DEV g_uart2port /* UART2 is ttyS3 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
-# define TTYS3_DEV g_uart3port /* UART3 is ttyS3 */
-# define UART3_ASSIGNED 1
-#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
-# define TTYS3_DEV g_uart4port /* UART4 is ttyS3 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
-# define TTYS3_DEV g_uart5port /* UART5 is ttyS3 */
-# define UART5_ASSIGNED 1
-#endif
-
-/* Pick ttys4. This could be one of UART3-5. It can't be UART0-2 because
- * those have already been assigned to ttsyS0, 1, 2 or 3. One of
- * UART 3-5 could also be the console.
- */
-
-#if defined(CONFIG_KL_UART3) && !defined(UART3_ASSIGNED)
-# define TTYS4_DEV g_uart3port /* UART3 is ttyS4 */
-# define UART3_ASSIGNED 1
-#elif defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
-# define TTYS4_DEV g_uart4port /* UART4 is ttyS4 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
-# define TTYS4_DEV g_uart5port /* UART5 is ttyS4 */
-# define UART5_ASSIGNED 1
-#endif
-
-/* Pick ttys5. This could be one of UART4-5. It can't be UART0-3 because
- * those have already been assigned to ttsyS0, 1, 2, 3 or 4. One of
- * UART 4-5 could also be the console.
- */
-
-#if defined(CONFIG_KL_UART4) && !defined(UART4_ASSIGNED)
-# define TTYS5_DEV g_uart4port /* UART4 is ttyS5 */
-# define UART4_ASSIGNED 1
-#elif defined(CONFIG_KL_UART5) && !defined(UART5_ASSIGNED)
-# define TTYS5_DEV g_uart5port /* UART5 is ttyS5 */
-# define UART5_ASSIGNED 1
#endif
/****************************************************************************
@@ -305,18 +229,6 @@ static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
#endif
-#ifdef CONFIG_KL_UART3
-static char g_uart3rxbuffer[CONFIG_UART3_RXBUFSIZE];
-static char g_uart3txbuffer[CONFIG_UART3_TXBUFSIZE];
-#endif
-#ifdef CONFIG_KL_UART4
-static char g_uart4rxbuffer[CONFIG_UART4_RXBUFSIZE];
-static char g_uart4txbuffer[CONFIG_UART4_TXBUFSIZE];
-#endif
-#ifdef CONFIG_KL_UART5
-static char g_uart5rxbuffer[CONFIG_UART5_RXBUFSIZE];
-static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE];
-#endif
/* This describes the state of the Kinetis UART0 port. */
@@ -416,108 +328,6 @@ static uart_dev_t g_uart2port =
};
#endif
-/* This describes the state of the Kinetis UART3 port. */
-
-#ifdef CONFIG_KL_UART3
-static struct up_dev_s g_uart3priv =
-{
- .uartbase = KL_UART3_BASE,
- .clock = BOARD_BUSCLK_FREQ,
- .baud = CONFIG_UART3_BAUD,
-#ifdef CONFIG_DEBUG
- .irqe = KL_IRQ_UART3E,
-#endif
- .irqs = KL_IRQ_UART3S,
- .irqprio = CONFIG_KL_UART3PRIO,
- .parity = CONFIG_UART3_PARITY,
- .bits = CONFIG_UART3_BITS,
-};
-
-static uart_dev_t g_uart3port =
-{
- .recv =
- {
- .size = CONFIG_UART3_RXBUFSIZE,
- .buffer = g_uart3rxbuffer,
- },
- .xmit =
- {
- .size = CONFIG_UART3_TXBUFSIZE,
- .buffer = g_uart3txbuffer,
- },
- .ops = &g_uart_ops,
- .priv = &g_uart3priv,
-};
-#endif
-
-/* This describes the state of the Kinetis UART4 port. */
-
-#ifdef CONFIG_KL_UART4
-static struct up_dev_s g_uart4priv =
-{
- .uartbase = KL_UART4_BASE,
- .clock = BOARD_BUSCLK_FREQ,
- .baud = CONFIG_UART4_BAUD,
-#ifdef CONFIG_DEBUG
- .irqe = KL_IRQ_UART4E,
-#endif
- .irqs = KL_IRQ_UART4S,
- .irqprio = CONFIG_KL_UART4PRIO,
- .parity = CONFIG_UART4_PARITY,
- .bits = CONFIG_UART4_BITS,
-};
-
-static uart_dev_t g_uart4port =
-{
- .recv =
- {
- .size = CONFIG_UART4_RXBUFSIZE,
- .buffer = g_uart4rxbuffer,
- },
- .xmit =
- {
- .size = CONFIG_UART4_TXBUFSIZE,
- .buffer = g_uart4txbuffer,
- },
- .ops = &g_uart_ops,
- .priv = &g_uart4priv,
-};
-#endif
-
-/* This describes the state of the Kinetis UART5 port. */
-
-#ifdef CONFIG_KL_UART5
-static struct up_dev_s g_uart5priv =
-{
- .uartbase = KL_UART5_BASE,
- .clock = BOARD_BUSCLK_FREQ,
- .baud = CONFIG_UART5_BAUD,
-#ifdef CONFIG_DEBUG
- .irqe = KL_IRQ_UART5E,
-#endif
- .irqs = KL_IRQ_UART5S,
- .irqprio = CONFIG_KL_UART5PRIO,
- .parity = CONFIG_UART5_PARITY,
- .bits = CONFIG_UART5_BITS,
-};
-
-static uart_dev_t g_uart5port =
-{
- .recv =
- {
- .size = CONFIG_UART5_RXBUFSIZE,
- .buffer = g_uart5rxbuffer,
- },
- .xmit =
- {
- .size = CONFIG_UART5_TXBUFSIZE,
- .buffer = g_uart5txbuffer,
- },
- .ops = &g_uart_ops,
- .priv = &g_uart5priv,
-};
-#endif
-
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -758,27 +568,6 @@ static int up_interrupte(int irq, void *context)
}
else
#endif
-#ifdef CONFIG_KL_UART3
- if (g_uart3priv.irqe == irq)
- {
- dev = &g_uart3port;
- }
- else
-#endif
-#ifdef CONFIG_KL_UART4
- if (g_uart4priv.irqe == irq)
- {
- dev = &g_uart4port;
- }
- else
-#endif
-#ifdef CONFIG_KL_UART5
- if (g_uart5priv.irqe == irq)
- {
- dev = &g_uart5port;
- }
- else
-#endif
{
PANIC(OSERR_INTERNAL);
}
@@ -847,27 +636,6 @@ static int up_interrupts(int irq, void *context)
}
else
#endif
-#ifdef CONFIG_KL_UART3
- if (g_uart3priv.irqs == irq)
- {
- dev = &g_uart3port;
- }
- else
-#endif
-#ifdef CONFIG_KL_UART4
- if (g_uart4priv.irqs == irq)
- {
- dev = &g_uart4port;
- }
- else
-#endif
-#ifdef CONFIG_KL_UART5
- if (g_uart5priv.irq == irqs)
- {
- dev = &g_uart5port;
- }
- else
-#endif
{
PANIC(OSERR_INTERNAL);
}