summaryrefslogtreecommitdiff
path: root/chip/max32660
diff options
context:
space:
mode:
Diffstat (limited to 'chip/max32660')
-rw-r--r--chip/max32660/build.mk21
-rw-r--r--chip/max32660/clock_chip.c141
-rw-r--r--chip/max32660/config_chip.h104
-rw-r--r--chip/max32660/flash_chip.c404
-rw-r--r--chip/max32660/flc_regs.h283
-rw-r--r--chip/max32660/gcr_regs.h1365
-rw-r--r--chip/max32660/gpio_chip.c241
-rw-r--r--chip/max32660/gpio_regs.h866
-rw-r--r--chip/max32660/hwtimer_chip.c230
-rw-r--r--chip/max32660/i2c_chip.c1132
-rw-r--r--chip/max32660/i2c_regs.h1627
-rw-r--r--chip/max32660/icc_regs.h143
-rw-r--r--chip/max32660/pwrseq_regs.h489
-rw-r--r--chip/max32660/registers.h224
-rw-r--r--chip/max32660/system_chip.c64
-rw-r--r--chip/max32660/tmr_regs.h279
-rw-r--r--chip/max32660/uart_chip.c277
-rw-r--r--chip/max32660/uart_regs.h677
-rw-r--r--chip/max32660/wdt_chip.c67
-rw-r--r--chip/max32660/wdt_regs.h355
20 files changed, 0 insertions, 8989 deletions
diff --git a/chip/max32660/build.mk b/chip/max32660/build.mk
deleted file mode 100644
index e0f5636b2e..0000000000
--- a/chip/max32660/build.mk
+++ /dev/null
@@ -1,21 +0,0 @@
-# -*- makefile -*-
-# Copyright 2019 The Chromium OS Authors. All rights reserved.
-# Use of this source code is governed by a BSD-style license that can be
-# found in the LICENSE file.
-#
-# MAX32660 chip specific files build
-#
-
-# MAX32660 SoC has a Cortex-M4F ARM core
-CORE:=cortex-m
-# Allow the full Cortex-M4 instruction set
-CFLAGS_CPU+=-march=armv7e-m -mcpu=cortex-m4
-
-# Required chip modules
-chip-y=clock_chip.o gpio_chip.o system_chip.o hwtimer_chip.o uart_chip.o
-chip-$(CONFIG_I2C)+=i2c_chip.o
-
-# Optional chip modules
-chip-$(CONFIG_FLASH_PHYSICAL)+=flash_chip.o
-chip-$(CONFIG_WATCHDOG)+=wdt_chip.o
-
diff --git a/chip/max32660/clock_chip.c b/chip/max32660/clock_chip.c
deleted file mode 100644
index 901c5d559c..0000000000
--- a/chip/max32660/clock_chip.c
+++ /dev/null
@@ -1,141 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Clocks and Power Management Module for Chrome EC */
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "cpu.h"
-#include "hooks.h"
-#include "hwtimer.h"
-#include "registers.h"
-#include "system.h"
-#include "timer.h"
-#include "util.h"
-#include "watchdog.h"
-#include "tmr_regs.h"
-#include "gcr_regs.h"
-#include "pwrseq_regs.h"
-
-#define MAX32660_SYSTEMCLOCK SYS_CLOCK_HIRC
-
-/** Clock source */
-typedef enum {
- SYS_CLOCK_NANORING = MXC_V_GCR_CLKCN_CLKSEL_NANORING, /**< 8KHz nanoring
- on MAX32660 */
- SYS_CLOCK_HFXIN =
- MXC_V_GCR_CLKCN_CLKSEL_HFXIN, /**< 32KHz on MAX32660 */
- SYS_CLOCK_HFXIN_DIGITAL = 0x9, /**< External Clock Input*/
- SYS_CLOCK_HIRC = MXC_V_GCR_CLKCN_CLKSEL_HIRC, /**< High Frequency
- Internal Oscillator */
-} sys_system_clock_t;
-
-/***** Functions ******/
-static void clock_wait_ready(uint32_t ready)
-{
- // Start timeout, wait for ready
- do {
- if (MXC_GCR->clkcn & ready) {
- return;
- }
- } while (1);
-}
-
-extern void (*const __isr_vector[])(void);
-uint32_t SystemCoreClock = HIRC96_FREQ;
-
-static void clock_update(void)
-{
- uint32_t base_freq, divide, ovr;
-
- // Get the clock source and frequency
- ovr = (MXC_PWRSEQ->lp_ctrl & MXC_F_PWRSEQ_LP_CTRL_OVR);
- if (ovr == MXC_S_PWRSEQ_LP_CTRL_OVR_0_9V) {
- base_freq = HIRC96_FREQ / 4;
- } else {
- if (ovr == MXC_S_PWRSEQ_LP_CTRL_OVR_1_0V) {
- base_freq = HIRC96_FREQ / 2;
- } else {
- base_freq = HIRC96_FREQ;
- }
- }
-
- // Get the clock divider
- divide = (MXC_GCR->clkcn & MXC_F_GCR_CLKCN_PSC) >>
- MXC_F_GCR_CLKCN_PSC_POS;
-
- SystemCoreClock = base_freq >> divide;
-}
-
-void clock_init(void)
-{
- /* Switch system clock to HIRC */
- uint32_t ovr, divide;
-
- // Set FWS higher than what the minimum for the fastest clock is
- MXC_GCR->memckcn = (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x5UL << MXC_F_GCR_MEMCKCN_FWS_POS);
-
- // Enable 96MHz Clock
- MXC_GCR->clkcn |= MXC_F_GCR_CLKCN_HIRC_EN;
-
- // Wait for the 96MHz clock
- clock_wait_ready(MXC_F_GCR_CLKCN_HIRC_RDY);
-
- // Set 96MHz clock as System Clock
- MXC_SETFIELD(MXC_GCR->clkcn, MXC_F_GCR_CLKCN_CLKSEL,
- MXC_S_GCR_CLKCN_CLKSEL_HIRC);
-
- // Wait for system clock to be ready
- clock_wait_ready(MXC_F_GCR_CLKCN_CKRDY);
-
- // Update the system core clock
- clock_update();
-
- // Get the clock divider
- divide = (MXC_GCR->clkcn & MXC_F_GCR_CLKCN_PSC) >>
- MXC_F_GCR_CLKCN_PSC_POS;
-
- // get ovr setting
- ovr = (MXC_PWRSEQ->lp_ctrl & MXC_F_PWRSEQ_LP_CTRL_OVR);
-
- // Set flash wait settings
- if (ovr == MXC_S_PWRSEQ_LP_CTRL_OVR_0_9V) {
- if (divide == 0) {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x2UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- } else {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x1UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- }
- } else if (ovr == MXC_S_PWRSEQ_LP_CTRL_OVR_1_0V) {
- if (divide == 0) {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x2UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- } else {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x1UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- }
- } else {
- if (divide == 0) {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x4UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- } else if (divide == 1) {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x2UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- } else {
- MXC_GCR->memckcn =
- (MXC_GCR->memckcn & ~(MXC_F_GCR_MEMCKCN_FWS)) |
- (0x1UL << MXC_F_GCR_MEMCKCN_FWS_POS);
- }
- }
-}
diff --git a/chip/max32660/config_chip.h b/chip/max32660/config_chip.h
deleted file mode 100644
index c97c246bb7..0000000000
--- a/chip/max32660/config_chip.h
+++ /dev/null
@@ -1,104 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#ifndef __CROS_EC_CONFIG_CHIP_H
-#define __CROS_EC_CONFIG_CHIP_H
-
-/* CPU core BFD configuration */
-#include "core/cortex-m/config_core.h"
-
-/* 96.000 MHz internal oscillator frequency */
-#define INTERNAL_CLOCK 96000000
-
-/* Number of IRQ vectors on the NVIC */
-#define CONFIG_IRQ_COUNT 132
-
-/* Use a bigger console output buffer */
-#undef CONFIG_UART_TX_BUF_SIZE
-#define CONFIG_UART_TX_BUF_SIZE 8192
-
-/* Interval between HOOK_TICK notifications */
-#define HOOK_TICK_INTERVAL_MS 250
-#define HOOK_TICK_INTERVAL (HOOK_TICK_INTERVAL_MS * MSEC)
-
-/* Number of I2C ports */
-#define I2C_PORT_COUNT 2
-
-/*
- * Time it takes to set the RTC match register. This value is conservatively
- * set based on measurements around 200us.
- */
-#define HIB_SET_RTC_MATCH_DELAY_USEC 300
-
-/****************************************************************************/
-/* Memory mapping */
-
-#define CONFIG_RAM_BASE 0x20000000
-#define CONFIG_RAM_SIZE 0x00018000 /* 96k MAX32660 SRAM Size*/
-
-/* System stack size */
-#define CONFIG_STACK_SIZE 4096
-
-/* non-standard task stack sizes */
-#define IDLE_TASK_STACK_SIZE 512
-#define LARGER_TASK_STACK_SIZE 768
-#define SMALLER_TASK_STACK_SIZE 384
-
-/* Default task stack size */
-#define TASK_STACK_SIZE 512
-
-#define CONFIG_PROGRAM_MEMORY_BASE 0x00000000
-#define CONFIG_FLASH_BANK_SIZE 0x00002000 /* protect bank size */
-#define CONFIG_FLASH_ERASE_SIZE 0x00002000 /* erase bank size */
-#define CONFIG_FLASH_WRITE_SIZE 0x00000004 /* minimum write size */
-
-/* Ideal flash write size fills the 32-entry flash write buffer */
-#define CONFIG_FLASH_WRITE_IDEAL_SIZE (32 * 4)
-
-/* This is the physical size of the flash on the chip. We'll reserve one bank
- * in order to emulate per-bank write-protection UNTIL REBOOT. The hardware
- * doesn't support a write-protect pin, and if we make the write-protection
- * permanent, it can't be undone easily enough to support RMA. */
-#define CONFIG_FLASH_SIZE_BYTES 0x00040000 /* 256K MAX32660 FLASH Size */
-
-/****************************************************************************/
-/* Define our flash layout. */
-
-/* Memory-mapped internal flash */
-#define CONFIG_INTERNAL_STORAGE
-#define CONFIG_MAPPED_STORAGE
-
-/* Program is run directly from storage */
-#define CONFIG_MAPPED_STORAGE_BASE CONFIG_PROGRAM_MEMORY_BASE
-
-/* Compute the rest of the flash params from these */
-#include "config_std_internal_flash.h"
-
-/****************************************************************************/
-/* Lock the boot configuration to prevent brickage. */
-
-/*
- * No GPIO trigger for ROM bootloader.
- * Keep JTAG debugging enabled.
- * Use 0xA442 flash write key.
- * Lock it this way.
- */
-#define CONFIG_BOOTCFG_VALUE 0x7ffffffe
-
-/****************************************************************************/
-/* Customize the build */
-
-/* Optional features present on this chip */
-#define CONFIG_HOSTCMD_ALIGNED
-#define CONFIG_RTC
-#define CONFIG_SWITCH
-
-/* Chip needs to do custom pre-init */
-#define CONFIG_CHIP_PRE_INIT
-
-#define GPIO_PIN(port, index) GPIO_##port, (1 << index)
-#define GPIO_PIN_MASK(p, m) .port = GPIO_##p, .mask = (m)
-
-#endif /* __CROS_EC_CONFIG_CHIP_H */
diff --git a/chip/max32660/flash_chip.c b/chip/max32660/flash_chip.c
deleted file mode 100644
index 747d7dcc58..0000000000
--- a/chip/max32660/flash_chip.c
+++ /dev/null
@@ -1,404 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Flash Memory Module for Chrome EC */
-
-#include "flash.h"
-#include "switch.h"
-#include "system.h"
-#include "timer.h"
-#include "util.h"
-#include "watchdog.h"
-#include "registers.h"
-#include "common.h"
-#include "icc_regs.h"
-#include "flc_regs.h"
-
-#define CPUTS(outstr) cputs(CC_SYSTEM, outstr)
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ##args)
-
-/***** Definitions *****/
-
-/// Bit mask that can be used to find the starting address of a page in flash
-#define MXC_FLASH_PAGE_MASK ~(MXC_FLASH_PAGE_SIZE - 1)
-
-/// Calculate the address of a page in flash from the page number
-#define MXC_FLASH_PAGE_ADDR(page) \
- (MXC_FLASH_MEM_BASE + ((unsigned long)page * MXC_FLASH_PAGE_SIZE))
-
-void flash_operation(void)
-{
- volatile uint32_t *line_addr;
- volatile uint32_t __attribute__((unused)) line;
-
- // Clear the cache
- MXC_ICC->cache_ctrl ^= MXC_F_ICC_CACHE_CTRL_CACHE_EN;
- MXC_ICC->cache_ctrl ^= MXC_F_ICC_CACHE_CTRL_CACHE_EN;
-
- // Clear the line fill buffer
- line_addr = (uint32_t *)(MXC_FLASH_MEM_BASE);
- line = *line_addr;
-
- line_addr = (uint32_t *)(MXC_FLASH_MEM_BASE + MXC_FLASH_PAGE_SIZE);
- line = *line_addr;
-}
-
-static int flash_busy(void)
-{
- return (MXC_FLC->cn &
- (MXC_F_FLC_CN_WR | MXC_F_FLC_CN_ME | MXC_F_FLC_CN_PGE));
-}
-
-static int flash_init_controller(void)
-{
- // Set flash clock divider to generate a 1MHz clock from the APB clock
- MXC_FLC->clkdiv = SystemCoreClock / 1000000;
-
- /* Check if the flash controller is busy */
- if (flash_busy()) {
- return EC_ERROR_BUSY;
- }
-
- /* Clear stale errors */
- if (MXC_FLC->intr & MXC_F_FLC_INTR_AF) {
- MXC_FLC->intr &= ~MXC_F_FLC_INTR_AF;
- }
-
- /* Unlock flash */
- MXC_FLC->cn = (MXC_FLC->cn & ~MXC_F_FLC_CN_UNLOCK) |
- MXC_S_FLC_CN_UNLOCK_UNLOCKED;
-
- return EC_SUCCESS;
-}
-
-static int flash_device_page_erase(uint32_t address)
-{
- int err;
-
- if ((err = flash_init_controller()) != EC_SUCCESS)
- return err;
-
- // Align address on page boundary
- address = address - (address % MXC_FLASH_PAGE_SIZE);
-
- /* Write paflash_init_controllerde */
- MXC_FLC->cn = (MXC_FLC->cn & ~MXC_F_FLC_CN_ERASE_CODE) |
- MXC_S_FLC_CN_ERASE_CODE_ERASEPAGE;
- /* Issue page erase command */
- MXC_FLC->addr = address;
- MXC_FLC->cn |= MXC_F_FLC_CN_PGE;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
-
- /* Lock flash */
- MXC_FLC->cn &= ~MXC_F_FLC_CN_UNLOCK;
-
- /* Check access violations */
- if (MXC_FLC->intr & MXC_F_FLC_INTR_AF) {
- MXC_FLC->intr &= ~MXC_F_FLC_INTR_AF;
- return EC_ERROR_UNKNOWN;
- }
-
- flash_operation();
-
- return EC_SUCCESS;
-}
-
-int crec_flash_physical_write(int offset, int size, const char *data)
-{
- int err;
- uint32_t bytes_written;
- uint8_t current_data[4];
-
- if ((err = flash_init_controller()) != EC_SUCCESS)
- return err;
-
- // write in 32-bit units until we are 128-bit aligned
- MXC_FLC->cn &= ~MXC_F_FLC_CN_BRST;
- MXC_FLC->cn |= MXC_F_FLC_CN_WDTH;
-
- // Align the address and read/write if we have to
- if (offset & 0x3) {
-
- // Figure out how many bytes we have to write to round up the
- // address
- bytes_written = 4 - (offset & 0x3);
-
- // Save the data currently in the flash
- memcpy(current_data, (void *)(offset & (~0x3)), 4);
-
- // Modify current_data to insert the data from buffer
- memcpy(&current_data[4 - bytes_written], data, bytes_written);
-
- // Write the modified data
- MXC_FLC->addr = offset - (offset % 4);
- memcpy((void *)&MXC_FLC->data[0], &current_data, 4);
- MXC_FLC->cn |= MXC_F_FLC_CN_WR;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
-
- offset += bytes_written;
- size -= bytes_written;
- data += bytes_written;
- }
-
- while ((size >= 4) && ((offset & 0x1F) != 0)) {
- MXC_FLC->addr = offset;
- memcpy((void *)&MXC_FLC->data[0], data, 4);
- MXC_FLC->cn |= MXC_F_FLC_CN_WR;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
-
- offset += 4;
- size -= 4;
- data += 4;
- }
-
- if (size >= 16) {
-
- // write in 128-bit bursts while we can
- MXC_FLC->cn &= ~MXC_F_FLC_CN_WDTH;
-
- while (size >= 16) {
- MXC_FLC->addr = offset;
- memcpy((void *)&MXC_FLC->data[0], data, 16);
- MXC_FLC->cn |= MXC_F_FLC_CN_WR;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
-
- offset += 16;
- size -= 16;
- data += 16;
- }
-
- // Return to 32-bit writes.
- MXC_FLC->cn |= MXC_F_FLC_CN_WDTH;
- }
-
- while (size >= 4) {
- MXC_FLC->addr = offset;
- memcpy((void *)&MXC_FLC->data[0], data, 4);
- MXC_FLC->cn |= MXC_F_FLC_CN_WR;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
-
- offset += 4;
- size -= 4;
- data += 4;
- }
-
- if (size > 0) {
- // Save the data currently in the flash
- memcpy(current_data, (void *)(offset), 4);
-
- // Modify current_data to insert the data from data
- memcpy(current_data, data, size);
-
- MXC_FLC->addr = offset;
- memcpy((void *)&MXC_FLC->data[0], current_data, 4);
- MXC_FLC->cn |= MXC_F_FLC_CN_WR;
-
- /* Wait until flash operation is complete */
- while (flash_busy())
- ;
- }
-
- /* Lock flash */
- MXC_FLC->cn &= ~MXC_F_FLC_CN_UNLOCK;
-
- /* Check access violations */
- if (MXC_FLC->intr & MXC_F_FLC_INTR_AF) {
- MXC_FLC->intr &= ~MXC_F_FLC_INTR_AF;
- return EC_ERROR_UNKNOWN;
- }
-
- flash_operation();
-
- return EC_SUCCESS;
-}
-
-/*****************************************************************************/
-/* Physical layer APIs */
-
-int crec_flash_physical_erase(int offset, int size)
-{
- int i;
- int pages;
- int error_status;
-
- /*
- * erase 'size' number of bytes starting at address 'offset'
- */
- /* calculate the number of pages */
- pages = size / CONFIG_FLASH_ERASE_SIZE;
- /* iterate over the number of pages */
- for (i = 0; i < pages; i++) {
- /* erase the page after calculating the start address */
- error_status = flash_device_page_erase(
- offset + (i * CONFIG_FLASH_ERASE_SIZE));
- if (error_status != EC_SUCCESS) {
- return error_status;
- }
- }
- return EC_SUCCESS;
-}
-
-int crec_flash_physical_get_protect(int bank)
-{
- /* Not protected */
- return 0;
-}
-
-uint32_t crec_flash_physical_get_protect_flags(void)
-{
- /* no flags set */
- return 0;
-}
-
-uint32_t crec_flash_physical_get_valid_flags(void)
-{
- /* These are the flags we're going to pay attention to */
- return EC_FLASH_PROTECT_RO_AT_BOOT | EC_FLASH_PROTECT_RO_NOW |
- EC_FLASH_PROTECT_ALL_NOW;
-}
-
-uint32_t crec_flash_physical_get_writable_flags(uint32_t cur_flags)
-{
- /* no flags writable */
- return 0;
-}
-
-int crec_flash_physical_protect_at_boot(uint32_t new_flags)
-{
- /* nothing to do here */
- return EC_SUCCESS;
-}
-
-int crec_flash_physical_protect_now(int all)
-{
- /* nothing to do here */
- return EC_SUCCESS;
-}
-
-/*****************************************************************************/
-/* High-level APIs */
-
-int crec_flash_pre_init(void)
-{
- return EC_SUCCESS;
-}
-
-/*****************************************************************************/
-/* Test Commands */
-
-/*
- * Read, Write, and Erase a page of flash memory using chip routines
- * NOTE: This is a DESTRUCTIVE test for the range of flash pages tested
- * make sure that PAGE_START is beyond your flash code.
- */
-static int command_flash_test1(int argc, char **argv)
-{
- int i;
- uint8_t *ptr;
- const uint32_t PAGE_START = 9;
- const uint32_t PAGE_END = 32;
- uint32_t page;
- int error_status;
- uint32_t flash_address;
- const int BUFFER_SIZE = 32;
- uint8_t buffer[BUFFER_SIZE];
-
- /*
- * As a test, write unique data to each page in this for loop, later
- * verify data in pages
- */
- for (page = PAGE_START; page < PAGE_END; page++) {
- flash_address = page * CONFIG_FLASH_ERASE_SIZE;
-
- /*
- * erase page
- */
- error_status = crec_flash_physical_erase(flash_address,
- CONFIG_FLASH_ERASE_SIZE);
- if (error_status != EC_SUCCESS) {
- CPRINTS("Error with crec_flash_physical_erase\n");
- return EC_ERROR_UNKNOWN;
- }
-
- /*
- * verify page was erased
- */
- // CPRINTS("read flash page %d, address %x, ", page,
- // flash_address);
- ptr = (uint8_t *)flash_address;
- for (i = 0; i < CONFIG_FLASH_ERASE_SIZE; i++) {
- if (*ptr++ != 0xff) {
- CPRINTS("Error with verifying page erase\n");
- return EC_ERROR_UNKNOWN;
- }
- }
-
- /*
- * write pattern to page, just write BUFFER_SIZE worth of data
- */
- for (i = 0; i < BUFFER_SIZE; i++) {
- buffer[i] = i + page;
- }
- error_status = crec_flash_physical_write(flash_address,
- BUFFER_SIZE, buffer);
- if (error_status != EC_SUCCESS) {
- CPRINTS("Error with crec_flash_physical_write\n");
- return EC_ERROR_UNKNOWN;
- }
- }
-
- /*
- * Verify data in pages
- */
- for (page = PAGE_START; page < PAGE_END; page++) {
- flash_address = page * CONFIG_FLASH_ERASE_SIZE;
-
- /*
- * read a portion of flash memory
- */
- ptr = (uint8_t *)flash_address;
- for (i = 0; i < BUFFER_SIZE; i++) {
- if (*ptr++ != (i + page)) {
- CPRINTS("Error with verifing written test "
- "data\n");
- return EC_ERROR_UNKNOWN;
- }
- }
- CPRINTS("Verified Erase, Write, Read page %d", page);
- }
-
- /*
- * Clean up after tests
- */
- for (page = PAGE_START; page <= PAGE_END; page++) {
- flash_address = page * CONFIG_FLASH_ERASE_SIZE;
- error_status = crec_flash_physical_erase(flash_address,
- CONFIG_FLASH_ERASE_SIZE);
- if (error_status != EC_SUCCESS) {
- CPRINTS("Error with crec_flash_physical_erase\n");
- return EC_ERROR_UNKNOWN;
- }
- }
-
- CPRINTS("done command_flash_test1.");
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(flashtest1, command_flash_test1, "flashtest1",
- "Flash chip routine tests");
diff --git a/chip/max32660/flc_regs.h b/chip/max32660/flc_regs.h
deleted file mode 100644
index a484763c0b..0000000000
--- a/chip/max32660/flc_regs.h
+++ /dev/null
@@ -1,283 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the FLC Peripheral Module
- */
-
-#ifndef _FLC_REGS_H_
-#define _FLC_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/* **** Definitions **** */
-
-/**
- * Registers, Bit Masks and Bit Positions for the FLC Peripheral
- * Module.
- */
-
-/**
- * Structure type to access the FLC Registers.
- */
-typedef struct {
- __IO uint32_t addr; /**< <tt>\b 0x00:<\tt> FLC ADDR Register */
- __IO uint32_t clkdiv; /**< <tt>\b 0x04:<\tt> FLC CLKDIV Register */
- __IO uint32_t cn; /**< <tt>\b 0x08:<\tt> FLC CN Register */
- __R uint32_t rsv_0xc_0x23[6];
- __IO uint32_t intr; /**< <tt>\b 0x024:<\tt> FLC INTR Register */
- __R uint32_t rsv_0x28_0x2f[2];
- __IO uint32_t data[4]; /**< <tt>\b 0x30:<\tt> FLC DATA Register */
- __O uint32_t acntl; /**< <tt>\b 0x40:<\tt> FLC ACNTL Register */
-} mxc_flc_regs_t;
-
-/* Register offsets for module FLC */
-/**
- * FLC Peripheral Register Offsets from the FLC Base Peripheral
- * Address.
- */
-#define MXC_R_FLC_ADDR \
- ((uint32_t)0x00000000UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_FLC_CLKDIV \
- ((uint32_t)0x00000004UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_FLC_CN \
- ((uint32_t)0x00000008UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x008 */
-#define MXC_R_FLC_INTR \
- ((uint32_t)0x00000024UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x024 */
-#define MXC_R_FLC_DATA \
- ((uint32_t)0x00000030UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x030 */
-#define MXC_R_FLC_ACNTL \
- ((uint32_t)0x00000040UL) /**< Offset from FLC Base Address: <tt> \
- 0x0x040 */
-
-/**
- * Flash Write Address.
- */
-#define MXC_F_FLC_ADDR_ADDR_POS 0 /**< ADDR_ADDR Position */
-#define MXC_F_FLC_ADDR_ADDR \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_FLC_ADDR_ADDR_POS)) /**< ADDR_ADDR Mask */
-
-/**
- * Flash Clock Divide. The clock (PLL0) is divided by this value to
- * generate a 1 MHz clock for Flash controller.
- */
-#define MXC_F_FLC_CLKDIV_CLKDIV_POS 0 /**< CLKDIV_CLKDIV Position */
-#define MXC_F_FLC_CLKDIV_CLKDIV \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_FLC_CLKDIV_CLKDIV_POS)) /**< CLKDIV_CLKDIV Mask */
-
-/**
- * Flash Control Register.
- */
-#define MXC_F_FLC_CN_WR_POS 0 /**< CN_WR Position */
-#define MXC_F_FLC_CN_WR \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_WR_POS)) /**< CN_WR Mask */
-#define MXC_V_FLC_CN_WR_COMPLETE \
- ((uint32_t)0x0UL) /**< CN_WR_COMPLETE Value \
- */
-#define MXC_S_FLC_CN_WR_COMPLETE \
- (MXC_V_FLC_CN_WR_COMPLETE \
- << MXC_F_FLC_CN_WR_POS) /**< CN_WR_COMPLETE Setting */
-#define MXC_V_FLC_CN_WR_START ((uint32_t)0x1UL) /**< CN_WR_START Value */
-#define MXC_S_FLC_CN_WR_START \
- (MXC_V_FLC_CN_WR_START \
- << MXC_F_FLC_CN_WR_POS) /**< CN_WR_START Setting */
-
-#define MXC_F_FLC_CN_ME_POS 1 /**< CN_ME Position */
-#define MXC_F_FLC_CN_ME \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_ME_POS)) /**< CN_ME Mask */
-
-#define MXC_F_FLC_CN_PGE_POS 2 /**< CN_PGE Position */
-#define MXC_F_FLC_CN_PGE \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_PGE_POS)) /**< CN_PGE Mask */
-
-#define MXC_F_FLC_CN_WDTH_POS 4 /**< CN_WDTH Position */
-#define MXC_F_FLC_CN_WDTH \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_WDTH_POS)) /**< CN_WDTH Mask */
-#define MXC_V_FLC_CN_WDTH_SIZE128 \
- ((uint32_t)0x0UL) /**< CN_WDTH_SIZE128 Value */
-#define MXC_S_FLC_CN_WDTH_SIZE128 \
- (MXC_V_FLC_CN_WDTH_SIZE128 \
- << MXC_F_FLC_CN_WDTH_POS) /**< CN_WDTH_SIZE128 Setting */
-#define MXC_V_FLC_CN_WDTH_SIZE32 \
- ((uint32_t)0x1UL) /**< CN_WDTH_SIZE32 Value \
- */
-#define MXC_S_FLC_CN_WDTH_SIZE32 \
- (MXC_V_FLC_CN_WDTH_SIZE32 \
- << MXC_F_FLC_CN_WDTH_POS) /**< CN_WDTH_SIZE32 Setting */
-
-#define MXC_F_FLC_CN_ERASE_CODE_POS 8 /**< CN_ERASE_CODE Position */
-#define MXC_F_FLC_CN_ERASE_CODE \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_FLC_CN_ERASE_CODE_POS)) /**< CN_ERASE_CODE Mask */
-#define MXC_V_FLC_CN_ERASE_CODE_NOP \
- ((uint32_t)0x0UL) /**< CN_ERASE_CODE_NOP Value */
-#define MXC_S_FLC_CN_ERASE_CODE_NOP \
- (MXC_V_FLC_CN_ERASE_CODE_NOP \
- << MXC_F_FLC_CN_ERASE_CODE_POS) /**< CN_ERASE_CODE_NOP Setting */
-#define MXC_V_FLC_CN_ERASE_CODE_ERASEPAGE \
- ((uint32_t)0x55UL) /**< CN_ERASE_CODE_ERASEPAGE Value */
-#define MXC_S_FLC_CN_ERASE_CODE_ERASEPAGE \
- (MXC_V_FLC_CN_ERASE_CODE_ERASEPAGE \
- << MXC_F_FLC_CN_ERASE_CODE_POS) /**< CN_ERASE_CODE_ERASEPAGE Setting \
- */
-#define MXC_V_FLC_CN_ERASE_CODE_ERASEALL \
- ((uint32_t)0xAAUL) /**< CN_ERASE_CODE_ERASEALL Value */
-#define MXC_S_FLC_CN_ERASE_CODE_ERASEALL \
- (MXC_V_FLC_CN_ERASE_CODE_ERASEALL \
- << MXC_F_FLC_CN_ERASE_CODE_POS) /**< CN_ERASE_CODE_ERASEALL Setting \
- */
-
-#define MXC_F_FLC_CN_PEND_POS 24 /**< CN_PEND Position */
-#define MXC_F_FLC_CN_PEND \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_PEND_POS)) /**< CN_PEND Mask */
-#define MXC_V_FLC_CN_PEND_IDLE ((uint32_t)0x0UL) /**< CN_PEND_IDLE Value */
-#define MXC_S_FLC_CN_PEND_IDLE \
- (MXC_V_FLC_CN_PEND_IDLE \
- << MXC_F_FLC_CN_PEND_POS) /**< CN_PEND_IDLE Setting */
-#define MXC_V_FLC_CN_PEND_BUSY ((uint32_t)0x1UL) /**< CN_PEND_BUSY Value */
-#define MXC_S_FLC_CN_PEND_BUSY \
- (MXC_V_FLC_CN_PEND_BUSY \
- << MXC_F_FLC_CN_PEND_POS) /**< CN_PEND_BUSY Setting */
-
-#define MXC_F_FLC_CN_LVE_POS 25 /**< CN_LVE Position */
-#define MXC_F_FLC_CN_LVE \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_LVE_POS)) /**< CN_LVE Mask */
-#define MXC_V_FLC_CN_LVE_DIS ((uint32_t)0x0UL) /**< CN_LVE_DIS Value */
-#define MXC_S_FLC_CN_LVE_DIS \
- (MXC_V_FLC_CN_LVE_DIS \
- << MXC_F_FLC_CN_LVE_POS) /**< CN_LVE_DIS Setting */
-#define MXC_V_FLC_CN_LVE_EN ((uint32_t)0x1UL) /**< CN_LVE_EN Value */
-#define MXC_S_FLC_CN_LVE_EN \
- (MXC_V_FLC_CN_LVE_EN << MXC_F_FLC_CN_LVE_POS) /**< CN_LVE_EN Setting \
- */
-
-#define MXC_F_FLC_CN_BRST_POS 27 /**< CN_BRST Position */
-#define MXC_F_FLC_CN_BRST \
- ((uint32_t)(0x1UL << MXC_F_FLC_CN_BRST_POS)) /**< CN_BRST Mask */
-#define MXC_V_FLC_CN_BRST_DISABLE \
- ((uint32_t)0x0UL) /**< CN_BRST_DISABLE Value */
-#define MXC_S_FLC_CN_BRST_DISABLE \
- (MXC_V_FLC_CN_BRST_DISABLE \
- << MXC_F_FLC_CN_BRST_POS) /**< CN_BRST_DISABLE Setting */
-#define MXC_V_FLC_CN_BRST_ENABLE \
- ((uint32_t)0x1UL) /**< CN_BRST_ENABLE Value \
- */
-#define MXC_S_FLC_CN_BRST_ENABLE \
- (MXC_V_FLC_CN_BRST_ENABLE \
- << MXC_F_FLC_CN_BRST_POS) /**< CN_BRST_ENABLE Setting */
-
-#define MXC_F_FLC_CN_UNLOCK_POS 28 /**< CN_UNLOCK Position */
-#define MXC_F_FLC_CN_UNLOCK \
- ((uint32_t)(0xFUL << MXC_F_FLC_CN_UNLOCK_POS)) /**< CN_UNLOCK Mask */
-#define MXC_V_FLC_CN_UNLOCK_UNLOCKED \
- ((uint32_t)0x2UL) /**< CN_UNLOCK_UNLOCKED Value */
-#define MXC_S_FLC_CN_UNLOCK_UNLOCKED \
- (MXC_V_FLC_CN_UNLOCK_UNLOCKED \
- << MXC_F_FLC_CN_UNLOCK_POS) /**< CN_UNLOCK_UNLOCKED Setting */
-
-/**
- * Flash Interrupt Register.
- */
-#define MXC_F_FLC_INTR_DONE_POS 0 /**< INTR_DONE Position */
-#define MXC_F_FLC_INTR_DONE \
- ((uint32_t)(0x1UL << MXC_F_FLC_INTR_DONE_POS)) /**< INTR_DONE Mask */
-#define MXC_V_FLC_INTR_DONE_INACTIVE \
- ((uint32_t)0x0UL) /**< INTR_DONE_INACTIVE Value */
-#define MXC_S_FLC_INTR_DONE_INACTIVE \
- (MXC_V_FLC_INTR_DONE_INACTIVE \
- << MXC_F_FLC_INTR_DONE_POS) /**< INTR_DONE_INACTIVE Setting */
-#define MXC_V_FLC_INTR_DONE_PENDING \
- ((uint32_t)0x1UL) /**< INTR_DONE_PENDING Value */
-#define MXC_S_FLC_INTR_DONE_PENDING \
- (MXC_V_FLC_INTR_DONE_PENDING \
- << MXC_F_FLC_INTR_DONE_POS) /**< INTR_DONE_PENDING Setting */
-
-#define MXC_F_FLC_INTR_AF_POS 1 /**< INTR_AF Position */
-#define MXC_F_FLC_INTR_AF \
- ((uint32_t)(0x1UL << MXC_F_FLC_INTR_AF_POS)) /**< INTR_AF Mask */
-#define MXC_V_FLC_INTR_AF_NOERROR \
- ((uint32_t)0x0UL) /**< INTR_AF_NOERROR Value */
-#define MXC_S_FLC_INTR_AF_NOERROR \
- (MXC_V_FLC_INTR_AF_NOERROR \
- << MXC_F_FLC_INTR_AF_POS) /**< INTR_AF_NOERROR Setting */
-#define MXC_V_FLC_INTR_AF_ERROR ((uint32_t)0x1UL) /**< INTR_AF_ERROR Value */
-#define MXC_S_FLC_INTR_AF_ERROR \
- (MXC_V_FLC_INTR_AF_ERROR \
- << MXC_F_FLC_INTR_AF_POS) /**< INTR_AF_ERROR Setting */
-
-#define MXC_F_FLC_INTR_DONEIE_POS 8 /**< INTR_DONEIE Position */
-#define MXC_F_FLC_INTR_DONEIE \
- ((uint32_t)( \
- 0x1UL << MXC_F_FLC_INTR_DONEIE_POS)) /**< INTR_DONEIE Mask */
-#define MXC_V_FLC_INTR_DONEIE_DISABLE \
- ((uint32_t)0x0UL) /**< INTR_DONEIE_DISABLE Value */
-#define MXC_S_FLC_INTR_DONEIE_DISABLE \
- (MXC_V_FLC_INTR_DONEIE_DISABLE \
- << MXC_F_FLC_INTR_DONEIE_POS) /**< INTR_DONEIE_DISABLE Setting */
-#define MXC_V_FLC_INTR_DONEIE_ENABLE \
- ((uint32_t)0x1UL) /**< INTR_DONEIE_ENABLE Value */
-#define MXC_S_FLC_INTR_DONEIE_ENABLE \
- (MXC_V_FLC_INTR_DONEIE_ENABLE \
- << MXC_F_FLC_INTR_DONEIE_POS) /**< INTR_DONEIE_ENABLE Setting */
-
-#define MXC_F_FLC_INTR_AFIE_POS 9 /**< INTR_AFIE Position */
-#define MXC_F_FLC_INTR_AFIE \
- ((uint32_t)(0x1UL << MXC_F_FLC_INTR_AFIE_POS)) /**< INTR_AFIE Mask */
-
-/**
- * Flash Write Data.
- */
-#define MXC_F_FLC_DATA_DATA_POS 0 /**< DATA_DATA Position */
-#define MXC_F_FLC_DATA_DATA \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_FLC_DATA_DATA_POS)) /**< DATA_DATA Mask */
-
-/**
- * Access Control Register. Writing the ACNTL register with the
- * following values in the order shown, allows read and write access to the
- * system and user Information block: pflc-acntl = 0x3a7f5ca3; pflc-acntl =
- * 0xa1e34f20; pflc-acntl = 0x9608b2c1. When unlocked, a write of any word will
- * disable access to system and user information block. Readback of this
- * register is always zero.
- */
-#define MXC_F_FLC_ACNTL_ACNTL_POS 0 /**< ACNTL_ACNTL Position */
-#define MXC_F_FLC_ACNTL_ACNTL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_FLC_ACNTL_ACNTL_POS)) /**< ACNTL_ACNTL Mask */
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* _FLC_REGS_H_ */
diff --git a/chip/max32660/gcr_regs.h b/chip/max32660/gcr_regs.h
deleted file mode 100644
index c9de13812c..0000000000
--- a/chip/max32660/gcr_regs.h
+++ /dev/null
@@ -1,1365 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the GCR Peripheral Module
- */
-
-#ifndef _GCR_REGS_H_
-#define _GCR_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/* **** Definitions **** */
-
-/**
- * Registers, Bit Masks and Bit Positions for the GCR Peripheral
- * Module.
- */
-
-/**
- * Structure type to access the GCR Registers.
- */
-typedef struct {
- __IO uint32_t scon; /**< <tt>\b 0x00:<\tt> GCR SCON Register */
- __IO uint32_t rstr0; /**< <tt>\b 0x04:<\tt> GCR RSTR0 Register */
- __IO uint32_t clkcn; /**< <tt>\b 0x08:<\tt> GCR CLKCN Register */
- __IO uint32_t pm; /**< <tt>\b 0x0C:<\tt> GCR PM Register */
- __R uint32_t rsv_0x10_0x17[2];
- __IO uint32_t pckdiv; /**< <tt>\b 0x18:<\tt> GCR PCKDIV Register */
- __R uint32_t rsv_0x1c_0x23[2];
- __IO uint32_t perckcn0; /**< <tt>\b 0x24:<\tt> GCR PERCKCN0 Register */
- __IO uint32_t memckcn; /**< <tt>\b 0x28:<\tt> GCR MEMCKCN Register */
- __IO uint32_t memzcn; /**< <tt>\b 0x2C:<\tt> GCR MEMZCN Register */
- __R uint32_t rsv_0x30;
- __IO uint32_t scck; /**< <tt>\b 0x34:<\tt> GCR SCCK Register */
- __IO uint32_t mpri0; /**< <tt>\b 0x38:<\tt> GCR MPRI0 Register */
- __IO uint32_t mpri1; /**< <tt>\b 0x3C:<\tt> GCR MPRI1 Register */
- __IO uint32_t sysst; /**< <tt>\b 0x40:<\tt> GCR SYSST Register */
- __IO uint32_t rstr1; /**< <tt>\b 0x44:<\tt> GCR RSTR1 Register */
- __IO uint32_t perckcn1; /**< <tt>\b 0x48:<\tt> GCR PERCKCN1 Register */
- __IO uint32_t evten; /**< <tt>\b 0x4C:<\tt> GCR EVTEN Register */
- __I uint32_t revision; /**< <tt>\b 0x50:<\tt> GCR REVISION Register */
- __IO uint32_t syssie; /**< <tt>\b 0x54:<\tt> GCR SYSSIE Register */
-} mxc_gcr_regs_t;
-
-/**
- * GCR Peripheral Register Offsets from the GCR Base Peripheral
- * Address.
- */
-#define MXC_R_GCR_SCON \
- ((uint32_t)0x00000000UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_GCR_RSTR0 \
- ((uint32_t)0x00000004UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_GCR_CLKCN \
- ((uint32_t)0x00000008UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x008 */
-#define MXC_R_GCR_PM \
- ((uint32_t)0x0000000CUL) /**< Offset from GCR Base Address: <tt> \
- 0x0x00C */
-#define MXC_R_GCR_PCKDIV \
- ((uint32_t)0x00000018UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x018 */
-#define MXC_R_GCR_PERCKCN0 \
- ((uint32_t)0x00000024UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x024 */
-#define MXC_R_GCR_MEMCKCN \
- ((uint32_t)0x00000028UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x028 */
-#define MXC_R_GCR_MEMZCN \
- ((uint32_t)0x0000002CUL) /**< Offset from GCR Base Address: <tt> \
- 0x0x02C */
-#define MXC_R_GCR_SCCK \
- ((uint32_t)0x00000034UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x034 */
-#define MXC_R_GCR_MPRI0 \
- ((uint32_t)0x00000038UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x038 */
-#define MXC_R_GCR_MPRI1 \
- ((uint32_t)0x0000003CUL) /**< Offset from GCR Base Address: <tt> \
- 0x0x03C */
-#define MXC_R_GCR_SYSST \
- ((uint32_t)0x00000040UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x040 */
-#define MXC_R_GCR_RSTR1 \
- ((uint32_t)0x00000044UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x044 */
-#define MXC_R_GCR_PERCKCN1 \
- ((uint32_t)0x00000048UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x048 */
-#define MXC_R_GCR_EVTEN \
- ((uint32_t)0x0000004CUL) /**< Offset from GCR Base Address: <tt> \
- 0x0x04C */
-#define MXC_R_GCR_REVISION \
- ((uint32_t)0x00000050UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x050 */
-#define MXC_R_GCR_SYSSIE \
- ((uint32_t)0x00000054UL) /**< Offset from GCR Base Address: <tt> \
- 0x0x054 */
-
-/**
- * System Control.
- */
-#define MXC_F_GCR_SCON_SBUSARB_POS 1 /**< SCON_SBUSARB Position */
-#define MXC_F_GCR_SCON_SBUSARB \
- ((uint32_t)(0x3UL \
- << MXC_F_GCR_SCON_SBUSARB_POS)) /**< SCON_SBUSARB Mask */
-#define MXC_V_GCR_SCON_SBUSARB_FIX \
- ((uint32_t)0x0UL) /**< SCON_SBUSARB_FIX Value */
-#define MXC_S_GCR_SCON_SBUSARB_FIX \
- (MXC_V_GCR_SCON_SBUSARB_FIX \
- << MXC_F_GCR_SCON_SBUSARB_POS) /**< SCON_SBUSARB_FIX Setting */
-#define MXC_V_GCR_SCON_SBUSARB_ROUND \
- ((uint32_t)0x1UL) /**< SCON_SBUSARB_ROUND Value */
-#define MXC_S_GCR_SCON_SBUSARB_ROUND \
- (MXC_V_GCR_SCON_SBUSARB_ROUND \
- << MXC_F_GCR_SCON_SBUSARB_POS) /**< SCON_SBUSARB_ROUND Setting */
-
-#define MXC_F_GCR_SCON_FLASH_PAGE_FLIP_POS \
- 4 /**< SCON_FLASH_PAGE_FLIP Position */
-#define MXC_F_GCR_SCON_FLASH_PAGE_FLIP \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_SCON_FLASH_PAGE_FLIP_POS)) /**< \
- SCON_FLASH_PAGE_FLIP \
- Mask */
-#define MXC_V_GCR_SCON_FLASH_PAGE_FLIP_NORMAL \
- ((uint32_t)0x0UL) /**< SCON_FLASH_PAGE_FLIP_NORMAL Value */
-#define MXC_S_GCR_SCON_FLASH_PAGE_FLIP_NORMAL \
- (MXC_V_GCR_SCON_FLASH_PAGE_FLIP_NORMAL \
- << MXC_F_GCR_SCON_FLASH_PAGE_FLIP_POS) /**< \
- SCON_FLASH_PAGE_FLIP_NORMAL \
- Setting */
-#define MXC_V_GCR_SCON_FLASH_PAGE_FLIP_SWAPPED \
- ((uint32_t)0x1UL) /**< SCON_FLASH_PAGE_FLIP_SWAPPED Value */
-#define MXC_S_GCR_SCON_FLASH_PAGE_FLIP_SWAPPED \
- (MXC_V_GCR_SCON_FLASH_PAGE_FLIP_SWAPPED \
- << MXC_F_GCR_SCON_FLASH_PAGE_FLIP_POS) /**< \
- SCON_FLASH_PAGE_FLIP_SWAPPED \
- Setting */
-
-#define MXC_F_GCR_SCON_FPU_DIS_POS 5 /**< SCON_FPU_DIS Position */
-#define MXC_F_GCR_SCON_FPU_DIS \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_SCON_FPU_DIS_POS)) /**< SCON_FPU_DIS Mask */
-#define MXC_V_GCR_SCON_FPU_DIS_ENABLE \
- ((uint32_t)0x0UL) /**< SCON_FPU_DIS_ENABLE Value */
-#define MXC_S_GCR_SCON_FPU_DIS_ENABLE \
- (MXC_V_GCR_SCON_FPU_DIS_ENABLE \
- << MXC_F_GCR_SCON_FPU_DIS_POS) /**< SCON_FPU_DIS_ENABLE Setting */
-#define MXC_V_GCR_SCON_FPU_DIS_DISABLE \
- ((uint32_t)0x1UL) /**< SCON_FPU_DIS_DISABLE Value */
-#define MXC_S_GCR_SCON_FPU_DIS_DISABLE \
- (MXC_V_GCR_SCON_FPU_DIS_DISABLE \
- << MXC_F_GCR_SCON_FPU_DIS_POS) /**< SCON_FPU_DIS_DISABLE Setting */
-
-#define MXC_F_GCR_SCON_CCACHE_FLUSH_POS 6 /**< SCON_CCACHE_FLUSH Position */
-#define MXC_F_GCR_SCON_CCACHE_FLUSH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_SCON_CCACHE_FLUSH_POS)) /**< SCON_CCACHE_FLUSH \
- Mask */
-#define MXC_V_GCR_SCON_CCACHE_FLUSH_NORMAL \
- ((uint32_t)0x0UL) /**< SCON_CCACHE_FLUSH_NORMAL Value */
-#define MXC_S_GCR_SCON_CCACHE_FLUSH_NORMAL \
- (MXC_V_GCR_SCON_CCACHE_FLUSH_NORMAL \
- << MXC_F_GCR_SCON_CCACHE_FLUSH_POS) /**< SCON_CCACHE_FLUSH_NORMAL \
- Setting */
-#define MXC_V_GCR_SCON_CCACHE_FLUSH_FLUSH \
- ((uint32_t)0x1UL) /**< SCON_CCACHE_FLUSH_FLUSH Value */
-#define MXC_S_GCR_SCON_CCACHE_FLUSH_FLUSH \
- (MXC_V_GCR_SCON_CCACHE_FLUSH_FLUSH \
- << MXC_F_GCR_SCON_CCACHE_FLUSH_POS) /**< SCON_CCACHE_FLUSH_FLUSH \
- Setting */
-
-#define MXC_F_GCR_SCON_SWD_DIS_POS 14 /**< SCON_SWD_DIS Position */
-#define MXC_F_GCR_SCON_SWD_DIS \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_SCON_SWD_DIS_POS)) /**< SCON_SWD_DIS Mask */
-#define MXC_V_GCR_SCON_SWD_DIS_ENABLE \
- ((uint32_t)0x0UL) /**< SCON_SWD_DIS_ENABLE Value */
-#define MXC_S_GCR_SCON_SWD_DIS_ENABLE \
- (MXC_V_GCR_SCON_SWD_DIS_ENABLE \
- << MXC_F_GCR_SCON_SWD_DIS_POS) /**< SCON_SWD_DIS_ENABLE Setting */
-#define MXC_V_GCR_SCON_SWD_DIS_DISABLE \
- ((uint32_t)0x1UL) /**< SCON_SWD_DIS_DISABLE Value */
-#define MXC_S_GCR_SCON_SWD_DIS_DISABLE \
- (MXC_V_GCR_SCON_SWD_DIS_DISABLE \
- << MXC_F_GCR_SCON_SWD_DIS_POS) /**< SCON_SWD_DIS_DISABLE Setting */
-
-/**
- * Reset Register 0.
- */
-#define MXC_F_GCR_RSTR0_DMA_POS 0 /**< RSTR0_DMA Position */
-#define MXC_F_GCR_RSTR0_DMA \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_DMA_POS)) /**< RSTR0_DMA Mask */
-#define MXC_V_GCR_RSTR0_DMA_RFU ((uint32_t)0x0UL) /**< RSTR0_DMA_RFU Value */
-#define MXC_S_GCR_RSTR0_DMA_RFU \
- (MXC_V_GCR_RSTR0_DMA_RFU \
- << MXC_F_GCR_RSTR0_DMA_POS) /**< RSTR0_DMA_RFU Setting */
-#define MXC_V_GCR_RSTR0_DMA_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_DMA_RESET Value */
-#define MXC_S_GCR_RSTR0_DMA_RESET \
- (MXC_V_GCR_RSTR0_DMA_RESET \
- << MXC_F_GCR_RSTR0_DMA_POS) /**< RSTR0_DMA_RESET Setting */
-#define MXC_V_GCR_RSTR0_DMA_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_DMA_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_DMA_RESET_DONE \
- (MXC_V_GCR_RSTR0_DMA_RESET_DONE \
- << MXC_F_GCR_RSTR0_DMA_POS) /**< RSTR0_DMA_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_DMA_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_DMA_BUSY Value \
- */
-#define MXC_S_GCR_RSTR0_DMA_BUSY \
- (MXC_V_GCR_RSTR0_DMA_BUSY \
- << MXC_F_GCR_RSTR0_DMA_POS) /**< RSTR0_DMA_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_WDT_POS 1 /**< RSTR0_WDT Position */
-#define MXC_F_GCR_RSTR0_WDT \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_WDT_POS)) /**< RSTR0_WDT Mask */
-#define MXC_V_GCR_RSTR0_WDT_RFU ((uint32_t)0x0UL) /**< RSTR0_WDT_RFU Value */
-#define MXC_S_GCR_RSTR0_WDT_RFU \
- (MXC_V_GCR_RSTR0_WDT_RFU \
- << MXC_F_GCR_RSTR0_WDT_POS) /**< RSTR0_WDT_RFU Setting */
-#define MXC_V_GCR_RSTR0_WDT_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_WDT_RESET Value */
-#define MXC_S_GCR_RSTR0_WDT_RESET \
- (MXC_V_GCR_RSTR0_WDT_RESET \
- << MXC_F_GCR_RSTR0_WDT_POS) /**< RSTR0_WDT_RESET Setting */
-#define MXC_V_GCR_RSTR0_WDT_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_WDT_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_WDT_RESET_DONE \
- (MXC_V_GCR_RSTR0_WDT_RESET_DONE \
- << MXC_F_GCR_RSTR0_WDT_POS) /**< RSTR0_WDT_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_WDT_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_WDT_BUSY Value \
- */
-#define MXC_S_GCR_RSTR0_WDT_BUSY \
- (MXC_V_GCR_RSTR0_WDT_BUSY \
- << MXC_F_GCR_RSTR0_WDT_POS) /**< RSTR0_WDT_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_GPIO0_POS 2 /**< RSTR0_GPIO0 Position */
-#define MXC_F_GCR_RSTR0_GPIO0 \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_RSTR0_GPIO0_POS)) /**< RSTR0_GPIO0 Mask */
-#define MXC_V_GCR_RSTR0_GPIO0_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_GPIO0_RFU Value */
-#define MXC_S_GCR_RSTR0_GPIO0_RFU \
- (MXC_V_GCR_RSTR0_GPIO0_RFU \
- << MXC_F_GCR_RSTR0_GPIO0_POS) /**< RSTR0_GPIO0_RFU Setting */
-#define MXC_V_GCR_RSTR0_GPIO0_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_GPIO0_RESET Value */
-#define MXC_S_GCR_RSTR0_GPIO0_RESET \
- (MXC_V_GCR_RSTR0_GPIO0_RESET \
- << MXC_F_GCR_RSTR0_GPIO0_POS) /**< RSTR0_GPIO0_RESET Setting */
-#define MXC_V_GCR_RSTR0_GPIO0_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_GPIO0_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_GPIO0_RESET_DONE \
- (MXC_V_GCR_RSTR0_GPIO0_RESET_DONE \
- << MXC_F_GCR_RSTR0_GPIO0_POS) /**< RSTR0_GPIO0_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_GPIO0_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_GPIO0_BUSY Value */
-#define MXC_S_GCR_RSTR0_GPIO0_BUSY \
- (MXC_V_GCR_RSTR0_GPIO0_BUSY \
- << MXC_F_GCR_RSTR0_GPIO0_POS) /**< RSTR0_GPIO0_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_TIMER0_POS 5 /**< RSTR0_TIMER0 Position */
-#define MXC_F_GCR_RSTR0_TIMER0 \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_RSTR0_TIMER0_POS)) /**< RSTR0_TIMER0 Mask */
-#define MXC_V_GCR_RSTR0_TIMER0_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER0_RFU Value */
-#define MXC_S_GCR_RSTR0_TIMER0_RFU \
- (MXC_V_GCR_RSTR0_TIMER0_RFU \
- << MXC_F_GCR_RSTR0_TIMER0_POS) /**< RSTR0_TIMER0_RFU Setting */
-#define MXC_V_GCR_RSTR0_TIMER0_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER0_RESET Value */
-#define MXC_S_GCR_RSTR0_TIMER0_RESET \
- (MXC_V_GCR_RSTR0_TIMER0_RESET \
- << MXC_F_GCR_RSTR0_TIMER0_POS) /**< RSTR0_TIMER0_RESET Setting */
-#define MXC_V_GCR_RSTR0_TIMER0_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER0_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_TIMER0_RESET_DONE \
- (MXC_V_GCR_RSTR0_TIMER0_RESET_DONE \
- << MXC_F_GCR_RSTR0_TIMER0_POS) /**< RSTR0_TIMER0_RESET_DONE Setting \
- */
-#define MXC_V_GCR_RSTR0_TIMER0_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER0_BUSY Value */
-#define MXC_S_GCR_RSTR0_TIMER0_BUSY \
- (MXC_V_GCR_RSTR0_TIMER0_BUSY \
- << MXC_F_GCR_RSTR0_TIMER0_POS) /**< RSTR0_TIMER0_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_TIMER1_POS 6 /**< RSTR0_TIMER1 Position */
-#define MXC_F_GCR_RSTR0_TIMER1 \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_RSTR0_TIMER1_POS)) /**< RSTR0_TIMER1 Mask */
-#define MXC_V_GCR_RSTR0_TIMER1_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER1_RFU Value */
-#define MXC_S_GCR_RSTR0_TIMER1_RFU \
- (MXC_V_GCR_RSTR0_TIMER1_RFU \
- << MXC_F_GCR_RSTR0_TIMER1_POS) /**< RSTR0_TIMER1_RFU Setting */
-#define MXC_V_GCR_RSTR0_TIMER1_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER1_RESET Value */
-#define MXC_S_GCR_RSTR0_TIMER1_RESET \
- (MXC_V_GCR_RSTR0_TIMER1_RESET \
- << MXC_F_GCR_RSTR0_TIMER1_POS) /**< RSTR0_TIMER1_RESET Setting */
-#define MXC_V_GCR_RSTR0_TIMER1_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER1_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_TIMER1_RESET_DONE \
- (MXC_V_GCR_RSTR0_TIMER1_RESET_DONE \
- << MXC_F_GCR_RSTR0_TIMER1_POS) /**< RSTR0_TIMER1_RESET_DONE Setting \
- */
-#define MXC_V_GCR_RSTR0_TIMER1_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER1_BUSY Value */
-#define MXC_S_GCR_RSTR0_TIMER1_BUSY \
- (MXC_V_GCR_RSTR0_TIMER1_BUSY \
- << MXC_F_GCR_RSTR0_TIMER1_POS) /**< RSTR0_TIMER1_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_TIMER2_POS 7 /**< RSTR0_TIMER2 Position */
-#define MXC_F_GCR_RSTR0_TIMER2 \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_RSTR0_TIMER2_POS)) /**< RSTR0_TIMER2 Mask */
-#define MXC_V_GCR_RSTR0_TIMER2_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER2_RFU Value */
-#define MXC_S_GCR_RSTR0_TIMER2_RFU \
- (MXC_V_GCR_RSTR0_TIMER2_RFU \
- << MXC_F_GCR_RSTR0_TIMER2_POS) /**< RSTR0_TIMER2_RFU Setting */
-#define MXC_V_GCR_RSTR0_TIMER2_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER2_RESET Value */
-#define MXC_S_GCR_RSTR0_TIMER2_RESET \
- (MXC_V_GCR_RSTR0_TIMER2_RESET \
- << MXC_F_GCR_RSTR0_TIMER2_POS) /**< RSTR0_TIMER2_RESET Setting */
-#define MXC_V_GCR_RSTR0_TIMER2_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_TIMER2_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_TIMER2_RESET_DONE \
- (MXC_V_GCR_RSTR0_TIMER2_RESET_DONE \
- << MXC_F_GCR_RSTR0_TIMER2_POS) /**< RSTR0_TIMER2_RESET_DONE Setting \
- */
-#define MXC_V_GCR_RSTR0_TIMER2_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_TIMER2_BUSY Value */
-#define MXC_S_GCR_RSTR0_TIMER2_BUSY \
- (MXC_V_GCR_RSTR0_TIMER2_BUSY \
- << MXC_F_GCR_RSTR0_TIMER2_POS) /**< RSTR0_TIMER2_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_UART0_POS 11 /**< RSTR0_UART0 Position */
-#define MXC_F_GCR_RSTR0_UART0 \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_RSTR0_UART0_POS)) /**< RSTR0_UART0 Mask */
-#define MXC_V_GCR_RSTR0_UART0_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_UART0_RFU Value */
-#define MXC_S_GCR_RSTR0_UART0_RFU \
- (MXC_V_GCR_RSTR0_UART0_RFU \
- << MXC_F_GCR_RSTR0_UART0_POS) /**< RSTR0_UART0_RFU Setting */
-#define MXC_V_GCR_RSTR0_UART0_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_UART0_RESET Value */
-#define MXC_S_GCR_RSTR0_UART0_RESET \
- (MXC_V_GCR_RSTR0_UART0_RESET \
- << MXC_F_GCR_RSTR0_UART0_POS) /**< RSTR0_UART0_RESET Setting */
-#define MXC_V_GCR_RSTR0_UART0_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_UART0_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_UART0_RESET_DONE \
- (MXC_V_GCR_RSTR0_UART0_RESET_DONE \
- << MXC_F_GCR_RSTR0_UART0_POS) /**< RSTR0_UART0_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_UART0_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_UART0_BUSY Value */
-#define MXC_S_GCR_RSTR0_UART0_BUSY \
- (MXC_V_GCR_RSTR0_UART0_BUSY \
- << MXC_F_GCR_RSTR0_UART0_POS) /**< RSTR0_UART0_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_UART1_POS 12 /**< RSTR0_UART1 Position */
-#define MXC_F_GCR_RSTR0_UART1 \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_RSTR0_UART1_POS)) /**< RSTR0_UART1 Mask */
-#define MXC_V_GCR_RSTR0_UART1_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_UART1_RFU Value */
-#define MXC_S_GCR_RSTR0_UART1_RFU \
- (MXC_V_GCR_RSTR0_UART1_RFU \
- << MXC_F_GCR_RSTR0_UART1_POS) /**< RSTR0_UART1_RFU Setting */
-#define MXC_V_GCR_RSTR0_UART1_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_UART1_RESET Value */
-#define MXC_S_GCR_RSTR0_UART1_RESET \
- (MXC_V_GCR_RSTR0_UART1_RESET \
- << MXC_F_GCR_RSTR0_UART1_POS) /**< RSTR0_UART1_RESET Setting */
-#define MXC_V_GCR_RSTR0_UART1_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_UART1_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_UART1_RESET_DONE \
- (MXC_V_GCR_RSTR0_UART1_RESET_DONE \
- << MXC_F_GCR_RSTR0_UART1_POS) /**< RSTR0_UART1_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_UART1_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_UART1_BUSY Value */
-#define MXC_S_GCR_RSTR0_UART1_BUSY \
- (MXC_V_GCR_RSTR0_UART1_BUSY \
- << MXC_F_GCR_RSTR0_UART1_POS) /**< RSTR0_UART1_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_SPI0_POS 13 /**< RSTR0_SPI0 Position */
-#define MXC_F_GCR_RSTR0_SPI0 \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_SPI0_POS)) /**< RSTR0_SPI0 Mask \
- */
-#define MXC_V_GCR_RSTR0_SPI0_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_SPI0_RFU Value \
- */
-#define MXC_S_GCR_RSTR0_SPI0_RFU \
- (MXC_V_GCR_RSTR0_SPI0_RFU \
- << MXC_F_GCR_RSTR0_SPI0_POS) /**< RSTR0_SPI0_RFU Setting */
-#define MXC_V_GCR_RSTR0_SPI0_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_SPI0_RESET Value */
-#define MXC_S_GCR_RSTR0_SPI0_RESET \
- (MXC_V_GCR_RSTR0_SPI0_RESET \
- << MXC_F_GCR_RSTR0_SPI0_POS) /**< RSTR0_SPI0_RESET Setting */
-#define MXC_V_GCR_RSTR0_SPI0_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_SPI0_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_SPI0_RESET_DONE \
- (MXC_V_GCR_RSTR0_SPI0_RESET_DONE \
- << MXC_F_GCR_RSTR0_SPI0_POS) /**< RSTR0_SPI0_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_SPI0_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_SPI0_BUSY Value */
-#define MXC_S_GCR_RSTR0_SPI0_BUSY \
- (MXC_V_GCR_RSTR0_SPI0_BUSY \
- << MXC_F_GCR_RSTR0_SPI0_POS) /**< RSTR0_SPI0_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_SPI1_POS 14 /**< RSTR0_SPI1 Position */
-#define MXC_F_GCR_RSTR0_SPI1 \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_SPI1_POS)) /**< RSTR0_SPI1 Mask \
- */
-#define MXC_V_GCR_RSTR0_SPI1_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_SPI1_RFU Value \
- */
-#define MXC_S_GCR_RSTR0_SPI1_RFU \
- (MXC_V_GCR_RSTR0_SPI1_RFU \
- << MXC_F_GCR_RSTR0_SPI1_POS) /**< RSTR0_SPI1_RFU Setting */
-#define MXC_V_GCR_RSTR0_SPI1_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_SPI1_RESET Value */
-#define MXC_S_GCR_RSTR0_SPI1_RESET \
- (MXC_V_GCR_RSTR0_SPI1_RESET \
- << MXC_F_GCR_RSTR0_SPI1_POS) /**< RSTR0_SPI1_RESET Setting */
-#define MXC_V_GCR_RSTR0_SPI1_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_SPI1_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_SPI1_RESET_DONE \
- (MXC_V_GCR_RSTR0_SPI1_RESET_DONE \
- << MXC_F_GCR_RSTR0_SPI1_POS) /**< RSTR0_SPI1_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_SPI1_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_SPI1_BUSY Value */
-#define MXC_S_GCR_RSTR0_SPI1_BUSY \
- (MXC_V_GCR_RSTR0_SPI1_BUSY \
- << MXC_F_GCR_RSTR0_SPI1_POS) /**< RSTR0_SPI1_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_I2C0_POS 16 /**< RSTR0_I2C0 Position */
-#define MXC_F_GCR_RSTR0_I2C0 \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_I2C0_POS)) /**< RSTR0_I2C0 Mask \
- */
-#define MXC_V_GCR_RSTR0_I2C0_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_I2C0_RFU Value \
- */
-#define MXC_S_GCR_RSTR0_I2C0_RFU \
- (MXC_V_GCR_RSTR0_I2C0_RFU \
- << MXC_F_GCR_RSTR0_I2C0_POS) /**< RSTR0_I2C0_RFU Setting */
-#define MXC_V_GCR_RSTR0_I2C0_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_I2C0_RESET Value */
-#define MXC_S_GCR_RSTR0_I2C0_RESET \
- (MXC_V_GCR_RSTR0_I2C0_RESET \
- << MXC_F_GCR_RSTR0_I2C0_POS) /**< RSTR0_I2C0_RESET Setting */
-#define MXC_V_GCR_RSTR0_I2C0_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_I2C0_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_I2C0_RESET_DONE \
- (MXC_V_GCR_RSTR0_I2C0_RESET_DONE \
- << MXC_F_GCR_RSTR0_I2C0_POS) /**< RSTR0_I2C0_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_I2C0_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_I2C0_BUSY Value */
-#define MXC_S_GCR_RSTR0_I2C0_BUSY \
- (MXC_V_GCR_RSTR0_I2C0_BUSY \
- << MXC_F_GCR_RSTR0_I2C0_POS) /**< RSTR0_I2C0_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_RTC_POS 17 /**< RSTR0_RTC Position */
-#define MXC_F_GCR_RSTR0_RTC \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_RTC_POS)) /**< RSTR0_RTC Mask */
-#define MXC_V_GCR_RSTR0_RTC_RFU ((uint32_t)0x0UL) /**< RSTR0_RTC_RFU Value */
-#define MXC_S_GCR_RSTR0_RTC_RFU \
- (MXC_V_GCR_RSTR0_RTC_RFU \
- << MXC_F_GCR_RSTR0_RTC_POS) /**< RSTR0_RTC_RFU Setting */
-#define MXC_V_GCR_RSTR0_RTC_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_RTC_RESET Value */
-#define MXC_S_GCR_RSTR0_RTC_RESET \
- (MXC_V_GCR_RSTR0_RTC_RESET \
- << MXC_F_GCR_RSTR0_RTC_POS) /**< RSTR0_RTC_RESET Setting */
-#define MXC_V_GCR_RSTR0_RTC_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_RTC_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_RTC_RESET_DONE \
- (MXC_V_GCR_RSTR0_RTC_RESET_DONE \
- << MXC_F_GCR_RSTR0_RTC_POS) /**< RSTR0_RTC_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_RTC_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_RTC_BUSY Value \
- */
-#define MXC_S_GCR_RSTR0_RTC_BUSY \
- (MXC_V_GCR_RSTR0_RTC_BUSY \
- << MXC_F_GCR_RSTR0_RTC_POS) /**< RSTR0_RTC_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_SRST_POS 29 /**< RSTR0_SRST Position */
-#define MXC_F_GCR_RSTR0_SRST \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_SRST_POS)) /**< RSTR0_SRST Mask \
- */
-#define MXC_V_GCR_RSTR0_SRST_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_SRST_RFU Value \
- */
-#define MXC_S_GCR_RSTR0_SRST_RFU \
- (MXC_V_GCR_RSTR0_SRST_RFU \
- << MXC_F_GCR_RSTR0_SRST_POS) /**< RSTR0_SRST_RFU Setting */
-#define MXC_V_GCR_RSTR0_SRST_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_SRST_RESET Value */
-#define MXC_S_GCR_RSTR0_SRST_RESET \
- (MXC_V_GCR_RSTR0_SRST_RESET \
- << MXC_F_GCR_RSTR0_SRST_POS) /**< RSTR0_SRST_RESET Setting */
-#define MXC_V_GCR_RSTR0_SRST_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_SRST_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_SRST_RESET_DONE \
- (MXC_V_GCR_RSTR0_SRST_RESET_DONE \
- << MXC_F_GCR_RSTR0_SRST_POS) /**< RSTR0_SRST_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_SRST_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_SRST_BUSY Value */
-#define MXC_S_GCR_RSTR0_SRST_BUSY \
- (MXC_V_GCR_RSTR0_SRST_BUSY \
- << MXC_F_GCR_RSTR0_SRST_POS) /**< RSTR0_SRST_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_PRST_POS 30 /**< RSTR0_PRST Position */
-#define MXC_F_GCR_RSTR0_PRST \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR0_PRST_POS)) /**< RSTR0_PRST Mask \
- */
-#define MXC_V_GCR_RSTR0_PRST_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_PRST_RFU Value \
- */
-#define MXC_S_GCR_RSTR0_PRST_RFU \
- (MXC_V_GCR_RSTR0_PRST_RFU \
- << MXC_F_GCR_RSTR0_PRST_POS) /**< RSTR0_PRST_RFU Setting */
-#define MXC_V_GCR_RSTR0_PRST_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_PRST_RESET Value */
-#define MXC_S_GCR_RSTR0_PRST_RESET \
- (MXC_V_GCR_RSTR0_PRST_RESET \
- << MXC_F_GCR_RSTR0_PRST_POS) /**< RSTR0_PRST_RESET Setting */
-#define MXC_V_GCR_RSTR0_PRST_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_PRST_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_PRST_RESET_DONE \
- (MXC_V_GCR_RSTR0_PRST_RESET_DONE \
- << MXC_F_GCR_RSTR0_PRST_POS) /**< RSTR0_PRST_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR0_PRST_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_PRST_BUSY Value */
-#define MXC_S_GCR_RSTR0_PRST_BUSY \
- (MXC_V_GCR_RSTR0_PRST_BUSY \
- << MXC_F_GCR_RSTR0_PRST_POS) /**< RSTR0_PRST_BUSY Setting */
-
-#define MXC_F_GCR_RSTR0_SYSTEM_POS 31 /**< RSTR0_SYSTEM Position */
-#define MXC_F_GCR_RSTR0_SYSTEM \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_RSTR0_SYSTEM_POS)) /**< RSTR0_SYSTEM Mask */
-#define MXC_V_GCR_RSTR0_SYSTEM_RFU \
- ((uint32_t)0x0UL) /**< RSTR0_SYSTEM_RFU Value */
-#define MXC_S_GCR_RSTR0_SYSTEM_RFU \
- (MXC_V_GCR_RSTR0_SYSTEM_RFU \
- << MXC_F_GCR_RSTR0_SYSTEM_POS) /**< RSTR0_SYSTEM_RFU Setting */
-#define MXC_V_GCR_RSTR0_SYSTEM_RESET \
- ((uint32_t)0x1UL) /**< RSTR0_SYSTEM_RESET Value */
-#define MXC_S_GCR_RSTR0_SYSTEM_RESET \
- (MXC_V_GCR_RSTR0_SYSTEM_RESET \
- << MXC_F_GCR_RSTR0_SYSTEM_POS) /**< RSTR0_SYSTEM_RESET Setting */
-#define MXC_V_GCR_RSTR0_SYSTEM_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR0_SYSTEM_RESET_DONE Value */
-#define MXC_S_GCR_RSTR0_SYSTEM_RESET_DONE \
- (MXC_V_GCR_RSTR0_SYSTEM_RESET_DONE \
- << MXC_F_GCR_RSTR0_SYSTEM_POS) /**< RSTR0_SYSTEM_RESET_DONE Setting \
- */
-#define MXC_V_GCR_RSTR0_SYSTEM_BUSY \
- ((uint32_t)0x1UL) /**< RSTR0_SYSTEM_BUSY Value */
-#define MXC_S_GCR_RSTR0_SYSTEM_BUSY \
- (MXC_V_GCR_RSTR0_SYSTEM_BUSY \
- << MXC_F_GCR_RSTR0_SYSTEM_POS) /**< RSTR0_SYSTEM_BUSY Setting */
-
-/**
- * Clock Control.
- */
-#define MXC_F_GCR_CLKCN_PSC_POS 6 /**< CLKCN_PSC Position */
-#define MXC_F_GCR_CLKCN_PSC \
- ((uint32_t)(0x7UL << MXC_F_GCR_CLKCN_PSC_POS)) /**< CLKCN_PSC Mask */
-#define MXC_V_GCR_CLKCN_PSC_DIV1 \
- ((uint32_t)0x0UL) /**< CLKCN_PSC_DIV1 Value \
- */
-#define MXC_S_GCR_CLKCN_PSC_DIV1 \
- (MXC_V_GCR_CLKCN_PSC_DIV1 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV1 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV2 \
- ((uint32_t)0x1UL) /**< CLKCN_PSC_DIV2 Value \
- */
-#define MXC_S_GCR_CLKCN_PSC_DIV2 \
- (MXC_V_GCR_CLKCN_PSC_DIV2 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV2 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV4 \
- ((uint32_t)0x2UL) /**< CLKCN_PSC_DIV4 Value \
- */
-#define MXC_S_GCR_CLKCN_PSC_DIV4 \
- (MXC_V_GCR_CLKCN_PSC_DIV4 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV4 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV8 \
- ((uint32_t)0x3UL) /**< CLKCN_PSC_DIV8 Value \
- */
-#define MXC_S_GCR_CLKCN_PSC_DIV8 \
- (MXC_V_GCR_CLKCN_PSC_DIV8 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV8 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV16 \
- ((uint32_t)0x4UL) /**< CLKCN_PSC_DIV16 Value */
-#define MXC_S_GCR_CLKCN_PSC_DIV16 \
- (MXC_V_GCR_CLKCN_PSC_DIV16 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV16 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV32 \
- ((uint32_t)0x5UL) /**< CLKCN_PSC_DIV32 Value */
-#define MXC_S_GCR_CLKCN_PSC_DIV32 \
- (MXC_V_GCR_CLKCN_PSC_DIV32 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV32 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV64 \
- ((uint32_t)0x6UL) /**< CLKCN_PSC_DIV64 Value */
-#define MXC_S_GCR_CLKCN_PSC_DIV64 \
- (MXC_V_GCR_CLKCN_PSC_DIV64 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV64 Setting */
-#define MXC_V_GCR_CLKCN_PSC_DIV128 \
- ((uint32_t)0x7UL) /**< CLKCN_PSC_DIV128 Value */
-#define MXC_S_GCR_CLKCN_PSC_DIV128 \
- (MXC_V_GCR_CLKCN_PSC_DIV128 \
- << MXC_F_GCR_CLKCN_PSC_POS) /**< CLKCN_PSC_DIV128 Setting */
-
-#define MXC_F_GCR_CLKCN_CLKSEL_POS 9 /**< CLKCN_CLKSEL Position */
-#define MXC_F_GCR_CLKCN_CLKSEL \
- ((uint32_t)(0x7UL \
- << MXC_F_GCR_CLKCN_CLKSEL_POS)) /**< CLKCN_CLKSEL Mask */
-#define MXC_V_GCR_CLKCN_CLKSEL_HIRC \
- ((uint32_t)0x0UL) /**< CLKCN_CLKSEL_HIRC Value */
-#define MXC_S_GCR_CLKCN_CLKSEL_HIRC \
- (MXC_V_GCR_CLKCN_CLKSEL_HIRC \
- << MXC_F_GCR_CLKCN_CLKSEL_POS) /**< CLKCN_CLKSEL_HIRC Setting */
-#define MXC_V_GCR_CLKCN_CLKSEL_NANORING \
- ((uint32_t)0x3UL) /**< CLKCN_CLKSEL_NANORING Value */
-#define MXC_S_GCR_CLKCN_CLKSEL_NANORING \
- (MXC_V_GCR_CLKCN_CLKSEL_NANORING \
- << MXC_F_GCR_CLKCN_CLKSEL_POS) /**< CLKCN_CLKSEL_NANORING Setting */
-#define MXC_V_GCR_CLKCN_CLKSEL_HFXIN \
- ((uint32_t)0x6UL) /**< CLKCN_CLKSEL_HFXIN Value */
-#define MXC_S_GCR_CLKCN_CLKSEL_HFXIN \
- (MXC_V_GCR_CLKCN_CLKSEL_HFXIN \
- << MXC_F_GCR_CLKCN_CLKSEL_POS) /**< CLKCN_CLKSEL_HFXIN Setting */
-
-#define MXC_F_GCR_CLKCN_CKRDY_POS 13 /**< CLKCN_CKRDY Position */
-#define MXC_F_GCR_CLKCN_CKRDY \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_CLKCN_CKRDY_POS)) /**< CLKCN_CKRDY Mask */
-#define MXC_V_GCR_CLKCN_CKRDY_BUSY \
- ((uint32_t)0x0UL) /**< CLKCN_CKRDY_BUSY Value */
-#define MXC_S_GCR_CLKCN_CKRDY_BUSY \
- (MXC_V_GCR_CLKCN_CKRDY_BUSY \
- << MXC_F_GCR_CLKCN_CKRDY_POS) /**< CLKCN_CKRDY_BUSY Setting */
-#define MXC_V_GCR_CLKCN_CKRDY_READY \
- ((uint32_t)0x1UL) /**< CLKCN_CKRDY_READY Value */
-#define MXC_S_GCR_CLKCN_CKRDY_READY \
- (MXC_V_GCR_CLKCN_CKRDY_READY \
- << MXC_F_GCR_CLKCN_CKRDY_POS) /**< CLKCN_CKRDY_READY Setting */
-
-#define MXC_F_GCR_CLKCN_X32K_EN_POS 17 /**< CLKCN_X32K_EN Position */
-#define MXC_F_GCR_CLKCN_X32K_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_CLKCN_X32K_EN_POS)) /**< CLKCN_X32K_EN Mask */
-#define MXC_V_GCR_CLKCN_X32K_EN_DIS \
- ((uint32_t)0x0UL) /**< CLKCN_X32K_EN_DIS Value */
-#define MXC_S_GCR_CLKCN_X32K_EN_DIS \
- (MXC_V_GCR_CLKCN_X32K_EN_DIS \
- << MXC_F_GCR_CLKCN_X32K_EN_POS) /**< CLKCN_X32K_EN_DIS Setting */
-#define MXC_V_GCR_CLKCN_X32K_EN_EN \
- ((uint32_t)0x1UL) /**< CLKCN_X32K_EN_EN Value */
-#define MXC_S_GCR_CLKCN_X32K_EN_EN \
- (MXC_V_GCR_CLKCN_X32K_EN_EN \
- << MXC_F_GCR_CLKCN_X32K_EN_POS) /**< CLKCN_X32K_EN_EN Setting */
-
-#define MXC_F_GCR_CLKCN_HIRC_EN_POS 18 /**< CLKCN_HIRC_EN Position */
-#define MXC_F_GCR_CLKCN_HIRC_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_CLKCN_HIRC_EN_POS)) /**< CLKCN_HIRC_EN Mask */
-#define MXC_V_GCR_CLKCN_HIRC_EN_DIS \
- ((uint32_t)0x0UL) /**< CLKCN_HIRC_EN_DIS Value */
-#define MXC_S_GCR_CLKCN_HIRC_EN_DIS \
- (MXC_V_GCR_CLKCN_HIRC_EN_DIS \
- << MXC_F_GCR_CLKCN_HIRC_EN_POS) /**< CLKCN_HIRC_EN_DIS Setting */
-#define MXC_V_GCR_CLKCN_HIRC_EN_EN \
- ((uint32_t)0x1UL) /**< CLKCN_HIRC_EN_EN Value */
-#define MXC_S_GCR_CLKCN_HIRC_EN_EN \
- (MXC_V_GCR_CLKCN_HIRC_EN_EN \
- << MXC_F_GCR_CLKCN_HIRC_EN_POS) /**< CLKCN_HIRC_EN_EN Setting */
-
-#define MXC_F_GCR_CLKCN_X32K_RDY_POS 25 /**< CLKCN_X32K_RDY Position */
-#define MXC_F_GCR_CLKCN_X32K_RDY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_CLKCN_X32K_RDY_POS)) /**< CLKCN_X32K_RDY Mask */
-#define MXC_V_GCR_CLKCN_X32K_RDY_NOT \
- ((uint32_t)0x0UL) /**< CLKCN_X32K_RDY_NOT Value */
-#define MXC_S_GCR_CLKCN_X32K_RDY_NOT \
- (MXC_V_GCR_CLKCN_X32K_RDY_NOT \
- << MXC_F_GCR_CLKCN_X32K_RDY_POS) /**< CLKCN_X32K_RDY_NOT Setting */
-#define MXC_V_GCR_CLKCN_X32K_RDY_READY \
- ((uint32_t)0x1UL) /**< CLKCN_X32K_RDY_READY Value */
-#define MXC_S_GCR_CLKCN_X32K_RDY_READY \
- (MXC_V_GCR_CLKCN_X32K_RDY_READY \
- << MXC_F_GCR_CLKCN_X32K_RDY_POS) /**< CLKCN_X32K_RDY_READY Setting */
-
-#define MXC_F_GCR_CLKCN_HIRC_RDY_POS 26 /**< CLKCN_HIRC_RDY Position */
-#define MXC_F_GCR_CLKCN_HIRC_RDY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_CLKCN_HIRC_RDY_POS)) /**< CLKCN_HIRC_RDY Mask */
-#define MXC_V_GCR_CLKCN_HIRC_RDY_NOT \
- ((uint32_t)0x0UL) /**< CLKCN_HIRC_RDY_NOT Value */
-#define MXC_S_GCR_CLKCN_HIRC_RDY_NOT \
- (MXC_V_GCR_CLKCN_HIRC_RDY_NOT \
- << MXC_F_GCR_CLKCN_HIRC_RDY_POS) /**< CLKCN_HIRC_RDY_NOT Setting */
-#define MXC_V_GCR_CLKCN_HIRC_RDY_READY \
- ((uint32_t)0x1UL) /**< CLKCN_HIRC_RDY_READY Value */
-#define MXC_S_GCR_CLKCN_HIRC_RDY_READY \
- (MXC_V_GCR_CLKCN_HIRC_RDY_READY \
- << MXC_F_GCR_CLKCN_HIRC_RDY_POS) /**< CLKCN_HIRC_RDY_READY Setting */
-
-#define MXC_F_GCR_CLKCN_LIRC8K_RDY_POS 29 /**< CLKCN_LIRC8K_RDY Position */
-#define MXC_F_GCR_CLKCN_LIRC8K_RDY \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_CLKCN_LIRC8K_RDY_POS)) /**< CLKCN_LIRC8K_RDY \
- Mask */
-#define MXC_V_GCR_CLKCN_LIRC8K_RDY_NOT \
- ((uint32_t)0x0UL) /**< CLKCN_LIRC8K_RDY_NOT Value */
-#define MXC_S_GCR_CLKCN_LIRC8K_RDY_NOT \
- (MXC_V_GCR_CLKCN_LIRC8K_RDY_NOT \
- << MXC_F_GCR_CLKCN_LIRC8K_RDY_POS) /**< CLKCN_LIRC8K_RDY_NOT Setting \
- */
-#define MXC_V_GCR_CLKCN_LIRC8K_RDY_READY \
- ((uint32_t)0x1UL) /**< CLKCN_LIRC8K_RDY_READY Value */
-#define MXC_S_GCR_CLKCN_LIRC8K_RDY_READY \
- (MXC_V_GCR_CLKCN_LIRC8K_RDY_READY \
- << MXC_F_GCR_CLKCN_LIRC8K_RDY_POS) /**< CLKCN_LIRC8K_RDY_READY \
- Setting */
-
-/**
- * Power Management.
- */
-#define MXC_F_GCR_PM_MODE_POS 0 /**< PM_MODE Position */
-#define MXC_F_GCR_PM_MODE \
- ((uint32_t)(0x7UL << MXC_F_GCR_PM_MODE_POS)) /**< PM_MODE Mask */
-#define MXC_V_GCR_PM_MODE_ACTIVE \
- ((uint32_t)0x0UL) /**< PM_MODE_ACTIVE Value \
- */
-#define MXC_S_GCR_PM_MODE_ACTIVE \
- (MXC_V_GCR_PM_MODE_ACTIVE \
- << MXC_F_GCR_PM_MODE_POS) /**< PM_MODE_ACTIVE Setting */
-#define MXC_V_GCR_PM_MODE_SHUTDOWN \
- ((uint32_t)0x3UL) /**< PM_MODE_SHUTDOWN Value */
-#define MXC_S_GCR_PM_MODE_SHUTDOWN \
- (MXC_V_GCR_PM_MODE_SHUTDOWN \
- << MXC_F_GCR_PM_MODE_POS) /**< PM_MODE_SHUTDOWN Setting */
-#define MXC_V_GCR_PM_MODE_BACKUP \
- ((uint32_t)0x4UL) /**< PM_MODE_BACKUP Value \
- */
-#define MXC_S_GCR_PM_MODE_BACKUP \
- (MXC_V_GCR_PM_MODE_BACKUP \
- << MXC_F_GCR_PM_MODE_POS) /**< PM_MODE_BACKUP Setting */
-
-#define MXC_F_GCR_PM_GPIOWKEN_POS 4 /**< PM_GPIOWKEN Position */
-#define MXC_F_GCR_PM_GPIOWKEN \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_PM_GPIOWKEN_POS)) /**< PM_GPIOWKEN Mask */
-#define MXC_V_GCR_PM_GPIOWKEN_DIS \
- ((uint32_t)0x0UL) /**< PM_GPIOWKEN_DIS Value */
-#define MXC_S_GCR_PM_GPIOWKEN_DIS \
- (MXC_V_GCR_PM_GPIOWKEN_DIS \
- << MXC_F_GCR_PM_GPIOWKEN_POS) /**< PM_GPIOWKEN_DIS Setting */
-#define MXC_V_GCR_PM_GPIOWKEN_EN \
- ((uint32_t)0x1UL) /**< PM_GPIOWKEN_EN Value \
- */
-#define MXC_S_GCR_PM_GPIOWKEN_EN \
- (MXC_V_GCR_PM_GPIOWKEN_EN \
- << MXC_F_GCR_PM_GPIOWKEN_POS) /**< PM_GPIOWKEN_EN Setting */
-
-#define MXC_F_GCR_PM_RTCWKEN_POS 5 /**< PM_RTCWKEN Position */
-#define MXC_F_GCR_PM_RTCWKEN \
- ((uint32_t)(0x1UL << MXC_F_GCR_PM_RTCWKEN_POS)) /**< PM_RTCWKEN Mask \
- */
-#define MXC_V_GCR_PM_RTCWKEN_DIS \
- ((uint32_t)0x0UL) /**< PM_RTCWKEN_DIS Value \
- */
-#define MXC_S_GCR_PM_RTCWKEN_DIS \
- (MXC_V_GCR_PM_RTCWKEN_DIS \
- << MXC_F_GCR_PM_RTCWKEN_POS) /**< PM_RTCWKEN_DIS Setting */
-#define MXC_V_GCR_PM_RTCWKEN_EN ((uint32_t)0x1UL) /**< PM_RTCWKEN_EN Value */
-#define MXC_S_GCR_PM_RTCWKEN_EN \
- (MXC_V_GCR_PM_RTCWKEN_EN \
- << MXC_F_GCR_PM_RTCWKEN_POS) /**< PM_RTCWKEN_EN Setting */
-
-#define MXC_F_GCR_PM_HIRCPD_POS 15 /**< PM_HIRCPD Position */
-#define MXC_F_GCR_PM_HIRCPD \
- ((uint32_t)(0x1UL << MXC_F_GCR_PM_HIRCPD_POS)) /**< PM_HIRCPD Mask */
-#define MXC_V_GCR_PM_HIRCPD_ACTIVE \
- ((uint32_t)0x0UL) /**< PM_HIRCPD_ACTIVE Value */
-#define MXC_S_GCR_PM_HIRCPD_ACTIVE \
- (MXC_V_GCR_PM_HIRCPD_ACTIVE \
- << MXC_F_GCR_PM_HIRCPD_POS) /**< PM_HIRCPD_ACTIVE Setting */
-#define MXC_V_GCR_PM_HIRCPD_DEEPSLEEP \
- ((uint32_t)0x1UL) /**< PM_HIRCPD_DEEPSLEEP Value */
-#define MXC_S_GCR_PM_HIRCPD_DEEPSLEEP \
- (MXC_V_GCR_PM_HIRCPD_DEEPSLEEP \
- << MXC_F_GCR_PM_HIRCPD_POS) /**< PM_HIRCPD_DEEPSLEEP Setting */
-
-/**
- * Peripheral Clock Divider.
- */
-#define MXC_F_GCR_PCKDIV_AONCD_POS 0 /**< PCKDIV_AONCD Position */
-#define MXC_F_GCR_PCKDIV_AONCD \
- ((uint32_t)(0x3UL \
- << MXC_F_GCR_PCKDIV_AONCD_POS)) /**< PCKDIV_AONCD Mask */
-#define MXC_V_GCR_PCKDIV_AONCD_DIV_4 \
- ((uint32_t)0x0UL) /**< PCKDIV_AONCD_DIV_4 Value */
-#define MXC_S_GCR_PCKDIV_AONCD_DIV_4 \
- (MXC_V_GCR_PCKDIV_AONCD_DIV_4 \
- << MXC_F_GCR_PCKDIV_AONCD_POS) /**< PCKDIV_AONCD_DIV_4 Setting */
-#define MXC_V_GCR_PCKDIV_AONCD_DIV_8 \
- ((uint32_t)0x1UL) /**< PCKDIV_AONCD_DIV_8 Value */
-#define MXC_S_GCR_PCKDIV_AONCD_DIV_8 \
- (MXC_V_GCR_PCKDIV_AONCD_DIV_8 \
- << MXC_F_GCR_PCKDIV_AONCD_POS) /**< PCKDIV_AONCD_DIV_8 Setting */
-#define MXC_V_GCR_PCKDIV_AONCD_DIV_16 \
- ((uint32_t)0x2UL) /**< PCKDIV_AONCD_DIV_16 Value */
-#define MXC_S_GCR_PCKDIV_AONCD_DIV_16 \
- (MXC_V_GCR_PCKDIV_AONCD_DIV_16 \
- << MXC_F_GCR_PCKDIV_AONCD_POS) /**< PCKDIV_AONCD_DIV_16 Setting */
-#define MXC_V_GCR_PCKDIV_AONCD_DIV_32 \
- ((uint32_t)0x3UL) /**< PCKDIV_AONCD_DIV_32 Value */
-#define MXC_S_GCR_PCKDIV_AONCD_DIV_32 \
- (MXC_V_GCR_PCKDIV_AONCD_DIV_32 \
- << MXC_F_GCR_PCKDIV_AONCD_POS) /**< PCKDIV_AONCD_DIV_32 Setting */
-
-/**
- * Peripheral Clock Disable.
- */
-#define MXC_F_GCR_PERCKCN0_GPIO0D_POS 0 /**< PERCKCN0_GPIO0D Position */
-#define MXC_F_GCR_PERCKCN0_GPIO0D \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_PERCKCN0_GPIO0D_POS)) /**< PERCKCN0_GPIO0D \
- Mask */
-#define MXC_V_GCR_PERCKCN0_GPIO0D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_GPIO0D_EN Value */
-#define MXC_S_GCR_PERCKCN0_GPIO0D_EN \
- (MXC_V_GCR_PERCKCN0_GPIO0D_EN \
- << MXC_F_GCR_PERCKCN0_GPIO0D_POS) /**< PERCKCN0_GPIO0D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_GPIO0D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_GPIO0D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_GPIO0D_DIS \
- (MXC_V_GCR_PERCKCN0_GPIO0D_DIS \
- << MXC_F_GCR_PERCKCN0_GPIO0D_POS) /**< PERCKCN0_GPIO0D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_DMAD_POS 5 /**< PERCKCN0_DMAD Position */
-#define MXC_F_GCR_PERCKCN0_DMAD \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN0_DMAD_POS)) /**< PERCKCN0_DMAD Mask */
-#define MXC_V_GCR_PERCKCN0_DMAD_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_DMAD_EN Value */
-#define MXC_S_GCR_PERCKCN0_DMAD_EN \
- (MXC_V_GCR_PERCKCN0_DMAD_EN \
- << MXC_F_GCR_PERCKCN0_DMAD_POS) /**< PERCKCN0_DMAD_EN Setting */
-#define MXC_V_GCR_PERCKCN0_DMAD_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_DMAD_DIS Value */
-#define MXC_S_GCR_PERCKCN0_DMAD_DIS \
- (MXC_V_GCR_PERCKCN0_DMAD_DIS \
- << MXC_F_GCR_PERCKCN0_DMAD_POS) /**< PERCKCN0_DMAD_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_SPI0D_POS 6 /**< PERCKCN0_SPI0D Position */
-#define MXC_F_GCR_PERCKCN0_SPI0D \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN0_SPI0D_POS)) /**< PERCKCN0_SPI0D Mask */
-#define MXC_V_GCR_PERCKCN0_SPI0D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_SPI0D_EN Value */
-#define MXC_S_GCR_PERCKCN0_SPI0D_EN \
- (MXC_V_GCR_PERCKCN0_SPI0D_EN \
- << MXC_F_GCR_PERCKCN0_SPI0D_POS) /**< PERCKCN0_SPI0D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_SPI0D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_SPI0D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_SPI0D_DIS \
- (MXC_V_GCR_PERCKCN0_SPI0D_DIS \
- << MXC_F_GCR_PERCKCN0_SPI0D_POS) /**< PERCKCN0_SPI0D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_SPI1D_POS 7 /**< PERCKCN0_SPI1D Position */
-#define MXC_F_GCR_PERCKCN0_SPI1D \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN0_SPI1D_POS)) /**< PERCKCN0_SPI1D Mask */
-#define MXC_V_GCR_PERCKCN0_SPI1D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_SPI1D_EN Value */
-#define MXC_S_GCR_PERCKCN0_SPI1D_EN \
- (MXC_V_GCR_PERCKCN0_SPI1D_EN \
- << MXC_F_GCR_PERCKCN0_SPI1D_POS) /**< PERCKCN0_SPI1D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_SPI1D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_SPI1D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_SPI1D_DIS \
- (MXC_V_GCR_PERCKCN0_SPI1D_DIS \
- << MXC_F_GCR_PERCKCN0_SPI1D_POS) /**< PERCKCN0_SPI1D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_UART0D_POS 9 /**< PERCKCN0_UART0D Position */
-#define MXC_F_GCR_PERCKCN0_UART0D \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_PERCKCN0_UART0D_POS)) /**< PERCKCN0_UART0D \
- Mask */
-#define MXC_V_GCR_PERCKCN0_UART0D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_UART0D_EN Value */
-#define MXC_S_GCR_PERCKCN0_UART0D_EN \
- (MXC_V_GCR_PERCKCN0_UART0D_EN \
- << MXC_F_GCR_PERCKCN0_UART0D_POS) /**< PERCKCN0_UART0D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_UART0D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_UART0D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_UART0D_DIS \
- (MXC_V_GCR_PERCKCN0_UART0D_DIS \
- << MXC_F_GCR_PERCKCN0_UART0D_POS) /**< PERCKCN0_UART0D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_UART1D_POS 10 /**< PERCKCN0_UART1D Position */
-#define MXC_F_GCR_PERCKCN0_UART1D \
- ((uint32_t)( \
- 0x1UL << MXC_F_GCR_PERCKCN0_UART1D_POS)) /**< PERCKCN0_UART1D \
- Mask */
-#define MXC_V_GCR_PERCKCN0_UART1D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_UART1D_EN Value */
-#define MXC_S_GCR_PERCKCN0_UART1D_EN \
- (MXC_V_GCR_PERCKCN0_UART1D_EN \
- << MXC_F_GCR_PERCKCN0_UART1D_POS) /**< PERCKCN0_UART1D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_UART1D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_UART1D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_UART1D_DIS \
- (MXC_V_GCR_PERCKCN0_UART1D_DIS \
- << MXC_F_GCR_PERCKCN0_UART1D_POS) /**< PERCKCN0_UART1D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_I2C0D_POS 13 /**< PERCKCN0_I2C0D Position */
-#define MXC_F_GCR_PERCKCN0_I2C0D \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN0_I2C0D_POS)) /**< PERCKCN0_I2C0D Mask */
-#define MXC_V_GCR_PERCKCN0_I2C0D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_I2C0D_EN Value */
-#define MXC_S_GCR_PERCKCN0_I2C0D_EN \
- (MXC_V_GCR_PERCKCN0_I2C0D_EN \
- << MXC_F_GCR_PERCKCN0_I2C0D_POS) /**< PERCKCN0_I2C0D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_I2C0D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_I2C0D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_I2C0D_DIS \
- (MXC_V_GCR_PERCKCN0_I2C0D_DIS \
- << MXC_F_GCR_PERCKCN0_I2C0D_POS) /**< PERCKCN0_I2C0D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_T0D_POS 15 /**< PERCKCN0_T0D Position */
-#define MXC_F_GCR_PERCKCN0_T0D \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_PERCKCN0_T0D_POS)) /**< PERCKCN0_T0D Mask */
-#define MXC_V_GCR_PERCKCN0_T0D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_T0D_EN Value */
-#define MXC_S_GCR_PERCKCN0_T0D_EN \
- (MXC_V_GCR_PERCKCN0_T0D_EN \
- << MXC_F_GCR_PERCKCN0_T0D_POS) /**< PERCKCN0_T0D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_T0D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_T0D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_T0D_DIS \
- (MXC_V_GCR_PERCKCN0_T0D_DIS \
- << MXC_F_GCR_PERCKCN0_T0D_POS) /**< PERCKCN0_T0D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_T1D_POS 16 /**< PERCKCN0_T1D Position */
-#define MXC_F_GCR_PERCKCN0_T1D \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_PERCKCN0_T1D_POS)) /**< PERCKCN0_T1D Mask */
-#define MXC_V_GCR_PERCKCN0_T1D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_T1D_EN Value */
-#define MXC_S_GCR_PERCKCN0_T1D_EN \
- (MXC_V_GCR_PERCKCN0_T1D_EN \
- << MXC_F_GCR_PERCKCN0_T1D_POS) /**< PERCKCN0_T1D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_T1D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_T1D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_T1D_DIS \
- (MXC_V_GCR_PERCKCN0_T1D_DIS \
- << MXC_F_GCR_PERCKCN0_T1D_POS) /**< PERCKCN0_T1D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_T2D_POS 17 /**< PERCKCN0_T2D Position */
-#define MXC_F_GCR_PERCKCN0_T2D \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_PERCKCN0_T2D_POS)) /**< PERCKCN0_T2D Mask */
-#define MXC_V_GCR_PERCKCN0_T2D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_T2D_EN Value */
-#define MXC_S_GCR_PERCKCN0_T2D_EN \
- (MXC_V_GCR_PERCKCN0_T2D_EN \
- << MXC_F_GCR_PERCKCN0_T2D_POS) /**< PERCKCN0_T2D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_T2D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_T2D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_T2D_DIS \
- (MXC_V_GCR_PERCKCN0_T2D_DIS \
- << MXC_F_GCR_PERCKCN0_T2D_POS) /**< PERCKCN0_T2D_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN0_I2C1D_POS 28 /**< PERCKCN0_I2C1D Position */
-#define MXC_F_GCR_PERCKCN0_I2C1D \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN0_I2C1D_POS)) /**< PERCKCN0_I2C1D Mask */
-#define MXC_V_GCR_PERCKCN0_I2C1D_EN \
- ((uint32_t)0x0UL) /**< PERCKCN0_I2C1D_EN Value */
-#define MXC_S_GCR_PERCKCN0_I2C1D_EN \
- (MXC_V_GCR_PERCKCN0_I2C1D_EN \
- << MXC_F_GCR_PERCKCN0_I2C1D_POS) /**< PERCKCN0_I2C1D_EN Setting */
-#define MXC_V_GCR_PERCKCN0_I2C1D_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN0_I2C1D_DIS Value */
-#define MXC_S_GCR_PERCKCN0_I2C1D_DIS \
- (MXC_V_GCR_PERCKCN0_I2C1D_DIS \
- << MXC_F_GCR_PERCKCN0_I2C1D_POS) /**< PERCKCN0_I2C1D_DIS Setting */
-
-/**
- * Memory Clock Control Register.
- */
-#define MXC_F_GCR_MEMCKCN_FWS_POS 0 /**< MEMCKCN_FWS Position */
-#define MXC_F_GCR_MEMCKCN_FWS \
- ((uint32_t)( \
- 0x7UL << MXC_F_GCR_MEMCKCN_FWS_POS)) /**< MEMCKCN_FWS Mask */
-
-#define MXC_F_GCR_MEMCKCN_SYSRAM0LS_POS 8 /**< MEMCKCN_SYSRAM0LS Position */
-#define MXC_F_GCR_MEMCKCN_SYSRAM0LS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMCKCN_SYSRAM0LS_POS)) /**< MEMCKCN_SYSRAM0LS \
- Mask */
-#define MXC_V_GCR_MEMCKCN_SYSRAM0LS_ACTIVE \
- ((uint32_t)0x0UL) /**< MEMCKCN_SYSRAM0LS_ACTIVE Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM0LS_ACTIVE \
- (MXC_V_GCR_MEMCKCN_SYSRAM0LS_ACTIVE \
- << MXC_F_GCR_MEMCKCN_SYSRAM0LS_POS) /**< MEMCKCN_SYSRAM0LS_ACTIVE \
- Setting */
-#define MXC_V_GCR_MEMCKCN_SYSRAM0LS_LIGHT_SLEEP \
- ((uint32_t)0x1UL) /**< MEMCKCN_SYSRAM0LS_LIGHT_SLEEP Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM0LS_LIGHT_SLEEP \
- (MXC_V_GCR_MEMCKCN_SYSRAM0LS_LIGHT_SLEEP \
- << MXC_F_GCR_MEMCKCN_SYSRAM0LS_POS) /**< \
- MEMCKCN_SYSRAM0LS_LIGHT_SLEEP \
- Setting */
-
-#define MXC_F_GCR_MEMCKCN_SYSRAM1LS_POS 9 /**< MEMCKCN_SYSRAM1LS Position */
-#define MXC_F_GCR_MEMCKCN_SYSRAM1LS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMCKCN_SYSRAM1LS_POS)) /**< MEMCKCN_SYSRAM1LS \
- Mask */
-#define MXC_V_GCR_MEMCKCN_SYSRAM1LS_ACTIVE \
- ((uint32_t)0x0UL) /**< MEMCKCN_SYSRAM1LS_ACTIVE Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM1LS_ACTIVE \
- (MXC_V_GCR_MEMCKCN_SYSRAM1LS_ACTIVE \
- << MXC_F_GCR_MEMCKCN_SYSRAM1LS_POS) /**< MEMCKCN_SYSRAM1LS_ACTIVE \
- Setting */
-#define MXC_V_GCR_MEMCKCN_SYSRAM1LS_LIGHT_SLEEP \
- ((uint32_t)0x1UL) /**< MEMCKCN_SYSRAM1LS_LIGHT_SLEEP Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM1LS_LIGHT_SLEEP \
- (MXC_V_GCR_MEMCKCN_SYSRAM1LS_LIGHT_SLEEP \
- << MXC_F_GCR_MEMCKCN_SYSRAM1LS_POS) /**< \
- MEMCKCN_SYSRAM1LS_LIGHT_SLEEP \
- Setting */
-
-#define MXC_F_GCR_MEMCKCN_SYSRAM2LS_POS 10 /**< MEMCKCN_SYSRAM2LS Position */
-#define MXC_F_GCR_MEMCKCN_SYSRAM2LS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMCKCN_SYSRAM2LS_POS)) /**< MEMCKCN_SYSRAM2LS \
- Mask */
-#define MXC_V_GCR_MEMCKCN_SYSRAM2LS_ACTIVE \
- ((uint32_t)0x0UL) /**< MEMCKCN_SYSRAM2LS_ACTIVE Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM2LS_ACTIVE \
- (MXC_V_GCR_MEMCKCN_SYSRAM2LS_ACTIVE \
- << MXC_F_GCR_MEMCKCN_SYSRAM2LS_POS) /**< MEMCKCN_SYSRAM2LS_ACTIVE \
- Setting */
-#define MXC_V_GCR_MEMCKCN_SYSRAM2LS_LIGHT_SLEEP \
- ((uint32_t)0x1UL) /**< MEMCKCN_SYSRAM2LS_LIGHT_SLEEP Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM2LS_LIGHT_SLEEP \
- (MXC_V_GCR_MEMCKCN_SYSRAM2LS_LIGHT_SLEEP \
- << MXC_F_GCR_MEMCKCN_SYSRAM2LS_POS) /**< \
- MEMCKCN_SYSRAM2LS_LIGHT_SLEEP \
- Setting */
-
-#define MXC_F_GCR_MEMCKCN_SYSRAM3LS_POS 11 /**< MEMCKCN_SYSRAM3LS Position */
-#define MXC_F_GCR_MEMCKCN_SYSRAM3LS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMCKCN_SYSRAM3LS_POS)) /**< MEMCKCN_SYSRAM3LS \
- Mask */
-#define MXC_V_GCR_MEMCKCN_SYSRAM3LS_ACTIVE \
- ((uint32_t)0x0UL) /**< MEMCKCN_SYSRAM3LS_ACTIVE Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM3LS_ACTIVE \
- (MXC_V_GCR_MEMCKCN_SYSRAM3LS_ACTIVE \
- << MXC_F_GCR_MEMCKCN_SYSRAM3LS_POS) /**< MEMCKCN_SYSRAM3LS_ACTIVE \
- Setting */
-#define MXC_V_GCR_MEMCKCN_SYSRAM3LS_LIGHT_SLEEP \
- ((uint32_t)0x1UL) /**< MEMCKCN_SYSRAM3LS_LIGHT_SLEEP Value */
-#define MXC_S_GCR_MEMCKCN_SYSRAM3LS_LIGHT_SLEEP \
- (MXC_V_GCR_MEMCKCN_SYSRAM3LS_LIGHT_SLEEP \
- << MXC_F_GCR_MEMCKCN_SYSRAM3LS_POS) /**< \
- MEMCKCN_SYSRAM3LS_LIGHT_SLEEP \
- Setting */
-
-#define MXC_F_GCR_MEMCKCN_ICACHELS_POS 12 /**< MEMCKCN_ICACHELS Position */
-#define MXC_F_GCR_MEMCKCN_ICACHELS \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_MEMCKCN_ICACHELS_POS)) /**< MEMCKCN_ICACHELS \
- Mask */
-#define MXC_V_GCR_MEMCKCN_ICACHELS_ACTIVE \
- ((uint32_t)0x0UL) /**< MEMCKCN_ICACHELS_ACTIVE Value */
-#define MXC_S_GCR_MEMCKCN_ICACHELS_ACTIVE \
- (MXC_V_GCR_MEMCKCN_ICACHELS_ACTIVE \
- << MXC_F_GCR_MEMCKCN_ICACHELS_POS) /**< MEMCKCN_ICACHELS_ACTIVE \
- Setting */
-#define MXC_V_GCR_MEMCKCN_ICACHELS_LIGHT_SLEEP \
- ((uint32_t)0x1UL) /**< MEMCKCN_ICACHELS_LIGHT_SLEEP Value */
-#define MXC_S_GCR_MEMCKCN_ICACHELS_LIGHT_SLEEP \
- (MXC_V_GCR_MEMCKCN_ICACHELS_LIGHT_SLEEP \
- << MXC_F_GCR_MEMCKCN_ICACHELS_POS) /**< MEMCKCN_ICACHELS_LIGHT_SLEEP \
- Setting */
-
-/**
- * Memory Zeroize Control.
- */
-#define MXC_F_GCR_MEMZCN_SRAM0Z_POS 0 /**< MEMZCN_SRAM0Z Position */
-#define MXC_F_GCR_MEMZCN_SRAM0Z \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMZCN_SRAM0Z_POS)) /**< MEMZCN_SRAM0Z Mask */
-#define MXC_V_GCR_MEMZCN_SRAM0Z_NOP \
- ((uint32_t)0x0UL) /**< MEMZCN_SRAM0Z_NOP Value */
-#define MXC_S_GCR_MEMZCN_SRAM0Z_NOP \
- (MXC_V_GCR_MEMZCN_SRAM0Z_NOP \
- << MXC_F_GCR_MEMZCN_SRAM0Z_POS) /**< MEMZCN_SRAM0Z_NOP Setting */
-#define MXC_V_GCR_MEMZCN_SRAM0Z_START \
- ((uint32_t)0x1UL) /**< MEMZCN_SRAM0Z_START Value */
-#define MXC_S_GCR_MEMZCN_SRAM0Z_START \
- (MXC_V_GCR_MEMZCN_SRAM0Z_START \
- << MXC_F_GCR_MEMZCN_SRAM0Z_POS) /**< MEMZCN_SRAM0Z_START Setting */
-
-#define MXC_F_GCR_MEMZCN_ICACHEZ_POS 1 /**< MEMZCN_ICACHEZ Position */
-#define MXC_F_GCR_MEMZCN_ICACHEZ \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_MEMZCN_ICACHEZ_POS)) /**< MEMZCN_ICACHEZ Mask */
-#define MXC_V_GCR_MEMZCN_ICACHEZ_NOP \
- ((uint32_t)0x0UL) /**< MEMZCN_ICACHEZ_NOP Value */
-#define MXC_S_GCR_MEMZCN_ICACHEZ_NOP \
- (MXC_V_GCR_MEMZCN_ICACHEZ_NOP \
- << MXC_F_GCR_MEMZCN_ICACHEZ_POS) /**< MEMZCN_ICACHEZ_NOP Setting */
-#define MXC_V_GCR_MEMZCN_ICACHEZ_START \
- ((uint32_t)0x1UL) /**< MEMZCN_ICACHEZ_START Value */
-#define MXC_S_GCR_MEMZCN_ICACHEZ_START \
- (MXC_V_GCR_MEMZCN_ICACHEZ_START \
- << MXC_F_GCR_MEMZCN_ICACHEZ_POS) /**< MEMZCN_ICACHEZ_START Setting */
-
-/**
- * System Status Register.
- */
-#define MXC_F_GCR_SYSST_ICECLOCK_POS 0 /**< SYSST_ICECLOCK Position */
-#define MXC_F_GCR_SYSST_ICECLOCK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_SYSST_ICECLOCK_POS)) /**< SYSST_ICECLOCK Mask */
-#define MXC_V_GCR_SYSST_ICECLOCK_UNLOCKED \
- ((uint32_t)0x0UL) /**< SYSST_ICECLOCK_UNLOCKED Value */
-#define MXC_S_GCR_SYSST_ICECLOCK_UNLOCKED \
- (MXC_V_GCR_SYSST_ICECLOCK_UNLOCKED \
- << MXC_F_GCR_SYSST_ICECLOCK_POS) /**< SYSST_ICECLOCK_UNLOCKED Setting \
- */
-#define MXC_V_GCR_SYSST_ICECLOCK_LOCKED \
- ((uint32_t)0x1UL) /**< SYSST_ICECLOCK_LOCKED Value */
-#define MXC_S_GCR_SYSST_ICECLOCK_LOCKED \
- (MXC_V_GCR_SYSST_ICECLOCK_LOCKED \
- << MXC_F_GCR_SYSST_ICECLOCK_POS) /**< SYSST_ICECLOCK_LOCKED Setting \
- */
-
-#define MXC_F_GCR_SYSST_CODEINTERR_POS 1 /**< SYSST_CODEINTERR Position */
-#define MXC_F_GCR_SYSST_CODEINTERR \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_SYSST_CODEINTERR_POS)) /**< SYSST_CODEINTERR \
- Mask */
-#define MXC_V_GCR_SYSST_CODEINTERR_NORM \
- ((uint32_t)0x0UL) /**< SYSST_CODEINTERR_NORM Value */
-#define MXC_S_GCR_SYSST_CODEINTERR_NORM \
- (MXC_V_GCR_SYSST_CODEINTERR_NORM \
- << MXC_F_GCR_SYSST_CODEINTERR_POS) /**< SYSST_CODEINTERR_NORM Setting \
- */
-#define MXC_V_GCR_SYSST_CODEINTERR_CODE \
- ((uint32_t)0x1UL) /**< SYSST_CODEINTERR_CODE Value */
-#define MXC_S_GCR_SYSST_CODEINTERR_CODE \
- (MXC_V_GCR_SYSST_CODEINTERR_CODE \
- << MXC_F_GCR_SYSST_CODEINTERR_POS) /**< SYSST_CODEINTERR_CODE Setting \
- */
-
-#define MXC_F_GCR_SYSST_SCMEMF_POS 5 /**< SYSST_SCMEMF Position */
-#define MXC_F_GCR_SYSST_SCMEMF \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_SYSST_SCMEMF_POS)) /**< SYSST_SCMEMF Mask */
-#define MXC_V_GCR_SYSST_SCMEMF_NORM \
- ((uint32_t)0x0UL) /**< SYSST_SCMEMF_NORM Value */
-#define MXC_S_GCR_SYSST_SCMEMF_NORM \
- (MXC_V_GCR_SYSST_SCMEMF_NORM \
- << MXC_F_GCR_SYSST_SCMEMF_POS) /**< SYSST_SCMEMF_NORM Setting */
-#define MXC_V_GCR_SYSST_SCMEMF_MEMORY \
- ((uint32_t)0x1UL) /**< SYSST_SCMEMF_MEMORY Value */
-#define MXC_S_GCR_SYSST_SCMEMF_MEMORY \
- (MXC_V_GCR_SYSST_SCMEMF_MEMORY \
- << MXC_F_GCR_SYSST_SCMEMF_POS) /**< SYSST_SCMEMF_MEMORY Setting */
-
-/**
- * Reset Register.
- */
-#define MXC_F_GCR_RSTR1_I2C1_POS 0 /**< RSTR1_I2C1 Position */
-#define MXC_F_GCR_RSTR1_I2C1 \
- ((uint32_t)(0x1UL << MXC_F_GCR_RSTR1_I2C1_POS)) /**< RSTR1_I2C1 Mask \
- */
-#define MXC_V_GCR_RSTR1_I2C1_RESET \
- ((uint32_t)0x1UL) /**< RSTR1_I2C1_RESET Value */
-#define MXC_S_GCR_RSTR1_I2C1_RESET \
- (MXC_V_GCR_RSTR1_I2C1_RESET \
- << MXC_F_GCR_RSTR1_I2C1_POS) /**< RSTR1_I2C1_RESET Setting */
-#define MXC_V_GCR_RSTR1_I2C1_RESET_DONE \
- ((uint32_t)0x0UL) /**< RSTR1_I2C1_RESET_DONE Value */
-#define MXC_S_GCR_RSTR1_I2C1_RESET_DONE \
- (MXC_V_GCR_RSTR1_I2C1_RESET_DONE \
- << MXC_F_GCR_RSTR1_I2C1_POS) /**< RSTR1_I2C1_RESET_DONE Setting */
-#define MXC_V_GCR_RSTR1_I2C1_BUSY \
- ((uint32_t)0x1UL) /**< RSTR1_I2C1_BUSY Value */
-#define MXC_S_GCR_RSTR1_I2C1_BUSY \
- (MXC_V_GCR_RSTR1_I2C1_BUSY \
- << MXC_F_GCR_RSTR1_I2C1_POS) /**< RSTR1_I2C1_BUSY Setting */
-
-/**
- * Peripheral Clock Disable.
- */
-#define MXC_F_GCR_PERCKCN1_FLCD_POS 3 /**< PERCKCN1_FLCD Position */
-#define MXC_F_GCR_PERCKCN1_FLCD \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_PERCKCN1_FLCD_POS)) /**< PERCKCN1_FLCD Mask */
-#define MXC_V_GCR_PERCKCN1_FLCD_EN \
- ((uint32_t)0x0UL) /**< PERCKCN1_FLCD_EN Value */
-#define MXC_S_GCR_PERCKCN1_FLCD_EN \
- (MXC_V_GCR_PERCKCN1_FLCD_EN \
- << MXC_F_GCR_PERCKCN1_FLCD_POS) /**< PERCKCN1_FLCD_EN Setting */
-#define MXC_V_GCR_PERCKCN1_FLCD_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN1_FLCD_DIS Value */
-#define MXC_S_GCR_PERCKCN1_FLCD_DIS \
- (MXC_V_GCR_PERCKCN1_FLCD_DIS \
- << MXC_F_GCR_PERCKCN1_FLCD_POS) /**< PERCKCN1_FLCD_DIS Setting */
-
-#define MXC_F_GCR_PERCKCN1_ICACHED_POS 11 /**< PERCKCN1_ICACHED Position */
-#define MXC_F_GCR_PERCKCN1_ICACHED \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_PERCKCN1_ICACHED_POS)) /**< PERCKCN1_ICACHED \
- Mask */
-#define MXC_V_GCR_PERCKCN1_ICACHED_EN \
- ((uint32_t)0x0UL) /**< PERCKCN1_ICACHED_EN Value */
-#define MXC_S_GCR_PERCKCN1_ICACHED_EN \
- (MXC_V_GCR_PERCKCN1_ICACHED_EN \
- << MXC_F_GCR_PERCKCN1_ICACHED_POS) /**< PERCKCN1_ICACHED_EN Setting \
- */
-#define MXC_V_GCR_PERCKCN1_ICACHED_DIS \
- ((uint32_t)0x1UL) /**< PERCKCN1_ICACHED_DIS Value */
-#define MXC_S_GCR_PERCKCN1_ICACHED_DIS \
- (MXC_V_GCR_PERCKCN1_ICACHED_DIS \
- << MXC_F_GCR_PERCKCN1_ICACHED_POS) /**< PERCKCN1_ICACHED_DIS Setting \
- */
-
-/**
- * Event Enable Register.
- */
-#define MXC_F_GCR_EVTEN_DMAEVENT_POS 0 /**< EVTEN_DMAEVENT Position */
-#define MXC_F_GCR_EVTEN_DMAEVENT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_EVTEN_DMAEVENT_POS)) /**< EVTEN_DMAEVENT Mask */
-
-#define MXC_F_GCR_EVTEN_RXEVENT_POS 1 /**< EVTEN_RXEVENT Position */
-#define MXC_F_GCR_EVTEN_RXEVENT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_EVTEN_RXEVENT_POS)) /**< EVTEN_RXEVENT Mask */
-
-/**
- * Revision Register.
- */
-#define MXC_F_GCR_REVISION_REVISION_POS 0 /**< REVISION_REVISION Position */
-#define MXC_F_GCR_REVISION_REVISION \
- ((uint32_t)( \
- 0xFFFFUL \
- << MXC_F_GCR_REVISION_REVISION_POS)) /**< REVISION_REVISION \
- Mask */
-
-/**
- * System Status Interrupt Enable Register.
- */
-#define MXC_F_GCR_SYSSIE_ICEULIE_POS 0 /**< SYSSIE_ICEULIE Position */
-#define MXC_F_GCR_SYSSIE_ICEULIE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_SYSSIE_ICEULIE_POS)) /**< SYSSIE_ICEULIE Mask */
-#define MXC_V_GCR_SYSSIE_ICEULIE_DIS \
- ((uint32_t)0x0UL) /**< SYSSIE_ICEULIE_DIS Value */
-#define MXC_S_GCR_SYSSIE_ICEULIE_DIS \
- (MXC_V_GCR_SYSSIE_ICEULIE_DIS \
- << MXC_F_GCR_SYSSIE_ICEULIE_POS) /**< SYSSIE_ICEULIE_DIS Setting */
-#define MXC_V_GCR_SYSSIE_ICEULIE_EN \
- ((uint32_t)0x1UL) /**< SYSSIE_ICEULIE_EN Value */
-#define MXC_S_GCR_SYSSIE_ICEULIE_EN \
- (MXC_V_GCR_SYSSIE_ICEULIE_EN \
- << MXC_F_GCR_SYSSIE_ICEULIE_POS) /**< SYSSIE_ICEULIE_EN Setting */
-
-#define MXC_F_GCR_SYSSIE_CIEIE_POS 1 /**< SYSSIE_CIEIE Position */
-#define MXC_F_GCR_SYSSIE_CIEIE \
- ((uint32_t)(0x1UL \
- << MXC_F_GCR_SYSSIE_CIEIE_POS)) /**< SYSSIE_CIEIE Mask */
-#define MXC_V_GCR_SYSSIE_CIEIE_DIS \
- ((uint32_t)0x0UL) /**< SYSSIE_CIEIE_DIS Value */
-#define MXC_S_GCR_SYSSIE_CIEIE_DIS \
- (MXC_V_GCR_SYSSIE_CIEIE_DIS \
- << MXC_F_GCR_SYSSIE_CIEIE_POS) /**< SYSSIE_CIEIE_DIS Setting */
-#define MXC_V_GCR_SYSSIE_CIEIE_EN \
- ((uint32_t)0x1UL) /**< SYSSIE_CIEIE_EN Value */
-#define MXC_S_GCR_SYSSIE_CIEIE_EN \
- (MXC_V_GCR_SYSSIE_CIEIE_EN \
- << MXC_F_GCR_SYSSIE_CIEIE_POS) /**< SYSSIE_CIEIE_EN Setting */
-
-#define MXC_F_GCR_SYSSIE_SCMFIE_POS 5 /**< SYSSIE_SCMFIE Position */
-#define MXC_F_GCR_SYSSIE_SCMFIE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_GCR_SYSSIE_SCMFIE_POS)) /**< SYSSIE_SCMFIE Mask */
-#define MXC_V_GCR_SYSSIE_SCMFIE_DIS \
- ((uint32_t)0x0UL) /**< SYSSIE_SCMFIE_DIS Value */
-#define MXC_S_GCR_SYSSIE_SCMFIE_DIS \
- (MXC_V_GCR_SYSSIE_SCMFIE_DIS \
- << MXC_F_GCR_SYSSIE_SCMFIE_POS) /**< SYSSIE_SCMFIE_DIS Setting */
-#define MXC_V_GCR_SYSSIE_SCMFIE_EN \
- ((uint32_t)0x1UL) /**< SYSSIE_SCMFIE_EN Value */
-#define MXC_S_GCR_SYSSIE_SCMFIE_EN \
- (MXC_V_GCR_SYSSIE_SCMFIE_EN \
- << MXC_F_GCR_SYSSIE_SCMFIE_POS) /**< SYSSIE_SCMFIE_EN Setting */
-
-#endif /* _GCR_REGS_H_ */
diff --git a/chip/max32660/gpio_chip.c b/chip/max32660/gpio_chip.c
deleted file mode 100644
index 5fe38cd657..0000000000
--- a/chip/max32660/gpio_chip.c
+++ /dev/null
@@ -1,241 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 GPIO module for Chrome EC */
-
-#include "clock.h"
-#include "console.h"
-#include "common.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "switch.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-#include "registers.h"
-#include "gpio_regs.h"
-
-#define CPRINTF(format, args...) cprintf(CC_GPIO, format, ##args)
-#define CPRINTS(format, args...) cprints(CC_GPIO, format, ##args)
-
-/* 0-terminated list of GPIO base addresses */
-static mxc_gpio_regs_t *gpio_bases[] = {MXC_GPIO0, 0};
-
-void gpio_set_alternate_function(uint32_t port, uint32_t mask,
- enum gpio_alternate_func func)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(port);
-
- switch (func) {
- case GPIO_ALT_FUNC_1:
- gpio->en_clr = mask;
- gpio->en1_clr = mask;
- break;
- case GPIO_ALT_FUNC_2:
- gpio->en_clr = mask;
- gpio->en1_set = mask;
- break;
- case GPIO_ALT_FUNC_3:
- gpio->en_set = mask;
- gpio->en1_set = mask;
- break;
- default:
- /* Default as input */
- gpio->out_en_clr = mask;
- gpio->en_set = mask;
- gpio->en1_clr = mask;
- break;
- }
-}
-
-test_mockable int gpio_get_level(enum gpio_signal signal)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpio_list[signal].port);
-
- return (gpio->in & gpio_list[signal].mask);
-}
-
-void gpio_set_level(enum gpio_signal signal, int value)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpio_list[signal].port);
-
- if (value) {
- gpio->out_set = gpio_list[signal].mask;
- } else {
- gpio->out_clr = gpio_list[signal].mask;
- }
-}
-
-void gpio_set_flags_by_mask(uint32_t port, uint32_t mask, uint32_t flags)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(port);
-
- /* Setup for either an output or input. */
- if (flags & GPIO_OUTPUT) {
- gpio->out_en_set = mask;
- gpio->en_set = mask;
- gpio->en1_clr = mask;
- } else {
- gpio->out_en_clr = mask;
- gpio->en_set = mask;
- gpio->en1_clr = mask;
- }
-
- /* Handle pull up, pull down or neither. */
- if (flags & GPIO_PULL_UP) {
- gpio->pad_cfg1 |= mask;
- gpio->pad_cfg2 &= ~mask;
- gpio->ps |= mask;
- } else if (flags & GPIO_PULL_DOWN) {
- gpio->pad_cfg1 &= ~mask;
- gpio->pad_cfg2 |= mask;
- gpio->ps &= ~mask;
- } else {
- /* No pull up/down */
- gpio->pad_cfg1 &= ~mask;
- gpio->pad_cfg2 &= ~mask;
- gpio->ps &= ~mask;
- }
-
- /* Handle setting up level interrupts. */
- if (flags & GPIO_INT_F_HIGH) {
- /* Level triggered mode. */
- gpio->int_mod &= ~mask;
- /* Level high generates interrupt. */
- gpio->int_pol |= mask;
- } else if (flags & GPIO_INT_F_LOW) {
- /* Level triggered mode. */
- gpio->int_mod &= ~mask;
- /* Level low generates interrupt. */
- gpio->int_pol &= ~mask;
- }
-
- /* Handle setting up edge interrupts. */
- if (flags & GPIO_INT_F_RISING) {
- /* Edge triggered mode. */
- gpio->int_mod |= mask;
- /* Rising edge generates interrupt. */
- gpio->int_pol |= mask;
- } else if (flags & GPIO_INT_F_FALLING) {
- /* Edge triggered mode. */
- gpio->int_mod |= mask;
- /* Falling edge generates interrupt. */
- gpio->int_pol &= ~mask;
- }
-
- /* Handle interrupting on both edges. */
- if ((flags & GPIO_INT_F_RISING) && (flags & GPIO_INT_F_FALLING)) {
- /* Dual edge triggered mode. */
- gpio->int_dual_edge |= mask;
- } else {
- /* Not dual edge triggered mode. */
- gpio->int_dual_edge &= ~mask;
- }
-
- /* Set the gpio pin high or low. */
- if (flags & GPIO_HIGH) {
- gpio->out_set = mask;
- } else if (flags & GPIO_LOW) {
- gpio->out_clr = mask;
- }
-}
-
-int gpio_enable_interrupt(enum gpio_signal signal)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpio_list[signal].port);
-
- gpio->int_en_set = gpio_list[signal].mask;
- return EC_SUCCESS;
-}
-
-int gpio_disable_interrupt(enum gpio_signal signal)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpio_list[signal].port);
-
- gpio->int_en_clr = gpio_list[signal].mask;
- return EC_SUCCESS;
-}
-
-int gpio_clear_pending_interrupt(enum gpio_signal signal)
-{
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpio_list[signal].port);
-
- gpio->int_clr = gpio_list[signal].mask;
- return EC_SUCCESS;
-}
-
-void gpio_pre_init(void)
-{
- const struct gpio_info *g = gpio_list;
- int i;
-
- /* Mask all GPIO interrupts */
- for (i = 0; gpio_bases[i]; i++)
- gpio_bases[i]->int_en = 0;
-
- /* Set all GPIOs to defaults */
- for (i = 0; i < GPIO_COUNT; i++, g++) {
- int flags = g->flags;
-
- if (flags & GPIO_DEFAULT)
- continue;
-
- /* Use as GPIO, not alternate function */
- gpio_set_alternate_function(g->port, g->mask,
- GPIO_ALT_FUNC_NONE);
-
- /* Set up GPIO based on flags */
- gpio_set_flags_by_mask(g->port, g->mask, flags);
- }
-}
-
-static void gpio_init(void)
-{
- /*
- * Enable global GPIO0 Port interrupt. Note that interrupts still need to be
- * enabled at the per pin level.
- */
- task_enable_irq(EC_GPIO0_IRQn);
-}
-DECLARE_HOOK(HOOK_INIT, gpio_init, HOOK_PRIO_DEFAULT);
-
-/*****************************************************************************/
-/* Interrupt handlers */
-
-/**
- * Handle a GPIO interrupt.
- *
- * port GPIO port
- * mis Masked interrupt status value for that port
- */
-static void gpio_interrupt(int port, uint32_t mis)
-{
- int i = 0;
- const struct gpio_info *g = gpio_list;
-
- for (i = 0; i < GPIO_IH_COUNT && mis; i++, g++) {
- if (port == g->port && (mis & g->mask)) {
- gpio_irq_handlers[i](i);
- mis &= ~g->mask;
- }
- }
-}
-
-/**
- * Handlers for each GPIO port. Read the interrupt status, call the common GPIO
- * interrupt handler and clear the GPIO hardware interrupt status.
- */
-#define GPIO_IRQ_FUNC(irqfunc, gpiobase) \
- void irqfunc(void) \
- { \
- mxc_gpio_regs_t *gpio = MXC_GPIO_GET_GPIO(gpiobase); \
- uint32_t mis = gpio->int_stat; \
- gpio_interrupt(gpiobase, mis); \
- gpio->int_clr = mis; \
- }
-
-GPIO_IRQ_FUNC(__gpio_0_interrupt, PORT_0);
-#undef GPIO_IRQ_FUNC
-DECLARE_IRQ(EC_GPIO0_IRQn, __gpio_0_interrupt, 1);
diff --git a/chip/max32660/gpio_regs.h b/chip/max32660/gpio_regs.h
deleted file mode 100644
index 1c6fcf7a71..0000000000
--- a/chip/max32660/gpio_regs.h
+++ /dev/null
@@ -1,866 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the GPIO Peripheral
- * Module */
-
-#ifndef _GPIO_REGS_H_
-#define _GPIO_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/* **** Definitions **** */
-
-/**
- * gpio
- * Individual I/O for each GPIO
- */
-
-/**
- * gpio_registers
- * Structure type to access the GPIO Registers.
- */
-typedef struct {
- __IO uint32_t en; /**< <tt>\b 0x00:<\tt> GPIO EN Register */
- __IO uint32_t en_set; /**< <tt>\b 0x04:<\tt> GPIO EN_SET Register */
- __IO uint32_t en_clr; /**< <tt>\b 0x08:<\tt> GPIO EN_CLR Register */
- __IO uint32_t out_en; /**< <tt>\b 0x0C:<\tt> GPIO OUT_EN Register */
- __IO uint32_t
- out_en_set; /**< <tt>\b 0x10:<\tt> GPIO OUT_EN_SET Register */
- __IO uint32_t
- out_en_clr; /**< <tt>\b 0x14:<\tt> GPIO OUT_EN_CLR Register */
- __IO uint32_t out; /**< <tt>\b 0x18:<\tt> GPIO OUT Register */
- __O uint32_t out_set; /**< <tt>\b 0x1C:<\tt> GPIO OUT_SET Register */
- __O uint32_t out_clr; /**< <tt>\b 0x20:<\tt> GPIO OUT_CLR Register */
- __I uint32_t in; /**< <tt>\b 0x24:<\tt> GPIO IN Register */
- __IO uint32_t int_mod; /**< <tt>\b 0x28:<\tt> GPIO INT_MOD Register */
- __IO uint32_t int_pol; /**< <tt>\b 0x2C:<\tt> GPIO INT_POL Register */
- __R uint32_t rsv_0x30;
- __IO uint32_t int_en; /**< <tt>\b 0x34:<\tt> GPIO INT_EN Register */
- __IO uint32_t
- int_en_set; /**< <tt>\b 0x38:<\tt> GPIO INT_EN_SET Register */
- __IO uint32_t
- int_en_clr; /**< <tt>\b 0x3C:<\tt> GPIO INT_EN_CLR Register */
- __I uint32_t int_stat; /**< <tt>\b 0x40:<\tt> GPIO INT_STAT Register */
- __R uint32_t rsv_0x44;
- __IO uint32_t int_clr; /**< <tt>\b 0x48:<\tt> GPIO INT_CLR Register */
- __IO uint32_t wake_en; /**< <tt>\b 0x4C:<\tt> GPIO WAKE_EN Register */
- __IO uint32_t
- wake_en_set; /**< <tt>\b 0x50:<\tt> GPIO WAKE_EN_SET Register */
- __IO uint32_t
- wake_en_clr; /**< <tt>\b 0x54:<\tt> GPIO WAKE_EN_CLR Register */
- __R uint32_t rsv_0x58;
- __IO uint32_t int_dual_edge; /**< <tt>\b 0x5C:<\tt> GPIO INT_DUAL_EDGE
- Register */
- __IO uint32_t pad_cfg1; /**< <tt>\b 0x60:<\tt> GPIO PAD_CFG1 Register */
- __IO uint32_t pad_cfg2; /**< <tt>\b 0x64:<\tt> GPIO PAD_CFG2 Register */
- __IO uint32_t en1; /**< <tt>\b 0x68:<\tt> GPIO EN1 Register */
- __IO uint32_t en1_set; /**< <tt>\b 0x6C:<\tt> GPIO EN1_SET Register */
- __IO uint32_t en1_clr; /**< <tt>\b 0x70:<\tt> GPIO EN1_CLR Register */
- __IO uint32_t en2; /**< <tt>\b 0x74:<\tt> GPIO EN2 Register */
- __IO uint32_t en2_set; /**< <tt>\b 0x78:<\tt> GPIO EN2_SET Register */
- __IO uint32_t en2_clr; /**< <tt>\b 0x7C:<\tt> GPIO EN2_CLR Register */
- __R uint32_t rsv_0x80_0xa7[10];
- __IO uint32_t is; /**< <tt>\b 0xA8:<\tt> GPIO IS Register */
- __IO uint32_t sr; /**< <tt>\b 0xAC:<\tt> GPIO SR Register */
- __IO uint32_t ds; /**< <tt>\b 0xB0:<\tt> GPIO DS Register */
- __IO uint32_t ds1; /**< <tt>\b 0xB4:<\tt> GPIO DS1 Register */
- __IO uint32_t ps; /**< <tt>\b 0xB8:<\tt> GPIO PS Register */
- __R uint32_t rsv_0xbc;
- __IO uint32_t vssel; /**< <tt>\b 0xC0:<\tt> GPIO VSSEL Register */
-} mxc_gpio_regs_t;
-
-#define PIN_0 ((uint32_t)(1UL << 0)) /**< Pin 0 Define */
-#define PIN_1 ((uint32_t)(1UL << 1)) /**< Pin 1 Define */
-#define PIN_2 ((uint32_t)(1UL << 2)) /**< Pin 2 Define */
-#define PIN_3 ((uint32_t)(1UL << 3)) /**< Pin 3 Define */
-#define PIN_4 ((uint32_t)(1UL << 4)) /**< Pin 4 Define */
-#define PIN_5 ((uint32_t)(1UL << 5)) /**< Pin 5 Define */
-#define PIN_6 ((uint32_t)(1UL << 6)) /**< Pin 6 Define */
-#define PIN_7 ((uint32_t)(1UL << 7)) /**< Pin 7 Define */
-#define PIN_8 ((uint32_t)(1UL << 8)) /**< Pin 8 Define */
-#define PIN_9 ((uint32_t)(1UL << 9)) /**< Pin 9 Define */
-#define PIN_10 ((uint32_t)(1UL << 10)) /**< Pin 10 Define */
-#define PIN_11 ((uint32_t)(1UL << 11)) /**< Pin 11 Define */
-#define PIN_12 ((uint32_t)(1UL << 12)) /**< Pin 12 Define */
-#define PIN_13 ((uint32_t)(1UL << 13)) /**< Pin 13 Define */
-#define PIN_14 ((uint32_t)(1UL << 14)) /**< Pin 14 Define */
-#define PIN_15 ((uint32_t)(1UL << 15)) /**< Pin 15 Define */
-#define PIN_16 ((uint32_t)(1UL << 16)) /**< Pin 16 Define */
-#define PIN_17 ((uint32_t)(1UL << 17)) /**< Pin 17 Define */
-#define PIN_18 ((uint32_t)(1UL << 18)) /**< Pin 18 Define */
-#define PIN_19 ((uint32_t)(1UL << 19)) /**< Pin 19 Define */
-#define PIN_20 ((uint32_t)(1UL << 20)) /**< Pin 20 Define */
-#define PIN_21 ((uint32_t)(1UL << 21)) /**< Pin 21 Define */
-#define PIN_22 ((uint32_t)(1UL << 22)) /**< Pin 22 Define */
-#define PIN_23 ((uint32_t)(1UL << 23)) /**< Pin 23 Define */
-#define PIN_24 ((uint32_t)(1UL << 24)) /**< Pin 24 Define */
-#define PIN_25 ((uint32_t)(1UL << 25)) /**< Pin 25 Define */
-#define PIN_26 ((uint32_t)(1UL << 26)) /**< Pin 26 Define */
-#define PIN_27 ((uint32_t)(1UL << 27)) /**< Pin 27 Define */
-#define PIN_28 ((uint32_t)(1UL << 28)) /**< Pin 28 Define */
-#define PIN_29 ((uint32_t)(1UL << 29)) /**< Pin 29 Define */
-#define PIN_30 ((uint32_t)(1UL << 30)) /**< Pin 30 Define */
-#define PIN_31 ((uint32_t)(1UL << 31)) /**< Pin 31 Define */
-
-/**
- * Enumeration type for the GPIO Function Type
- */
-typedef enum {
- GPIO_FUNC_IN, /**< GPIO Input */
- GPIO_FUNC_OUT, /**< GPIO Output */
- GPIO_FUNC_ALT1, /**< Alternate Function Selection */
- GPIO_FUNC_ALT2, /**< Alternate Function Selection */
- GPIO_FUNC_ALT3, /**< Alternate Function Selection */
- GPIO_FUNC_ALT4, /**< Alternate Function Selection */
-} gpio_func_t;
-
-/**
- * Enumeration type for the type of GPIO pad on a given pin.
- */
-typedef enum {
- GPIO_PAD_NONE, /**< No pull-up or pull-down */
- GPIO_PAD_PULL_UP, /**< Set pad to weak pull-up */
- GPIO_PAD_PULL_DOWN, /**< Set pad to weak pull-down */
-} gpio_pad_t;
-
-/**
- * Structure type for configuring a GPIO port.
- */
-typedef struct {
- uint32_t port; /**< Index of GPIO port */
- uint32_t mask; /**< Pin mask (multiple pins may be set) */
- gpio_func_t func; /**< Function type */
- gpio_pad_t pad; /**< Pad type */
-} gpio_cfg_t;
-
-typedef enum { GPIO_INTERRUPT_LEVEL, GPIO_INTERRUPT_EDGE } gpio_int_mode_t;
-
-typedef enum {
- GPIO_INTERRUPT_FALLING = 0, /**< Interrupt triggers on falling edge */
- GPIO_INTERRUPT_HIGH = GPIO_INTERRUPT_FALLING, /**< Interrupt triggers
- when level is high */
- GPIO_INTERRUPT_RISING, /**< Interrupt triggers on rising edge */
- GPIO_INTERRUPT_LOW = GPIO_INTERRUPT_RISING, /**< Interrupt triggers when
- level is low */
- GPIO_INTERRUPT_BOTH /**< Interrupt triggers on either edge */
-} gpio_int_pol_t;
-
-/* Register offsets for module GPIO */
-#define MXC_R_GPIO_EN \
- ((uint32_t)0x00000000UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_GPIO_EN_SET \
- ((uint32_t)0x00000004UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_GPIO_EN_CLR \
- ((uint32_t)0x00000008UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x008 */
-#define MXC_R_GPIO_OUT_EN \
- ((uint32_t)0x0000000CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x00C */
-#define MXC_R_GPIO_OUT_EN_SET \
- ((uint32_t)0x00000010UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x010 */
-#define MXC_R_GPIO_OUT_EN_CLR \
- ((uint32_t)0x00000014UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x014 */
-#define MXC_R_GPIO_OUT \
- ((uint32_t)0x00000018UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x018 */
-#define MXC_R_GPIO_OUT_SET \
- ((uint32_t)0x0000001CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x01C */
-#define MXC_R_GPIO_OUT_CLR \
- ((uint32_t)0x00000020UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x020 */
-#define MXC_R_GPIO_IN \
- ((uint32_t)0x00000024UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x024 */
-#define MXC_R_GPIO_INT_MOD \
- ((uint32_t)0x00000028UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x028 */
-#define MXC_R_GPIO_INT_POL \
- ((uint32_t)0x0000002CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x02C */
-#define MXC_R_GPIO_INT_EN \
- ((uint32_t)0x00000034UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x034 */
-#define MXC_R_GPIO_INT_EN_SET \
- ((uint32_t)0x00000038UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x038 */
-#define MXC_R_GPIO_INT_EN_CLR \
- ((uint32_t)0x0000003CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x03C */
-#define MXC_R_GPIO_INT_STAT \
- ((uint32_t)0x00000040UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x040 */
-#define MXC_R_GPIO_INT_CLR \
- ((uint32_t)0x00000048UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x048 */
-#define MXC_R_GPIO_WAKE_EN \
- ((uint32_t)0x0000004CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x04C */
-#define MXC_R_GPIO_WAKE_EN_SET \
- ((uint32_t)0x00000050UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x050 */
-#define MXC_R_GPIO_WAKE_EN_CLR \
- ((uint32_t)0x00000054UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x054 */
-#define MXC_R_GPIO_INT_DUAL_EDGE \
- ((uint32_t)0x0000005CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x05C */
-#define MXC_R_GPIO_PAD_CFG1 \
- ((uint32_t)0x00000060UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x060 */
-#define MXC_R_GPIO_PAD_CFG2 \
- ((uint32_t)0x00000064UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x064 */
-#define MXC_R_GPIO_EN1 \
- ((uint32_t)0x00000068UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x068 */
-#define MXC_R_GPIO_EN1_SET \
- ((uint32_t)0x0000006CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x06C */
-#define MXC_R_GPIO_EN1_CLR \
- ((uint32_t)0x00000070UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x070 */
-#define MXC_R_GPIO_EN2 \
- ((uint32_t)0x00000074UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x074 */
-#define MXC_R_GPIO_EN2_SET \
- ((uint32_t)0x00000078UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x078 */
-#define MXC_R_GPIO_EN2_CLR \
- ((uint32_t)0x0000007CUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x07C */
-#define MXC_R_GPIO_IS \
- ((uint32_t)0x000000A8UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0A8 */
-#define MXC_R_GPIO_SR \
- ((uint32_t)0x000000ACUL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0AC */
-#define MXC_R_GPIO_DS \
- ((uint32_t)0x000000B0UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0B0 */
-#define MXC_R_GPIO_DS1 \
- ((uint32_t)0x000000B4UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0B4 */
-#define MXC_R_GPIO_PS \
- ((uint32_t)0x000000B8UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0B8 */
-#define MXC_R_GPIO_VSSEL \
- ((uint32_t)0x000000C0UL) /**< Offset from GPIO Base Address: <tt> \
- 0x0x0C0 */
-
-/**
- * GPIO Function Enable Register. Each bit controls the GPIO_EN
- * setting for one GPIO pin on the associated port.
- */
-#define MXC_F_GPIO_EN_GPIO_EN_POS 0 /**< EN_GPIO_EN Position */
-#define MXC_F_GPIO_EN_GPIO_EN \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN_GPIO_EN_POS)) /**< EN_GPIO_EN Mask */
-#define MXC_V_GPIO_EN_GPIO_EN_ALTERNATE \
- ((uint32_t)0x0UL) /**< EN_GPIO_EN_ALTERNATE Value */
-#define MXC_S_GPIO_EN_GPIO_EN_ALTERNATE \
- (MXC_V_GPIO_EN_GPIO_EN_ALTERNATE \
- << MXC_F_GPIO_EN_GPIO_EN_POS) /**< EN_GPIO_EN_ALTERNATE Setting */
-#define MXC_V_GPIO_EN_GPIO_EN_GPIO \
- ((uint32_t)0x1UL) /**< EN_GPIO_EN_GPIO Value */
-#define MXC_S_GPIO_EN_GPIO_EN_GPIO \
- (MXC_V_GPIO_EN_GPIO_EN_GPIO \
- << MXC_F_GPIO_EN_GPIO_EN_POS) /**< EN_GPIO_EN_GPIO Setting */
-
-/**
- * GPIO Set Function Enable Register. Writing a 1 to one or more bits
- * in this register sets the bits in the same positions in GPIO_EN to 1, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN_SET_ALL_POS 0 /**< EN_SET_ALL Position */
-#define MXC_F_GPIO_EN_SET_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN_SET_ALL_POS)) /**< EN_SET_ALL Mask */
-
-/**
- * GPIO Clear Function Enable Register. Writing a 1 to one or more
- * bits in this register clears the bits in the same positions in GPIO_EN to 0,
- * without affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN_CLR_ALL_POS 0 /**< EN_CLR_ALL Position */
-#define MXC_F_GPIO_EN_CLR_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN_CLR_ALL_POS)) /**< EN_CLR_ALL Mask */
-
-/**
- * GPIO Output Enable Register. Each bit controls the GPIO_OUT_EN
- * setting for one GPIO pin in the associated port.
- */
-#define MXC_F_GPIO_OUT_EN_GPIO_OUT_EN_POS \
- 0 /**< OUT_EN_GPIO_OUT_EN Position \
- */
-#define MXC_F_GPIO_OUT_EN_GPIO_OUT_EN \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_EN_GPIO_OUT_EN_POS)) /**< OUT_EN_GPIO_OUT_EN \
- Mask */
-#define MXC_V_GPIO_OUT_EN_GPIO_OUT_EN_DIS \
- ((uint32_t)0x0UL) /**< OUT_EN_GPIO_OUT_EN_DIS Value */
-#define MXC_S_GPIO_OUT_EN_GPIO_OUT_EN_DIS \
- (MXC_V_GPIO_OUT_EN_GPIO_OUT_EN_DIS \
- << MXC_F_GPIO_OUT_EN_GPIO_OUT_EN_POS) /**< OUT_EN_GPIO_OUT_EN_DIS \
- Setting */
-#define MXC_V_GPIO_OUT_EN_GPIO_OUT_EN_EN \
- ((uint32_t)0x1UL) /**< OUT_EN_GPIO_OUT_EN_EN Value */
-#define MXC_S_GPIO_OUT_EN_GPIO_OUT_EN_EN \
- (MXC_V_GPIO_OUT_EN_GPIO_OUT_EN_EN \
- << MXC_F_GPIO_OUT_EN_GPIO_OUT_EN_POS) /**< OUT_EN_GPIO_OUT_EN_EN \
- Setting */
-
-/**
- * GPIO Output Enable Set Function Enable Register. Writing a 1 to one
- * or more bits in this register sets the bits in the same positions in
- * GPIO_OUT_EN to 1, without affecting other bits in that register.
- */
-#define MXC_F_GPIO_OUT_EN_SET_ALL_POS 0 /**< OUT_EN_SET_ALL Position */
-#define MXC_F_GPIO_OUT_EN_SET_ALL \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_EN_SET_ALL_POS)) /**< OUT_EN_SET_ALL Mask */
-
-/**
- * GPIO Output Enable Clear Function Enable Register. Writing a 1 to
- * one or more bits in this register clears the bits in the same positions in
- * GPIO_OUT_EN to 0, without affecting other bits in that register.
- */
-#define MXC_F_GPIO_OUT_EN_CLR_ALL_POS 0 /**< OUT_EN_CLR_ALL Position */
-#define MXC_F_GPIO_OUT_EN_CLR_ALL \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_EN_CLR_ALL_POS)) /**< OUT_EN_CLR_ALL Mask */
-
-/**
- * GPIO Output Register. Each bit controls the GPIO_OUT setting for
- * one pin in the associated port. This register can be written either
- * directly, or by using the GPIO_OUT_SET and GPIO_OUT_CLR registers.
- */
-#define MXC_F_GPIO_OUT_GPIO_OUT_POS 0 /**< OUT_GPIO_OUT Position */
-#define MXC_F_GPIO_OUT_GPIO_OUT \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_GPIO_OUT_POS)) /**< OUT_GPIO_OUT Mask */
-#define MXC_V_GPIO_OUT_GPIO_OUT_LOW \
- ((uint32_t)0x0UL) /**< OUT_GPIO_OUT_LOW Value */
-#define MXC_S_GPIO_OUT_GPIO_OUT_LOW \
- (MXC_V_GPIO_OUT_GPIO_OUT_LOW \
- << MXC_F_GPIO_OUT_GPIO_OUT_POS) /**< OUT_GPIO_OUT_LOW Setting */
-#define MXC_V_GPIO_OUT_GPIO_OUT_HIGH \
- ((uint32_t)0x1UL) /**< OUT_GPIO_OUT_HIGH Value */
-#define MXC_S_GPIO_OUT_GPIO_OUT_HIGH \
- (MXC_V_GPIO_OUT_GPIO_OUT_HIGH \
- << MXC_F_GPIO_OUT_GPIO_OUT_POS) /**< OUT_GPIO_OUT_HIGH Setting */
-
-/**
- * GPIO Output Set. Writing a 1 to one or more bits in this register
- * sets the bits in the same positions in GPIO_OUT to 1, without affecting other
- * bits in that register.
- */
-#define MXC_F_GPIO_OUT_SET_GPIO_OUT_SET_POS \
- 0 /**< OUT_SET_GPIO_OUT_SET Position */
-#define MXC_F_GPIO_OUT_SET_GPIO_OUT_SET \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_SET_GPIO_OUT_SET_POS)) /**< \
- OUT_SET_GPIO_OUT_SET \
- Mask */
-#define MXC_V_GPIO_OUT_SET_GPIO_OUT_SET_NO \
- ((uint32_t)0x0UL) /**< OUT_SET_GPIO_OUT_SET_NO Value */
-#define MXC_S_GPIO_OUT_SET_GPIO_OUT_SET_NO \
- (MXC_V_GPIO_OUT_SET_GPIO_OUT_SET_NO \
- << MXC_F_GPIO_OUT_SET_GPIO_OUT_SET_POS) /**< OUT_SET_GPIO_OUT_SET_NO \
- Setting */
-#define MXC_V_GPIO_OUT_SET_GPIO_OUT_SET_SET \
- ((uint32_t)0x1UL) /**< OUT_SET_GPIO_OUT_SET_SET Value */
-#define MXC_S_GPIO_OUT_SET_GPIO_OUT_SET_SET \
- (MXC_V_GPIO_OUT_SET_GPIO_OUT_SET_SET \
- << MXC_F_GPIO_OUT_SET_GPIO_OUT_SET_POS) /**< OUT_SET_GPIO_OUT_SET_SET \
- Setting */
-/**
- * GPIO Output Clear. Writing a 1 to one or more bits in this register
- * clears the bits in the same positions in GPIO_OUT to 0, without affecting
- * other bits in that register.
- */
-#define MXC_F_GPIO_OUT_CLR_GPIO_OUT_CLR_POS \
- 0 /**< OUT_CLR_GPIO_OUT_CLR Position */
-#define MXC_F_GPIO_OUT_CLR_GPIO_OUT_CLR \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_OUT_CLR_GPIO_OUT_CLR_POS)) /**< \
- OUT_CLR_GPIO_OUT_CLR \
- Mask */
-
-/**
- * GPIO Input Register. Read-only register to read from the logic
- * states of the GPIO pins on this port.
- */
-#define MXC_F_GPIO_IN_GPIO_IN_POS 0 /**< IN_GPIO_IN Position */
-#define MXC_F_GPIO_IN_GPIO_IN \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_IN_GPIO_IN_POS)) /**< IN_GPIO_IN Mask */
-
-/**
- * GPIO Interrupt Mode Register. Each bit in this register controls
- * the interrupt mode setting for the associated GPIO pin on this port.
- */
-#define MXC_F_GPIO_INT_MOD_GPIO_INT_MOD_POS \
- 0 /**< INT_MOD_GPIO_INT_MOD Position */
-#define MXC_F_GPIO_INT_MOD_GPIO_INT_MOD \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_MOD_GPIO_INT_MOD_POS)) /**< \
- INT_MOD_GPIO_INT_MOD \
- Mask */
-#define MXC_V_GPIO_INT_MOD_GPIO_INT_MOD_LEVEL \
- ((uint32_t)0x0UL) /**< INT_MOD_GPIO_INT_MOD_LEVEL Value */
-#define MXC_S_GPIO_INT_MOD_GPIO_INT_MOD_LEVEL \
- (MXC_V_GPIO_INT_MOD_GPIO_INT_MOD_LEVEL \
- << MXC_F_GPIO_INT_MOD_GPIO_INT_MOD_POS) /**< \
- INT_MOD_GPIO_INT_MOD_LEVEL \
- Setting */
-#define MXC_V_GPIO_INT_MOD_GPIO_INT_MOD_EDGE \
- ((uint32_t)0x1UL) /**< INT_MOD_GPIO_INT_MOD_EDGE Value */
-#define MXC_S_GPIO_INT_MOD_GPIO_INT_MOD_EDGE \
- (MXC_V_GPIO_INT_MOD_GPIO_INT_MOD_EDGE \
- << MXC_F_GPIO_INT_MOD_GPIO_INT_MOD_POS) /**< \
- INT_MOD_GPIO_INT_MOD_EDGE \
- Setting */
-
-/**
- * GPIO Interrupt Polarity Register. Each bit in this register
- * controls the interrupt polarity setting for one GPIO pin in the associated
- * port.
- */
-#define MXC_F_GPIO_INT_POL_GPIO_INT_POL_POS \
- 0 /**< INT_POL_GPIO_INT_POL Position */
-#define MXC_F_GPIO_INT_POL_GPIO_INT_POL \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_POL_GPIO_INT_POL_POS)) /**< \
- INT_POL_GPIO_INT_POL \
- Mask */
-#define MXC_V_GPIO_INT_POL_GPIO_INT_POL_FALLING \
- ((uint32_t)0x0UL) /**< INT_POL_GPIO_INT_POL_FALLING Value */
-#define MXC_S_GPIO_INT_POL_GPIO_INT_POL_FALLING \
- (MXC_V_GPIO_INT_POL_GPIO_INT_POL_FALLING \
- << MXC_F_GPIO_INT_POL_GPIO_INT_POL_POS) /**< \
- INT_POL_GPIO_INT_POL_FALLING \
- Setting */
-#define MXC_V_GPIO_INT_POL_GPIO_INT_POL_RISING \
- ((uint32_t)0x1UL) /**< INT_POL_GPIO_INT_POL_RISING Value */
-#define MXC_S_GPIO_INT_POL_GPIO_INT_POL_RISING \
- (MXC_V_GPIO_INT_POL_GPIO_INT_POL_RISING \
- << MXC_F_GPIO_INT_POL_GPIO_INT_POL_POS) /**< \
- INT_POL_GPIO_INT_POL_RISING \
- Setting */
-
-/**
- * GPIO Interrupt Enable Register. Each bit in this register controls
- * the GPIO interrupt enable for the associated pin on the GPIO port.
- */
-#define MXC_F_GPIO_INT_EN_GPIO_INT_EN_POS \
- 0 /**< INT_EN_GPIO_INT_EN Position \
- */
-#define MXC_F_GPIO_INT_EN_GPIO_INT_EN \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_EN_GPIO_INT_EN_POS)) /**< INT_EN_GPIO_INT_EN \
- Mask */
-#define MXC_V_GPIO_INT_EN_GPIO_INT_EN_DIS \
- ((uint32_t)0x0UL) /**< INT_EN_GPIO_INT_EN_DIS Value */
-#define MXC_S_GPIO_INT_EN_GPIO_INT_EN_DIS \
- (MXC_V_GPIO_INT_EN_GPIO_INT_EN_DIS \
- << MXC_F_GPIO_INT_EN_GPIO_INT_EN_POS) /**< INT_EN_GPIO_INT_EN_DIS \
- Setting */
-#define MXC_V_GPIO_INT_EN_GPIO_INT_EN_EN \
- ((uint32_t)0x1UL) /**< INT_EN_GPIO_INT_EN_EN Value */
-#define MXC_S_GPIO_INT_EN_GPIO_INT_EN_EN \
- (MXC_V_GPIO_INT_EN_GPIO_INT_EN_EN \
- << MXC_F_GPIO_INT_EN_GPIO_INT_EN_POS) /**< INT_EN_GPIO_INT_EN_EN \
- Setting */
-
-/**
- * GPIO Interrupt Enable Set. Writing a 1 to one or more bits in this
- * register sets the bits in the same positions in GPIO_INT_EN to 1, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_INT_EN_SET_GPIO_INT_EN_SET_POS \
- 0 /**< INT_EN_SET_GPIO_INT_EN_SET Position */
-#define MXC_F_GPIO_INT_EN_SET_GPIO_INT_EN_SET \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_EN_SET_GPIO_INT_EN_SET_POS)) /**< \
- INT_EN_SET_GPIO_INT_EN_SET \
- Mask */
-#define MXC_V_GPIO_INT_EN_SET_GPIO_INT_EN_SET_NO \
- ((uint32_t)0x0UL) /**< INT_EN_SET_GPIO_INT_EN_SET_NO Value */
-#define MXC_S_GPIO_INT_EN_SET_GPIO_INT_EN_SET_NO \
- (MXC_V_GPIO_INT_EN_SET_GPIO_INT_EN_SET_NO \
- << MXC_F_GPIO_INT_EN_SET_GPIO_INT_EN_SET_POS) /**< \
- INT_EN_SET_GPIO_INT_EN_SET_NO \
- Setting */
-#define MXC_V_GPIO_INT_EN_SET_GPIO_INT_EN_SET_SET \
- ((uint32_t)0x1UL) /**< INT_EN_SET_GPIO_INT_EN_SET_SET Value */
-#define MXC_S_GPIO_INT_EN_SET_GPIO_INT_EN_SET_SET \
- (MXC_V_GPIO_INT_EN_SET_GPIO_INT_EN_SET_SET \
- << MXC_F_GPIO_INT_EN_SET_GPIO_INT_EN_SET_POS) /**< \
- INT_EN_SET_GPIO_INT_EN_SET_SET \
- Setting */
-/**
- * GPIO Interrupt Enable Clear. Writing a 1 to one or more bits in
- * this register clears the bits in the same positions in GPIO_INT_EN to 0,
- * without affecting other bits in that register.
- */
-#define MXC_F_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_POS \
- 0 /**< INT_EN_CLR_GPIO_INT_EN_CLR Position */
-#define MXC_F_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_POS)) /**< \
- INT_EN_CLR_GPIO_INT_EN_CLR \
- Mask */
-#define MXC_V_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_NO \
- ((uint32_t)0x0UL) /**< INT_EN_CLR_GPIO_INT_EN_CLR_NO Value */
-#define MXC_S_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_NO \
- (MXC_V_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_NO \
- << MXC_F_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_POS) /**< \
- INT_EN_CLR_GPIO_INT_EN_CLR_NO \
- Setting */
-#define MXC_V_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_CLEAR \
- ((uint32_t)0x1UL) /**< INT_EN_CLR_GPIO_INT_EN_CLR_CLEAR Value */
-#define MXC_S_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_CLEAR \
- (MXC_V_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_CLEAR \
- << MXC_F_GPIO_INT_EN_CLR_GPIO_INT_EN_CLR_POS) /**< \
- INT_EN_CLR_GPIO_INT_EN_CLR_CLEAR \
- Setting */
-/**
- * GPIO Interrupt Status Register. Each bit in this register contains
- * the pending interrupt status for the associated GPIO pin in this port.
- */
-#define MXC_F_GPIO_INT_STAT_GPIO_INT_STAT_POS \
- 0 /**< INT_STAT_GPIO_INT_STAT Position */
-#define MXC_F_GPIO_INT_STAT_GPIO_INT_STAT \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_STAT_GPIO_INT_STAT_POS)) /**< \
- INT_STAT_GPIO_INT_STAT \
- Mask */
-#define MXC_V_GPIO_INT_STAT_GPIO_INT_STAT_NO \
- ((uint32_t)0x0UL) /**< INT_STAT_GPIO_INT_STAT_NO Value */
-#define MXC_S_GPIO_INT_STAT_GPIO_INT_STAT_NO \
- (MXC_V_GPIO_INT_STAT_GPIO_INT_STAT_NO \
- << MXC_F_GPIO_INT_STAT_GPIO_INT_STAT_POS) /**< \
- INT_STAT_GPIO_INT_STAT_NO \
- Setting */
-#define MXC_V_GPIO_INT_STAT_GPIO_INT_STAT_PENDING \
- ((uint32_t)0x1UL) /**< INT_STAT_GPIO_INT_STAT_PENDING Value */
-#define MXC_S_GPIO_INT_STAT_GPIO_INT_STAT_PENDING \
- (MXC_V_GPIO_INT_STAT_GPIO_INT_STAT_PENDING \
- << MXC_F_GPIO_INT_STAT_GPIO_INT_STAT_POS) /**< \
- INT_STAT_GPIO_INT_STAT_PENDING \
- Setting */
-
-/**
- * GPIO Status Clear. Writing a 1 to one or more bits in this register
- * clears the bits in the same positions in GPIO_INT_STAT to 0, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_INT_CLR_ALL_POS 0 /**< INT_CLR_ALL Position */
-#define MXC_F_GPIO_INT_CLR_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_CLR_ALL_POS)) /**< INT_CLR_ALL Mask */
-
-/**
- * GPIO Wake Enable Register. Each bit in this register controls the
- * PMU wakeup enable for the associated GPIO pin in this port.
- */
-#define MXC_F_GPIO_WAKE_EN_GPIO_WAKE_EN_POS \
- 0 /**< WAKE_EN_GPIO_WAKE_EN Position */
-#define MXC_F_GPIO_WAKE_EN_GPIO_WAKE_EN \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_WAKE_EN_GPIO_WAKE_EN_POS)) /**< \
- WAKE_EN_GPIO_WAKE_EN \
- Mask */
-#define MXC_V_GPIO_WAKE_EN_GPIO_WAKE_EN_DIS \
- ((uint32_t)0x0UL) /**< WAKE_EN_GPIO_WAKE_EN_DIS Value */
-#define MXC_S_GPIO_WAKE_EN_GPIO_WAKE_EN_DIS \
- (MXC_V_GPIO_WAKE_EN_GPIO_WAKE_EN_DIS \
- << MXC_F_GPIO_WAKE_EN_GPIO_WAKE_EN_POS) /**< WAKE_EN_GPIO_WAKE_EN_DIS \
- Setting */
-#define MXC_V_GPIO_WAKE_EN_GPIO_WAKE_EN_EN \
- ((uint32_t)0x1UL) /**< WAKE_EN_GPIO_WAKE_EN_EN Value */
-#define MXC_S_GPIO_WAKE_EN_GPIO_WAKE_EN_EN \
- (MXC_V_GPIO_WAKE_EN_GPIO_WAKE_EN_EN \
- << MXC_F_GPIO_WAKE_EN_GPIO_WAKE_EN_POS) /**< WAKE_EN_GPIO_WAKE_EN_EN \
- Setting */
-
-/**
- * GPIO Wake Enable Set. Writing a 1 to one or more bits in this
- * register sets the bits in the same positions in GPIO_WAKE_EN to 1, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_WAKE_EN_SET_ALL_POS 0 /**< WAKE_EN_SET_ALL Position */
-#define MXC_F_GPIO_WAKE_EN_SET_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_WAKE_EN_SET_ALL_POS)) /**< WAKE_EN_SET_ALL \
- Mask */
-
-/**
- * GPIO Wake Enable Clear. Writing a 1 to one or more bits in this
- * register clears the bits in the same positions in GPIO_WAKE_EN to 0, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_WAKE_EN_CLR_ALL_POS 0 /**< WAKE_EN_CLR_ALL Position */
-#define MXC_F_GPIO_WAKE_EN_CLR_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_WAKE_EN_CLR_ALL_POS)) /**< WAKE_EN_CLR_ALL \
- Mask */
-
-/**
- * GPIO Interrupt Dual Edge Mode Register. Each bit in this register
- * selects dual edge mode for the associated GPIO pin in this port.
- */
-#define MXC_F_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_POS \
- 0 /**< INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE Position */
-#define MXC_F_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_POS)) /**< \
- INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE \
- Mask \
- */
-#define MXC_V_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_NO \
- ((uint32_t)0x0UL) /**< INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_NO Value */
-#define MXC_S_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_NO \
- (MXC_V_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_NO \
- << MXC_F_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_POS) /**< \
- INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_NO \
- Setting */
-#define MXC_V_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_EN \
- ((uint32_t)0x1UL) /**< INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_EN Value */
-#define MXC_S_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_EN \
- (MXC_V_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_EN \
- << MXC_F_GPIO_INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_POS) /**< \
- INT_DUAL_EDGE_GPIO_INT_DUAL_EDGE_EN \
- Setting */
-
-/**
- * GPIO Input Mode Config 1. Each bit in this register enables the
- * weak pull-up for the associated GPIO pin in this port.
- */
-#define MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1_POS \
- 0 /**< PAD_CFG1_GPIO_PAD_CFG1 Position */
-#define MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1 \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1_POS)) /**< \
- PAD_CFG1_GPIO_PAD_CFG1 \
- Mask */
-#define MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_IMPEDANCE \
- ((uint32_t)0x0UL) /**< PAD_CFG1_GPIO_PAD_CFG1_IMPEDANCE Value */
-#define MXC_S_GPIO_PAD_CFG1_GPIO_PAD_CFG1_IMPEDANCE \
- (MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_IMPEDANCE \
- << MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1_POS) /**< \
- PAD_CFG1_GPIO_PAD_CFG1_IMPEDANCE \
- Setting */
-#define MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PU \
- ((uint32_t)0x1UL) /**< PAD_CFG1_GPIO_PAD_CFG1_PU Value */
-#define MXC_S_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PU \
- (MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PU \
- << MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1_POS) /**< \
- PAD_CFG1_GPIO_PAD_CFG1_PU \
- Setting */
-#define MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PD \
- ((uint32_t)0x2UL) /**< PAD_CFG1_GPIO_PAD_CFG1_PD Value */
-#define MXC_S_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PD \
- (MXC_V_GPIO_PAD_CFG1_GPIO_PAD_CFG1_PD \
- << MXC_F_GPIO_PAD_CFG1_GPIO_PAD_CFG1_POS) /**< \
- PAD_CFG1_GPIO_PAD_CFG1_PD \
- Setting */
-
-/**
- * GPIO Input Mode Config 2. Each bit in this register enables the
- * weak pull-up for the associated GPIO pin in this port.
- */
-#define MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2_POS \
- 0 /**< PAD_CFG2_GPIO_PAD_CFG2 Position */
-#define MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2 \
- ((uint32_t)( \
- 0xFFFFFFFFUL \
- << MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2_POS)) /**< \
- PAD_CFG2_GPIO_PAD_CFG2 \
- Mask */
-#define MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_IMPEDANCE \
- ((uint32_t)0x0UL) /**< PAD_CFG2_GPIO_PAD_CFG2_IMPEDANCE Value */
-#define MXC_S_GPIO_PAD_CFG2_GPIO_PAD_CFG2_IMPEDANCE \
- (MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_IMPEDANCE \
- << MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2_POS) /**< \
- PAD_CFG2_GPIO_PAD_CFG2_IMPEDANCE \
- Setting */
-#define MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PU \
- ((uint32_t)0x1UL) /**< PAD_CFG2_GPIO_PAD_CFG2_PU Value */
-#define MXC_S_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PU \
- (MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PU \
- << MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2_POS) /**< \
- PAD_CFG2_GPIO_PAD_CFG2_PU \
- Setting */
-#define MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PD \
- ((uint32_t)0x2UL) /**< PAD_CFG2_GPIO_PAD_CFG2_PD Value */
-#define MXC_S_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PD \
- (MXC_V_GPIO_PAD_CFG2_GPIO_PAD_CFG2_PD \
- << MXC_F_GPIO_PAD_CFG2_GPIO_PAD_CFG2_POS) /**< \
- PAD_CFG2_GPIO_PAD_CFG2_PD \
- Setting */
-
-/**
- * GPIO Alternate Function Enable Register. Each bit in this register
- * selects between primary/secondary functions for the associated GPIO pin in
- * this port.
- */
-#define MXC_F_GPIO_EN1_GPIO_EN1_POS 0 /**< EN1_GPIO_EN1 Position */
-#define MXC_F_GPIO_EN1_GPIO_EN1 \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN1_GPIO_EN1_POS)) /**< EN1_GPIO_EN1 Mask */
-#define MXC_V_GPIO_EN1_GPIO_EN1_PRIMARY \
- ((uint32_t)0x0UL) /**< EN1_GPIO_EN1_PRIMARY Value */
-#define MXC_S_GPIO_EN1_GPIO_EN1_PRIMARY \
- (MXC_V_GPIO_EN1_GPIO_EN1_PRIMARY \
- << MXC_F_GPIO_EN1_GPIO_EN1_POS) /**< EN1_GPIO_EN1_PRIMARY Setting */
-#define MXC_V_GPIO_EN1_GPIO_EN1_SECONDARY \
- ((uint32_t)0x1UL) /**< EN1_GPIO_EN1_SECONDARY Value */
-#define MXC_S_GPIO_EN1_GPIO_EN1_SECONDARY \
- (MXC_V_GPIO_EN1_GPIO_EN1_SECONDARY \
- << MXC_F_GPIO_EN1_GPIO_EN1_POS) /**< EN1_GPIO_EN1_SECONDARY Setting \
- */
-
-/**
- * GPIO Alternate Function Set. Writing a 1 to one or more bits in
- * this register sets the bits in the same positions in GPIO_EN1 to 1, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN1_SET_ALL_POS 0 /**< EN1_SET_ALL Position */
-#define MXC_F_GPIO_EN1_SET_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN1_SET_ALL_POS)) /**< EN1_SET_ALL Mask */
-
-/**
- * GPIO Alternate Function Clear. Writing a 1 to one or more bits in
- * this register clears the bits in the same positions in GPIO_EN1 to 0, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN1_CLR_ALL_POS 0 /**< EN1_CLR_ALL Position */
-#define MXC_F_GPIO_EN1_CLR_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN1_CLR_ALL_POS)) /**< EN1_CLR_ALL Mask */
-
-/**
- * GPIO Alternate Function Enable Register. Each bit in this register
- * selects between primary/secondary functions for the associated GPIO pin in
- * this port.
- */
-#define MXC_F_GPIO_EN2_GPIO_EN2_POS 0 /**< EN2_GPIO_EN2 Position */
-#define MXC_F_GPIO_EN2_GPIO_EN2 \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN2_GPIO_EN2_POS)) /**< EN2_GPIO_EN2 Mask */
-#define MXC_V_GPIO_EN2_GPIO_EN2_PRIMARY \
- ((uint32_t)0x0UL) /**< EN2_GPIO_EN2_PRIMARY Value */
-#define MXC_S_GPIO_EN2_GPIO_EN2_PRIMARY \
- (MXC_V_GPIO_EN2_GPIO_EN2_PRIMARY \
- << MXC_F_GPIO_EN2_GPIO_EN2_POS) /**< EN2_GPIO_EN2_PRIMARY Setting */
-#define MXC_V_GPIO_EN2_GPIO_EN2_SECONDARY \
- ((uint32_t)0x1UL) /**< EN2_GPIO_EN2_SECONDARY Value */
-#define MXC_S_GPIO_EN2_GPIO_EN2_SECONDARY \
- (MXC_V_GPIO_EN2_GPIO_EN2_SECONDARY \
- << MXC_F_GPIO_EN2_GPIO_EN2_POS) /**< EN2_GPIO_EN2_SECONDARY Setting \
- */
-
-/**
- * GPIO Alternate Function 2 Set. Writing a 1 to one or more bits in
- * this register sets the bits in the same positions in GPIO_EN2 to 1, without
- * affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN2_SET_ALL_POS 0 /**< EN2_SET_ALL Position */
-#define MXC_F_GPIO_EN2_SET_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN2_SET_ALL_POS)) /**< EN2_SET_ALL Mask */
-
-/**
- * GPIO Wake Alternate Function Clear. Writing a 1 to one or more bits
- * in this register clears the bits in the same positions in GPIO_EN2 to 0,
- * without affecting other bits in that register.
- */
-#define MXC_F_GPIO_EN2_CLR_ALL_POS 0 /**< EN2_CLR_ALL Position */
-#define MXC_F_GPIO_EN2_CLR_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_EN2_CLR_ALL_POS)) /**< EN2_CLR_ALL Mask */
-
-/**
- * GPIO Drive Strength Register. Each bit in this register selects
- * the drive strength for the associated GPIO pin in this port. Refer to the
- * Datasheet for sink/source current of GPIO pins in each mode.
- */
-#define MXC_F_GPIO_DS_DS_POS 0 /**< DS_DS Position */
-#define MXC_F_GPIO_DS_DS \
- ((uint32_t)(0xFFFFFFFFUL << MXC_F_GPIO_DS_DS_POS)) /**< DS_DS Mask */
-#define MXC_V_GPIO_DS_DS_LD ((uint32_t)0x0UL) /**< DS_DS_LD Value */
-#define MXC_S_GPIO_DS_DS_LD \
- (MXC_V_GPIO_DS_DS_LD << MXC_F_GPIO_DS_DS_POS) /**< DS_DS_LD Setting */
-#define MXC_V_GPIO_DS_DS_HD ((uint32_t)0x1UL) /**< DS_DS_HD Value */
-#define MXC_S_GPIO_DS_DS_HD \
- (MXC_V_GPIO_DS_DS_HD << MXC_F_GPIO_DS_DS_POS) /**< DS_DS_HD Setting */
-
-/**
- * GPIO Drive Strength 1 Register. Each bit in this register selects
- * the drive strength for the associated GPIO pin in this port. Refer to the
- * Datasheet for sink/source current of GPIO pins in each mode.
- */
-#define MXC_F_GPIO_DS1_ALL_POS 0 /**< DS1_ALL Position */
-#define MXC_F_GPIO_DS1_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_DS1_ALL_POS)) /**< DS1_ALL Mask */
-
-/**
- * GPIO Pull Select Mode.
- */
-#define MXC_F_GPIO_PS_ALL_POS 0 /**< PS_ALL Position */
-#define MXC_F_GPIO_PS_ALL \
- ((uint32_t)(0xFFFFFFFFUL << MXC_F_GPIO_PS_ALL_POS)) /**< PS_ALL Mask \
- */
-
-/**
- * GPIO Voltage Select.
- */
-#define MXC_F_GPIO_VSSEL_ALL_POS 0 /**< VSSEL_ALL Position */
-#define MXC_F_GPIO_VSSEL_ALL \
- ((uint32_t)(0xFFFFFFFFUL \
- << MXC_F_GPIO_VSSEL_ALL_POS)) /**< VSSEL_ALL Mask */
-
-#endif /* _GPIO_REGS_H_ */
diff --git a/chip/max32660/hwtimer_chip.c b/chip/max32660/hwtimer_chip.c
deleted file mode 100644
index 5417e161b2..0000000000
--- a/chip/max32660/hwtimer_chip.c
+++ /dev/null
@@ -1,230 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 HW Timer module for Chrome EC */
-
-#include "clock.h"
-#include "console.h"
-#include "common.h"
-#include "hooks.h"
-#include "hwtimer.h"
-#include "task.h"
-#include "timer.h"
-#include "registers.h"
-#include "tmr_regs.h"
-#include "gcr_regs.h"
-
-/* Define the rollover timer */
-#define TMR_ROLLOVER MXC_TMR0
-#define TMR_ROLLOVER_IRQ EC_TMR0_IRQn
-
-/* Define the event timer */
-#define TMR_EVENT MXC_TMR1
-#define TMR_EVENT_IRQ EC_TMR1_IRQn
-
-#define ROLLOVER_EVENT 1
-#define NOT_ROLLOVER_EVENT 0
-
-#define TMR_PRESCALER MXC_V_TMR_CN_PRES_DIV8
-#define TMR_DIV (1 << TMR_PRESCALER)
-
-/* The frequency of timer using the prescaler */
-#define TIMER_FREQ_HZ (PeripheralClock / TMR_DIV)
-
-/* Console output macros */
-#define CPUTS(outstr) cputs(CC_SYSTEM, outstr)
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ##args)
-
-static uint32_t last_deadline;
-
-/* brief Timer prescaler values */
-enum tmr_pres {
- TMR_PRES_1 = MXC_V_TMR_CN_PRES_DIV1, /// Divide input clock by 1
- TMR_PRES_2 = MXC_V_TMR_CN_PRES_DIV2, /// Divide input clock by 2
- TMR_PRES_4 = MXC_V_TMR_CN_PRES_DIV4, /// Divide input clock by 4
- TMR_PRES_8 = MXC_V_TMR_CN_PRES_DIV8, /// Divide input clock by 8
- TMR_PRES_16 = MXC_V_TMR_CN_PRES_DIV16, /// Divide input clock by 16
- TMR_PRES_32 = MXC_V_TMR_CN_PRES_DIV32, /// Divide input clock by 32
- TMR_PRES_64 = MXC_V_TMR_CN_PRES_DIV64, /// Divide input clock by 64
- TMR_PRES_128 = MXC_V_TMR_CN_PRES_DIV128, /// Divide input clock by 128
- TMR_PRES_256 =
- (0x20 << MXC_F_TMR_CN_PRES_POS), /// Divide input clock by 256
- TMR_PRES_512 =
- (0x21 << MXC_F_TMR_CN_PRES_POS), /// Divide input clock by 512
- TMR_PRES_1024 =
- (0x22 << MXC_F_TMR_CN_PRES_POS), /// Divide input clock by 1024
- TMR_PRES_2048 =
- (0x23 << MXC_F_TMR_CN_PRES_POS), /// Divide input clock by 2048
- TMR_PRES_4096 =
- (0x24 << MXC_F_TMR_CN_PRES_POS), /// Divide input clock by 4096
-};
-
-/* Timer modes */
-enum tmr_mode {
- TMR_MODE_ONESHOT = MXC_V_TMR_CN_TMODE_ONESHOT, /// Timer Mode ONESHOT
- TMR_MODE_CONTINUOUS =
- MXC_V_TMR_CN_TMODE_CONTINUOUS, /// Timer Mode CONTINUOUS
- TMR_MODE_COUNTER = MXC_V_TMR_CN_TMODE_COUNTER, /// Timer Mode COUNTER
- TMR_MODE_PWM = MXC_V_TMR_CN_TMODE_PWM, /// Timer Mode PWM
- TMR_MODE_CAPTURE = MXC_V_TMR_CN_TMODE_CAPTURE, /// Timer Mode CAPTURE
- TMR_MODE_COMPARE = MXC_V_TMR_CN_TMODE_COMPARE, /// Timer Mode COMPARE
- TMR_MODE_GATED = MXC_V_TMR_CN_TMODE_GATED, /// Timer Mode GATED
- TMR_MODE_CAPTURE_COMPARE =
- MXC_V_TMR_CN_TMODE_CAPTURECOMPARE /// Timer Mode CAPTURECOMPARE
-};
-
-/*
- * Calculate the number of microseconds for a given timer tick
- */
-static inline uint32_t ticks_to_usecs(uint32_t ticks)
-{
- return (uint64_t)ticks * SECOND / TIMER_FREQ_HZ;
-}
-
-/*
- * Calculate the number of timer ticks for a given microsecond value
- */
-static inline uint32_t usecs_to_ticks(uint32_t usecs)
-{
- return ((uint64_t)(usecs)*TIMER_FREQ_HZ / SECOND);
-}
-
-void __hw_clock_event_set(uint32_t deadline)
-{
- uint32_t event_time_us;
- uint32_t event_time_ticks;
- uint32_t time_now;
-
- last_deadline = deadline;
- time_now = __hw_clock_source_read();
-
- /* check if the deadline has rolled over */
- if (deadline < time_now) {
- event_time_us = (0xFFFFFFFF - time_now) + deadline;
- } else {
- /* How long from the current time to the deadline? */
- event_time_us = (deadline - __hw_clock_source_read());
- }
-
- /* Convert event_time to ticks rounding up */
- event_time_ticks = usecs_to_ticks(event_time_us) + 1;
-
- /* set the event time into the timer compare */
- TMR_EVENT->cmp = event_time_ticks;
- /* zero out the timer */
- TMR_EVENT->cnt = 0;
- TMR_EVENT->cn |= MXC_F_TMR_CN_TEN;
-}
-
-uint32_t __hw_clock_event_get(void)
-{
- return last_deadline;
-}
-
-void __hw_clock_event_clear(void)
-{
- TMR_EVENT->cn &= ~(MXC_F_TMR_CN_TEN);
-}
-
-uint32_t __hw_clock_source_read(void)
-{
- uint32_t timer_count_ticks;
-
- /* Read the timer value and return the results in microseconds */
- timer_count_ticks = TMR_ROLLOVER->cnt;
- return ticks_to_usecs(timer_count_ticks);
-}
-
-void __hw_clock_source_set(uint32_t ts)
-{
- uint32_t timer_count_ticks;
- timer_count_ticks = usecs_to_ticks(ts);
- TMR_ROLLOVER->cnt = timer_count_ticks;
-}
-
-/**
- * Interrupt handler for Timer
- */
-static void __timer_event_isr(void)
-{
- /* Clear the event timer */
- TMR_EVENT->intr = MXC_F_TMR_INTR_IRQ_CLR;
- /* Process the timer, pass in that this was NOT a rollover event */
- if (TMR_ROLLOVER->intr) {
- TMR_ROLLOVER->intr = MXC_F_TMR_INTR_IRQ_CLR;
- process_timers(ROLLOVER_EVENT);
- } else {
- process_timers(NOT_ROLLOVER_EVENT);
- }
-}
-/*
- * Declare the EC Timer lower in priority than the I2C interrupt. This
- * allows the I2C driver to process time sensitive interrupts.
- */
-DECLARE_IRQ(EC_TMR1_IRQn, __timer_event_isr, 2);
-
-static void init_timer(mxc_tmr_regs_t *timer, enum tmr_pres prescaler,
- enum tmr_mode mode, uint32_t count)
-{
- /* Disable the Timer */
- timer->cn &= ~(MXC_F_TMR_CN_TEN);
-
- if (timer == MXC_TMR0) {
- /* Enable Timer 0 Clock */
- MXC_GCR->perckcn0 &= ~(MXC_F_GCR_PERCKCN0_T0D);
- } else if (timer == MXC_TMR1) {
- /* Enable Timer 1 Clock */
- MXC_GCR->perckcn0 &= ~(MXC_F_GCR_PERCKCN0_T1D);
- } else if (timer == MXC_TMR2) {
- /* Enable Timer 2 Clock */
- MXC_GCR->perckcn0 &= ~(MXC_F_GCR_PERCKCN0_T2D);
- }
-
- /* Disable timer and clear settings */
- timer->cn = 0;
-
- /* Clear interrupt flag */
- timer->intr = MXC_F_TMR_INTR_IRQ_CLR;
-
- /* Set the prescaler */
- timer->cn = (prescaler << MXC_F_TMR_CN_PRES_POS);
-
- /* Configure the timer */
- timer->cn = (timer->cn & ~(MXC_F_TMR_CN_TMODE | MXC_F_TMR_CN_TPOL)) |
- ((mode << MXC_F_TMR_CN_TMODE_POS) & MXC_F_TMR_CN_TMODE) |
- ((0 << MXC_F_TMR_CN_TPOL_POS) & MXC_F_TMR_CN_TPOL);
-
- timer->cnt = 0x1;
- timer->cmp = count;
-}
-
-int __hw_clock_source_init(uint32_t start_t)
-{
- /* Initialize two timers, one for the OS Rollover and one for the OS
- * Events */
- init_timer(TMR_ROLLOVER, TMR_PRESCALER, TMR_MODE_CONTINUOUS,
- 0xffffffff);
- init_timer(TMR_EVENT, TMR_PRESCALER, TMR_MODE_COMPARE, 0x0);
- __hw_clock_source_set(start_t);
-
- /* Enable the timers */
- TMR_ROLLOVER->cn |= MXC_F_TMR_CN_TEN;
- TMR_EVENT->cn |= MXC_F_TMR_CN_TEN;
-
- /* Enable the IRQ */
- task_enable_irq(TMR_EVENT_IRQ);
-
- /* Return the Event timer IRQ number (NOT the Rollover IRQ) */
- return TMR_EVENT_IRQ;
-}
-
-static int hwtimer_display(int argc, char **argv)
-{
- CPRINTS(" TMR_EVENT count 0x%08x", TMR_EVENT->cnt);
- CPRINTS(" TMR_ROLLOVER count 0x%08x", TMR_ROLLOVER->cnt);
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(hwtimer, hwtimer_display, "hwtimer",
- "Display hwtimer counts");
diff --git a/chip/max32660/i2c_chip.c b/chip/max32660/i2c_chip.c
deleted file mode 100644
index f28e85f0ca..0000000000
--- a/chip/max32660/i2c_chip.c
+++ /dev/null
@@ -1,1132 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 I2C port module for Chrome EC. */
-
-#include <stdint.h>
-#include <stddef.h>
-#include "common.h"
-#include "config_chip.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "stdbool.h"
-#include "system.h"
-#include "task.h"
-#include "registers.h"
-#include "i2c_regs.h"
-
-/**
- * Byte to use if the EC HOST requested more data
- * than the I2C Slave is able to send.
- */
-#define EC_PADDING_BYTE 0xec
-
-/* **** Definitions **** */
-#define I2C_ERROR \
- (MXC_F_I2C_INT_FL0_ARB_ER | MXC_F_I2C_INT_FL0_TO_ER | \
- MXC_F_I2C_INT_FL0_ADDR_NACK_ER | MXC_F_I2C_INT_FL0_DATA_ER | \
- MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER | MXC_F_I2C_INT_FL0_START_ER | \
- MXC_F_I2C_INT_FL0_STOP_ER)
-
-#define T_LOW_MIN (160) /* tLOW minimum in nanoseconds */
-#define T_HIGH_MIN (60) /* tHIGH minimum in nanoseconds */
-#define T_R_MAX_HS (40) /* tR maximum for high speed mode in nanoseconds */
-#define T_F_MAX_HS (40) /* tF maximum for high speed mode in nanoseconds */
-#define T_AF_MIN (10) /* tAF minimun in nanoseconds */
-
-/**
- * typedef i2c_speed_t - I2C speed modes.
- * @I2C_STD_MODE: 100KHz bus speed
- * @I2C_FAST_MODE: 400KHz Bus Speed
- * @I2C_FASTPLUS_MODE: 1MHz Bus Speed
- * @I2C_HS_MODE: 3.4MHz Bus Speed
- */
-typedef enum {
- I2C_STD_MODE = 100000,
- I2C_FAST_MODE = 400000,
- I2C_FASTPLUS_MODE = 1000000,
- I2C_HS_MODE = 3400000
-} i2c_speed_t;
-
-/**
- * typedef i2c_autoflush_disable_t - Enable/Disable TXFIFO Autoflush mode.
- */
-typedef enum {
- I2C_AUTOFLUSH_ENABLE = 0,
- I2C_AUTOFLUSH_DISABLE = 1
-} i2c_autoflush_disable_t;
-
-/**
- * typedef i2c_master_state_t - Available transaction states for I2C Master.
- */
-typedef enum {
- I2C_MASTER_IDLE = 1,
- I2C_MASTER_START = 2,
- I2C_MASTER_WRITE_COMPLETE = 3,
- I2C_MASTER_READ_COMPLETE = 4
-} i2c_master_state_t;
-
-/**
- * typedef i2c_slave_state_t - Available transaction states for I2C Slave.
- */
-typedef enum {
- I2C_SLAVE_WRITE_COMPLETE = 0,
- I2C_SLAVE_ADDR_MATCH_READ = 1,
- I2C_SLAVE_ADDR_MATCH_WRITE = 2,
-} i2c_slave_state_t;
-
-/**
- * typedef i2c_req_t - I2C Transaction request.
- */
-typedef struct i2c_req i2c_req_t;
-
-/**
- * typedef i2c_req_state_t - Saves the state of the non-blocking requests.
- * @req: Pointer to I2C transaction request information.
- */
-typedef struct {
- i2c_req_t *req;
-} i2c_req_state_t;
-
-/**
- * struct i2c_req - I2C Transaction request.
- * @addr: I2C 7-bit Address right aligned, bit 6 to bit 0.
- * Only supports 7-bit addressing. LSb of the given
- * address will be used as the read/write bit, the addr
- * will not be shifted. Used for both master and slave
- * transactions.
- * @addr_match_flag: Indicates which slave address was matched.
- * 0x1 indicates first slave address matched.
- * 0x2 indicates second slave address matched.
- * 0x4 indicates third slave address matched.
- * 0x8 indicates fourth slave address matched.
- * @tx_data: Data for master write/slave read.
- * @rx_data: Data for master read/slave write.
- * @received_count: Number of rx bytes sent.
- * @tx_remain: Number of bytes to transmit to the master. This
- * value is -1 if should clock stretch, 0 if start
- * sending EC_PADDING_BYTE. Any other values in this
- * field will transmit data to the Master.
- * @state: I2C slave state that indicates address match, read and
- * write status.
- * @restart: Restart or stop bit indicator.
- * 0 to send a stop bit at the end of the transaction
- * Non-zero to send a restart at end of the transaction
- * Only used for Master transactions.
- * @response_pending: Indicates that a response to the I2C master
- * is pending.
- * @expecting_done: Indicates if an I2C done flag is expected. This
- * is used by the driver to determine the order to process
- * the flags.
- * @expecting_start: Indicates if an I2C start flag is expected. This
- * is used by the driver to determine the order to process
- * the flags.
- */
-struct i2c_req {
- uint8_t addr;
- uint8_t addr_match_flag;
- const uint8_t *tx_data;
- uint8_t *rx_data;
- volatile unsigned received_count;
- volatile int tx_remain;
- volatile i2c_slave_state_t state;
- volatile int restart;
- volatile bool response_pending;
- volatile bool expecting_done;
- volatile bool expecting_start;
-};
-
-static i2c_req_state_t states[MXC_I2C_INSTANCES];
-
-/**
- * struct i2c_port_data
- * @out: Output data pointer.
- * @out_size: Output data to transfer, in bytes.
- * @in: Input data pointer.
- * @in_size: Input data to transfer, in bytes.
- * @flags: Flags (I2C_XFER_*).
- * @idx: Index into input/output data.
- * @err: Error code, if any.
- * @timeout_us: Transaction timeout, or 0 to use default.
- * @task_waiting: Task waiting on port, or TASK_ID_INVALID if none.
- */
-struct i2c_port_data {
- const uint8_t *out;
- int out_size;
- uint8_t *in;
- int in_size;
- int flags;
- int idx;
- int err;
- uint32_t timeout_us;
- volatile int task_waiting;
-};
-static struct i2c_port_data pdata[I2C_PORT_COUNT];
-
-/* **** Function Prototypes **** */
-static int i2c_init_peripheral(mxc_i2c_regs_t *i2c, i2c_speed_t i2cspeed);
-static int i2c_master_write(mxc_i2c_regs_t *i2c, uint8_t addr, int start,
- int stop, const uint8_t *data, int len,
- int restart);
-static int i2c_master_read(mxc_i2c_regs_t *i2c, uint8_t addr, int start,
- int stop, uint8_t *data, int len, int restart);
-
-#ifdef CONFIG_HOSTCMD_I2C_ADDR_FLAGS
-static void init_i2cs(int port);
-static int i2c_slave_async(mxc_i2c_regs_t *i2c, i2c_req_t *req);
-static void i2c_slave_handler(mxc_i2c_regs_t *i2c);
-#endif /* CONFIG_HOSTCMD_I2C_ADDR_FLAGS */
-
-/* Port address for each I2C */
-static mxc_i2c_regs_t *i2c_bus_ports[] = {MXC_I2C0, MXC_I2C1};
-
-#ifdef CONFIG_HOSTCMD_I2C_ADDR_FLAGS
-
-#ifdef CONFIG_BOARD_I2C_ADDR_FLAGS
-static void i2c_send_board_response(int len);
-static void i2c_process_board_command(int read, int addr, int len);
-void board_i2c_process(int read, uint8_t addr, int len, char *buffer,
- void (*send_response)(int len));
-#endif /* CONFIG_BOARD_I2C_ADDR_FLAGS */
-#endif /* CONFIG_HOSTCMD_I2C_ADDR_FLAGS */
-
-/**
- * chip_i2c_xfer() - Low Level function for I2C Master Reads and Writes.
- * @port: Port to access
- * @slave_addr: Slave device address
- * @out: Data to send
- * @out_size: Number of bytes to send
- * @in: Destination buffer for received data
- * @in_size: Number of bytes to receive
- * @flags: Flags (see I2C_XFER_* above)
- *
- * Chip-level function to transmit one block of raw data, then receive one
- * block of raw data.
- *
- * This is a low-level chip-dependent function and should only be called by
- * i2c_xfer().\
- *
- * Return EC_SUCCESS, or non-zero if error.
- */
-int chip_i2c_xfer(int port, const uint16_t slave_addr_flags, const uint8_t *out,
- int out_size, uint8_t *in, int in_size, int flags)
-{
- int xfer_start;
- int xfer_stop;
- int status;
-
- xfer_start = flags & I2C_XFER_START;
- xfer_stop = flags & I2C_XFER_STOP;
-
- if (out_size) {
- status = i2c_master_write(i2c_bus_ports[port], slave_addr_flags,
- xfer_start, xfer_stop, out, out_size,
- 1);
- if (status != EC_SUCCESS) {
- return status;
- }
- }
- if (in_size) {
- status = i2c_master_read(i2c_bus_ports[port], slave_addr_flags,
- xfer_start, xfer_stop, in, in_size, 0);
- if (status != EC_SUCCESS) {
- return status;
- }
- }
- return EC_SUCCESS;
-}
-
-/**
- * i2c_get_line_levels() - Read the current digital levels on the I2C pins.
- * @port: Port number to use when reading line levels.
- *
- * Return a byte where bit 0 is the line level of SCL and
- * bit 1 is the line level of SDA.
- */
-int i2c_get_line_levels(int port)
-{
- /* Retrieve the current levels of SCL and SDA from the control reg. */
- return (i2c_bus_ports[port]->ctrl >> MXC_F_I2C_CTRL_SCL_POS) & 0x03;
-}
-
-/**
- * i2c_set_timeout()
- * @port: Port number to set timeout for.
- * @timeout: Timeout duration in microseconds.
- */
-void i2c_set_timeout(int port, uint32_t timeout)
-{
- pdata[port].timeout_us = timeout ? timeout : I2C_TIMEOUT_DEFAULT_US;
-}
-
-/**
- * i2c_init() - Initialize the I2C ports used on device.
- */
-void i2c_init(void)
-{
- int i;
- int port;
-
- /* Configure GPIOs */
- gpio_config_module(MODULE_I2C, 1);
-
- /* Initialize all I2C ports used. */
- for (i = 0; i < i2c_ports_used; i++) {
- port = i2c_ports[i].port;
- i2c_init_peripheral(i2c_bus_ports[port],
- i2c_ports[i].kbps * 1000);
- i2c_set_timeout(i, 0);
- }
-
-#ifdef CONFIG_HOSTCMD_I2C_ADDR_FLAGS
- /* Initialize the I2C Slave */
- init_i2cs(I2C_PORT_EC);
-#ifdef CONFIG_BOARD_I2C_ADDR_FLAGS
- /*
- * Set the secondary I2C slave address for the board.
- */
- /* Index the secondary slave address. */
- i2c_bus_ports[I2C_PORT_EC]->slave_addr =
- (i2c_bus_ports[I2C_PORT_EC]->slave_addr &
- ~(MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX |
- MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_DIS)) |
- (1 << MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX_POS);
- /* Set the secondary slave address. */
- i2c_bus_ports[I2C_PORT_EC]->slave_addr =
- (1 << MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX_POS) |
- CONFIG_BOARD_I2C_ADDR_FLAGS;
-#endif /* CONFIG_BOARD_I2C_ADDR_FLAGS */
-#endif /* CONFIG_HOSTCMD_I2C_ADDR_FLAGS */
-
-}
-
-/**
- * I2C Peripheral Implementation
- */
-#ifdef CONFIG_HOSTCMD_I2C_ADDR_FLAGS
-/* IRQ for each I2C */
-static uint32_t i2c_bus_irqs[] = {EC_I2C0_IRQn, EC_I2C1_IRQn};
-
-/**
- * Buffer for received host command packets (including prefix byte on request,
- * and result/size on response). After any protocol-specific headers, the
- * buffers must be 32-bit aligned.
- */
-static uint8_t host_buffer_padded[I2C_MAX_HOST_PACKET_SIZE + 4 +
- CONFIG_I2C_EXTRA_PACKET_SIZE] __aligned(4);
-static uint8_t *const host_buffer = host_buffer_padded + 2;
-static uint8_t params_copy[I2C_MAX_HOST_PACKET_SIZE] __aligned(4);
-static struct host_packet i2c_packet;
-
-static i2c_req_t req_slave;
-volatile int ec_pending_response = 0;
-
-/**
- * i2c_send_response_packet() - Send the response packet to get processed.
- * @pkt: Packet to send.
- */
-static void i2c_send_response_packet(struct host_packet *pkt)
-{
- int size = pkt->response_size;
- uint8_t *out = host_buffer;
-
- /* Ignore host command in-progress. */
- if (pkt->driver_result == EC_RES_IN_PROGRESS)
- return;
-
- /* Write result and size to first two bytes. */
- *out++ = pkt->driver_result;
- *out++ = size;
-
- /* Host_buffer data range. */
- req_slave.tx_remain = size + 2;
- req_slave.response_pending = true;
-
- /* Call the handler to send the response packet. */
- i2c_slave_handler(i2c_bus_ports[I2C_PORT_EC]);
-}
-
-/**
- * i2c_process_command() - Process the command in the i2c host buffer.
- */
-static void i2c_process_command(void)
-{
- char *buff = host_buffer;
-
- i2c_packet.send_response = i2c_send_response_packet;
- i2c_packet.request = (const void *)(&buff[1]);
- i2c_packet.request_temp = params_copy;
- i2c_packet.request_max = sizeof(params_copy);
- /* Don't know the request size so pass in the entire buffer. */
- i2c_packet.request_size = I2C_MAX_HOST_PACKET_SIZE;
-
- /*
- * Stuff response at buff[2] to leave the first two bytes of
- * buffer available for the result and size to send over i2c. Note
- * that this 2-byte offset and the 2-byte offset from host_buffer
- * add up to make the response buffer 32-bit aligned.
- */
- i2c_packet.response = (void *)(&buff[2]);
- i2c_packet.response_max = I2C_MAX_HOST_PACKET_SIZE;
- i2c_packet.response_size = 0;
-
- if (*buff >= EC_COMMAND_PROTOCOL_3) {
- i2c_packet.driver_result = EC_RES_SUCCESS;
- } else {
- /* Only host command protocol 3 is supported. */
- i2c_packet.driver_result = EC_RES_INVALID_HEADER;
- }
-
- host_packet_receive(&i2c_packet);
-}
-
-/**
- * i2c_slave_service() - Called by the I2C slave interrupt controller.
- * @req: Request currently being processed.
- */
-void i2c_slave_service(i2c_req_t *req)
-{
- /* Check if there was a host command (I2C master write). */
- if (req->state == I2C_SLAVE_ADDR_MATCH_WRITE) {
- req->state = I2C_SLAVE_WRITE_COMPLETE;
- /* A response to this write is pending. */
- /* Assume that there is nothing to send back to the HOST. */
- req->tx_remain = -1;
-#ifdef CONFIG_BOARD_I2C_ADDR_FLAGS
- if (req->addr_match_flag != 0x1) {
- i2c_process_board_command(
- 0, CONFIG_BOARD_I2C_ADDR_FLAGS,
- req->received_count);
- } else
-#endif /* CONFIG_BOARD_I2C_ADDR_FLAGS */
- {
- i2c_process_command();
- }
- }
-}
-
-/**
- * I2C0_IRQHandler() - Async Handler for I2C Slave driver.
- */
-void I2C0_IRQHandler(void)
-{
- i2c_slave_handler(i2c_bus_ports[0]);
-}
-
-/**
- * I2C1_IRQHandler() - Async Handler for I2C Slave driver.
- */
-void I2C1_IRQHandler(void)
-{
- i2c_slave_handler(i2c_bus_ports[1]);
-}
-
-DECLARE_IRQ(EC_I2C0_IRQn, I2C0_IRQHandler, 1);
-DECLARE_IRQ(EC_I2C1_IRQn, I2C1_IRQHandler, 1);
-
-/**
- * i2c_slave_service_read() - Services the Master I2C read from the slave.
- * @i2c: I2C peripheral pointer.
- * @req: Pointer to the request info.
- */
-static void i2c_slave_service_read(mxc_i2c_regs_t *i2c, i2c_req_t *req)
-{
- /*
- * Clear the RX Threshold interrupt if set. Make sure and preserve
- * a possible done bit, address match, or multiple slave address
- * flags.
- */
- i2c->int_fl0 = i2c->int_fl0 & ~(MXC_F_I2C_INT_FL0_ADDR_MATCH |
- MXC_F_I2C_INT_FL0_MAMI_MASK | MXC_F_I2C_INT_FL0_DONE);
- i2c->int_fl1 = i2c->int_fl1;
- /*
- * If there is nothing to transmit to the EC HOST, then default
- * to clock stretching.
- */
- if (req->tx_remain < 0) {
- return;
- }
- /* If there is data to send to the Master then fill the TX FIFO. */
- if (req->tx_remain != 0) {
- /* There is no longer a response pending from the slave to the master. */
- req->response_pending = false;
- /* Fill the FIFO with data to transimit to the I2C Master. */
- while ((req->tx_remain > 0) &&
- !(i2c->status & MXC_F_I2C_STATUS_TX_FULL)) {
- i2c->fifo = *(req->tx_data)++;
- req->tx_remain--;
- }
- }
- /*
- * If we have sent everything to the Master that we can,
- * then send padding byte.
- */
- if (req->tx_remain == 0) {
- /* Tx response is fulfilled. */
- /* Fill the FIFO with the EC padding byte. */
- while (!(i2c->status & MXC_F_I2C_STATUS_TX_FULL)) {
- i2c->fifo = EC_PADDING_BYTE;
- }
- }
- /* Set the threshold for TX, the threshold is a four bit field. */
- i2c->tx_ctrl0 = ((i2c->tx_ctrl0 & ~(MXC_F_I2C_TX_CTRL0_TX_THRESH)) |
- (2 << MXC_F_I2C_TX_CTRL0_TX_THRESH_POS));
- /* Enable interrupts of interest. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_TX_THRESH | MXC_F_I2C_INT_EN0_DONE |
- I2C_ERROR | MXC_F_I2C_INT_EN0_ADDR_MATCH;
-}
-
-/**
- * i2c_slave_service_write() - Services the Master I2C write to the slave.
- * @i2c: I2C peripheral pointer.
- * @req: Pointer to the request info.
- */
-static void i2c_slave_service_write(mxc_i2c_regs_t *i2c, i2c_req_t *req)
-{
- /* Clear all flags except address matching and done. */
- i2c->int_fl0 = i2c->int_fl0 & ~(MXC_F_I2C_INT_FL0_ADDR_MATCH |
- MXC_F_I2C_INT_FL0_MAMI_MASK | MXC_F_I2C_INT_FL0_DONE);
- i2c->int_fl1 = i2c->int_fl1;
- /* Read out any data in the RX FIFO. */
- while (!(i2c->status & MXC_F_I2C_STATUS_RX_EMPTY)) {
- *(req->rx_data)++ = i2c->fifo;
- req->received_count++;
- }
- /* Set the RX threshold interrupt level. */
- i2c->rx_ctrl0 = ((i2c->rx_ctrl0 &
- ~(MXC_F_I2C_RX_CTRL0_RX_THRESH)) |
- (MXC_I2C_FIFO_DEPTH - 1)
- << MXC_F_I2C_RX_CTRL0_RX_THRESH_POS);
- /* Enable interrupts of interest. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_RX_THRESH | MXC_F_I2C_INT_EN0_DONE |
- I2C_ERROR | MXC_F_I2C_INT_EN0_ADDR_MATCH;
-}
-
-/**
- * i2c_slave_handler() - I2C interrupt handler.
- * @i2c: Base address of the I2C module.
- *
- * This function should be called by the application from the interrupt
- * handler if I2C interrupts are enabled. Alternately, this function
- * can be periodically called by the application if I2C interrupts are
- * disabled.
- */
-static void i2c_slave_handler(mxc_i2c_regs_t *i2c)
-{
- i2c_req_t *req;
-
- /* Get the request context for this interrupt. */
- req = states[MXC_I2C_GET_IDX(i2c)].req;
-
-
- /* Check for an address match flag. */
- if ((req->expecting_start) && (i2c->int_fl0 & MXC_F_I2C_INT_FL0_ADDR_MATCH)) {
- req->expecting_done = true;
- req->expecting_start = false;
- /*
- * Save the address match index to identify
- * targeted slave address.
- */
- req->addr_match_flag =
- (i2c->int_fl0 & MXC_F_I2C_INT_FL0_MAMI_MASK) >>
- MXC_F_I2C_INT_FL0_MAMI_POS;
-
- /* Clear all interrupt flags except a done interrupt. */
- i2c->int_fl0 = i2c->int_fl0 & ~(MXC_F_I2C_INT_FL0_DONE);
- i2c->int_fl1 = i2c->int_fl1;
-
- /* Only enable done, error and address match interrupts. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_DONE |
- I2C_ERROR | MXC_F_I2C_INT_EN0_ADDR_MATCH;
-
- /* Check if Master is writing to the slave. */
- if (!(i2c->ctrl & MXC_F_I2C_CTRL_READ)) {
- /* I2C Master is writing to the slave. */
- req->rx_data = host_buffer;
- req->tx_data = host_buffer;
- req->tx_remain = -1; /* Nothing to send yet. */
- /* Clear the RX (receive from I2C Master) byte counter. */
- req->received_count = 0;
- req->state = I2C_SLAVE_ADDR_MATCH_WRITE;
- /* The Master is writing, there can not be a response pending yet. */
- req->response_pending = false;
- /* Set the RX threshold interrupt level. */
- i2c->rx_ctrl0 = ((i2c->rx_ctrl0 &
- ~(MXC_F_I2C_RX_CTRL0_RX_THRESH)) |
- (MXC_I2C_FIFO_DEPTH - 2)
- << MXC_F_I2C_RX_CTRL0_RX_THRESH_POS);
- } else {
- /* The Master is reading from the slave. */
- /* Start transmitting to the Master from the start of buffer. */
- req->tx_data = host_buffer;
- req->state = I2C_SLAVE_ADDR_MATCH_READ;
- /* Set the threshold for TX, the threshold is a four bit field. */
- i2c->tx_ctrl0 = ((i2c->tx_ctrl0 & ~(MXC_F_I2C_TX_CTRL0_TX_THRESH)) |
- (2 << MXC_F_I2C_TX_CTRL0_TX_THRESH_POS));
-#ifdef CONFIG_BOARD_I2C_ADDR_FLAGS
- /*
- * If this is a board address match and there is not
- * already a pending response to the I2C Master then
- * fulfill this board read request.
- */
- if ((req->response_pending == 0) &&
- (req->addr_match_flag != 0x1)) {
- i2c_process_board_command(
- 1, CONFIG_BOARD_I2C_ADDR_FLAGS, 0);
- }
-#endif /* CONFIG_BOARD_I2C_ADDR_FLAGS */
- }
- /* Only enable done, error and address match interrupts. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_DONE |
- I2C_ERROR | MXC_F_I2C_INT_EN0_ADDR_MATCH;
- /* Inhibit sleep mode when addressed until STOPF flag is set. */
- disable_sleep(SLEEP_MASK_I2C_PERIPHERAL);
- }
-
- /* Check for DONE interrupt. */
- if ((req->expecting_done) && (i2c->int_fl0 & MXC_F_I2C_INT_FL0_DONE)) {
- req->expecting_start = true;
- req->expecting_done = false;
- /* Clear all interrupts except a possible address match. */
- i2c->int_fl0 = i2c->int_fl0 & ~(MXC_F_I2C_INT_FL0_ADDR_MATCH |
- MXC_F_I2C_INT_FL0_MAMI_MASK);
- i2c->int_fl1 = i2c->int_fl1;
-
- /* Only enable done, error and address match interrupts. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_DONE |
- I2C_ERROR | MXC_F_I2C_INT_EN0_ADDR_MATCH;
- i2c->int_en1 = 0;
- /* If this was a DONE after a write then read the fifo until empty. */
- if (req->state == I2C_SLAVE_ADDR_MATCH_WRITE) {
- /* Read out any data in the RX FIFO. */
- while (!(i2c->status & MXC_F_I2C_STATUS_RX_EMPTY)) {
- *(req->rx_data)++ = i2c->fifo;
- req->received_count++;
- }
- }
- /* Manually clear the RX FIFO. */
- i2c->rx_ctrl0 |= MXC_F_I2C_RX_CTRL0_RX_FLUSH;
- /* Manually clear the TX FIFO. */
- i2c->tx_ctrl0 |= MXC_F_I2C_TX_CTRL0_TX_FLUSH;
-
- /* Process the Master write that just finished. */
- i2c_slave_service(req);
-
- /* No longer inhibit deep sleep after done. */
- enable_sleep(SLEEP_MASK_I2C_PERIPHERAL);
- }
-
- /* Check for an I2C Master Read or Write. */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Clear the error interrupt. */
- i2c->int_fl0 = I2C_ERROR;
- i2c->int_en0 = 0;
- /* Manually clear the TXFIFO. */
- i2c->tx_ctrl0 |= MXC_F_I2C_TX_CTRL0_TX_FLUSH;
- /* Disable and clear interrupts. */
- i2c->int_en0 = 0;
- i2c->int_en1 = 0;
- i2c->int_fl0 = i2c->int_fl0;
- i2c->int_fl1 = i2c->int_fl1;
- /* Cycle the I2C peripheral enable on error. */
- i2c->ctrl = 0;
- i2c->ctrl = MXC_F_I2C_CTRL_I2C_EN;
- } else if (req->state == I2C_SLAVE_ADDR_MATCH_READ) {
- /* Service a read request from the I2C Master. */
- i2c_slave_service_read(i2c, req);
- } else if (req->state == I2C_SLAVE_ADDR_MATCH_WRITE) {
- /* Service a write request from the I2C Master. */
- i2c_slave_service_write(i2c, req);
- }
-
-}
-
-/**
- * init_i2cs() - Async Handler for I2C Slave driver.
- * @port: I2C port number to initialize.
- */
-void init_i2cs(int port)
-{
- int error;
-
- error = i2c_init_peripheral(i2c_bus_ports[port], I2C_STD_MODE);
- if (error != EC_SUCCESS) {
- while (1)
- ;
- }
- /* Prepare for interrupt driven slave requests. */
- req_slave.addr = CONFIG_HOSTCMD_I2C_ADDR_FLAGS;
- req_slave.tx_data = host_buffer; /* Transmitted to host. */
- req_slave.tx_remain = -1;
- req_slave.rx_data = host_buffer; /* Received from host. */
- req_slave.restart = 0;
- req_slave.response_pending = false;
- states[port].req = &req_slave;
- error = i2c_slave_async(i2c_bus_ports[port], &req_slave);
- if (error != EC_SUCCESS) {
- while (1)
- ;
- }
- states[port].req->expecting_done = false;
- states[port].req->expecting_start = true;
- task_enable_irq(i2c_bus_irqs[port]);
-}
-
-/**
- * i2c_slave_async() - Slave Read and Write Asynchronous.
- * @i2c: Pointer to I2C regs.
- * @req: Request for an I2C transaction.
- *
- * Return EC_SUCCESS if successful, otherwise returns a common error code.
- */
-static int i2c_slave_async(mxc_i2c_regs_t *i2c, i2c_req_t *req)
-{
- /* Make sure the I2C has been initialized. */
- if (!(i2c->ctrl & MXC_F_I2C_CTRL_I2C_EN))
- return EC_ERROR_UNKNOWN;
- /* Disable master mode. */
- i2c->ctrl &= ~(MXC_F_I2C_CTRL_MST);
- /* Set the Slave Address in the I2C peripheral register. */
- i2c->slave_addr = req->addr;
- /* Clear the receive count from the I2C Master. */
- req->received_count = 0;
- /* Disable and clear the interrupts. */
- i2c->int_en0 = 0;
- i2c->int_en1 = 0;
- i2c->int_fl0 = i2c->int_fl0;
- i2c->int_fl1 = i2c->int_fl1;
-
- /* Set the RX threshold interrupt level. */
- i2c->rx_ctrl0 = ((i2c->rx_ctrl0 &
- ~(MXC_F_I2C_RX_CTRL0_RX_THRESH)) |
- (MXC_I2C_FIFO_DEPTH - 2)
- << MXC_F_I2C_RX_CTRL0_RX_THRESH_POS);
-
- /* Only enable the I2C Address match interrupt. */
- i2c->int_en0 = MXC_F_I2C_INT_EN0_ADDR_MATCH;
-
- return EC_SUCCESS;
-}
-
-#ifdef CONFIG_BOARD_I2C_ADDR_FLAGS
-
-static void i2c_send_board_response(int len)
-{
- /* Set the number of bytes to send to the I2C master. */
- req_slave.tx_remain = len;
- /* Indicate that there is a response pending from the slave. */
- req_slave.response_pending = true;
-}
-
-
-static void i2c_process_board_command(int read, int addr, int len)
-{
- board_i2c_process(read, addr, len, &host_buffer[0],
- i2c_send_board_response);
-}
-#endif /* CONFIG_BOARD_I2C_ADDR_FLAGS */
-#endif /* CONFIG_HOSTCMD_I2C_ADDR_FLAGS */
-
-/**
- * i2c_set_speed() - Set the transfer speed of the selected I2C.
- * @i2c: Pointer to I2C peripheral.
- * @i2cspeed: Speed to set.
- *
- * Return EC_SUCCESS, or non-zero if error.
- */
-static int i2c_set_speed(mxc_i2c_regs_t *i2c, i2c_speed_t i2cspeed)
-{
- uint32_t ticks;
- uint32_t ticks_lo;
- uint32_t ticks_hi;
- uint32_t time_pclk;
- uint32_t target_bus_freq;
- uint32_t time_scl_min;
- uint32_t clock_low_min;
- uint32_t clock_high_min;
- uint32_t clock_min;
-
- if (i2cspeed == I2C_HS_MODE) {
- /* Compute dividers for high speed mode. */
- time_pclk = 1000000 / (PeripheralClock / 1000);
-
- target_bus_freq = i2cspeed;
- if (target_bus_freq < 1000) {
- return EC_ERROR_INVAL;
- }
-
- time_scl_min = 1000000 / (target_bus_freq / 1000);
- clock_low_min =
- ((T_LOW_MIN + T_F_MAX_HS + (time_pclk - 1) - T_AF_MIN) /
- time_pclk) - 1;
- clock_high_min = ((T_HIGH_MIN + T_R_MAX_HS + (time_pclk - 1) -
- T_AF_MIN) /
- time_pclk) - 1;
- clock_min = ((time_scl_min + (time_pclk - 1)) / time_pclk) - 2;
-
- ticks_lo = (clock_low_min > (clock_min - clock_high_min))
- ? (clock_low_min)
- : (clock_min - clock_high_min);
- ticks_hi = clock_high_min;
-
- if ((ticks_lo > (MXC_F_I2C_HS_CLK_HS_CLK_LO >>
- MXC_F_I2C_HS_CLK_HS_CLK_LO_POS)) ||
- (ticks_hi > (MXC_F_I2C_HS_CLK_HS_CLK_HI >>
- MXC_F_I2C_HS_CLK_HS_CLK_HI_POS))) {
- return EC_ERROR_INVAL;
- }
-
- /* Write results to destination registers. */
- i2c->hs_clk = (ticks_lo << MXC_F_I2C_HS_CLK_HS_CLK_LO_POS) |
- (ticks_hi << MXC_F_I2C_HS_CLK_HS_CLK_HI_POS);
-
- /* Still need to load dividers for the preamble that each
- * high-speed transaction starts with. Switch setting to fast
- * mode and fall out of if statement.
- */
- i2cspeed = I2C_FAST_MODE;
- }
-
- /* Get the number of periph clocks needed to achieve selected speed. */
- ticks = PeripheralClock / i2cspeed;
-
- /* For a 50% duty cycle, half the ticks will be spent high and half will
- * be low.
- */
- ticks_hi = (ticks >> 1) - 1;
- ticks_lo = (ticks >> 1) - 1;
-
- /* Account for rounding error in odd tick counts. */
- if (ticks & 1) {
- ticks_hi++;
- }
-
- /* Will results fit into 9 bit registers? (ticks_hi will always be >=
- * ticks_lo. No need to check ticks_lo.)
- */
- if (ticks_hi > 0x1FF) {
- return EC_ERROR_INVAL;
- }
-
- /* 0 is an invalid value for the destination registers. (ticks_hi will
- * always be >= ticks_lo. No need to check ticks_hi.)
- */
- if (ticks_lo == 0) {
- return EC_ERROR_INVAL;
- }
-
- /* Write results to destination registers. */
- i2c->clk_lo = ticks_lo;
- i2c->clk_hi = ticks_hi;
-
- return EC_SUCCESS;
-}
-
-/**
- * i2c_init_peripheral() - Initialize and enable I2C.
- * @i2c: Pointer to I2C peripheral registers.
- * @i2cspeed: Desired speed (I2C mode).
- * @sys_cfg: System configuration object.
- *
- * Return EC_SUCCESS, or non-zero if error.
- */
-static int i2c_init_peripheral(mxc_i2c_regs_t *i2c, i2c_speed_t i2cspeed)
-{
- /**
- * Always disable the HW autoflush on data NACK and let the SW handle
- * the flushing.
- */
- i2c->tx_ctrl0 |= 0x20;
-
- i2c->ctrl = 0; /* Clear configuration bits. */
- i2c->ctrl = MXC_F_I2C_CTRL_I2C_EN; /* Enable I2C. */
- i2c->master_ctrl = 0; /* Clear master configuration bits. */
- i2c->status = 0; /* Clear status bits. */
-
- i2c->ctrl = 0; /* Clear configuration bits. */
- i2c->ctrl = MXC_F_I2C_CTRL_I2C_EN; /* Enable I2C. */
- i2c->master_ctrl = 0; /* Clear master configuration bits. */
- i2c->status = 0; /* Clear status bits. */
-
- /* Check for HS mode. */
- if (i2cspeed == I2C_HS_MODE) {
- i2c->ctrl |= MXC_F_I2C_CTRL_HS_MODE; /* Enable HS mode. */
- }
-
- /* Disable and clear interrupts. */
- i2c->int_en0 = 0;
- i2c->int_en1 = 0;
- i2c->int_fl0 = i2c->int_fl0;
- i2c->int_fl1 = i2c->int_fl1;
-
- i2c->timeout = 0x0; /* Set timeout. */
- i2c->rx_ctrl0 |= MXC_F_I2C_RX_CTRL0_RX_FLUSH; /* Clear the RX FIFO. */
- i2c->tx_ctrl0 |= MXC_F_I2C_TX_CTRL0_TX_FLUSH; /* Clear the TX FIFO. */
-
- return i2c_set_speed(i2c, i2cspeed);
-}
-
-/**
- * i2c_master_write()
- * @i2c: Pointer to I2C regs.
- * @addr: I2C 7-bit Address left aligned, bit 7 to bit 1.
- * Only supports 7-bit addressing. LSb of the given address
- * will be used as the read/write bit, the \p addr <b>will
- * not be shifted. Used for both master and
- * slave transactions.
- * @data: Data to be written.
- * @len: Number of bytes to Write.
- * @restart: 0 to send a stop bit at the end of the transaction,
- * otherwise send a restart.
- *
- * Will block until transaction is complete.
- *
- * Return EC_SUCCESS, or non-zero if error.
- */
-static int i2c_master_write(mxc_i2c_regs_t *i2c, uint8_t addr, int start,
- int stop, const uint8_t *data, int len, int restart)
-{
- if (len == 0) {
- return EC_SUCCESS;
- }
-
- /* Clear the interrupt flag. */
- i2c->int_fl0 = i2c->int_fl0;
-
- /* Make sure the I2C has been initialized. */
- if (!(i2c->ctrl & MXC_F_I2C_CTRL_I2C_EN)) {
- return EC_ERROR_UNKNOWN;
- }
-
- /* Enable master mode. */
- i2c->ctrl |= MXC_F_I2C_CTRL_MST;
-
- /* Load FIFO with slave address for WRITE and as much data as we can. */
- while (i2c->status & MXC_F_I2C_STATUS_TX_FULL) {
- }
-
- if (start) {
- /**
- * The slave address is right-aligned, bits 6 to 0, shift
- * to the left and make room for the write bit.
- */
- i2c->fifo = (addr << 1) & ~(0x1);
- }
-
- while ((len > 0) && !(i2c->status & MXC_F_I2C_STATUS_TX_FULL)) {
- i2c->fifo = *data++;
- len--;
- }
- /* Generate Start signal. */
- if (start) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_START;
- }
-
- /* Write remaining data to FIFO. */
- while (len > 0) {
- /* Check for errors. */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit. */
- i2c->master_ctrl &= ~(MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
-
- if (!(i2c->status & MXC_F_I2C_STATUS_TX_FULL)) {
- i2c->fifo = *data++;
- len--;
- }
- }
- /* Check if Repeated Start requested. */
- if (restart) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_RESTART;
- } else {
- if (stop) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- }
- }
-
- if (stop) {
- /* Wait for Done. */
- while (!(i2c->int_fl0 & MXC_F_I2C_INT_FL0_DONE)) {
- /* Check for errors */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit */
- i2c->master_ctrl &=
- ~(MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
- }
- /* Clear Done interrupt flag. */
- i2c->int_fl0 = MXC_F_I2C_INT_FL0_DONE;
- }
-
- /* Wait for Stop if requested and there is no restart. */
- if (stop && !restart) {
- while (!(i2c->int_fl0 & MXC_F_I2C_INT_FL0_STOP)) {
- /* Check for errors */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit */
- i2c->master_ctrl &=
- ~(MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
- }
- /* Clear stop interrupt flag. */
- i2c->int_fl0 = MXC_F_I2C_INT_FL0_STOP;
- }
-
- /* Check for errors. */
- if (i2c->int_fl0 & I2C_ERROR) {
- return EC_ERROR_UNKNOWN;
- }
-
- return EC_SUCCESS;
-}
-
-/**
- * i2c_master_read()
- * @i2c: Pointer to I2C regs.
- * @addr: I2C 7-bit Address right aligned, bit 6 to bit 0.
- * @data: Data to be written.
- * @len: Number of bytes to Write.
- * @restart: 0 to send a stop bit at the end of the transaction,
- * otherwise send a restart.
- *
- * Will block until transaction is complete.
- *
- * Return: EC_SUCCESS if successful, otherwise returns a common error code
- */
-static int i2c_master_read(mxc_i2c_regs_t *i2c, uint8_t addr, int start,
- int stop, uint8_t *data, int len, int restart)
-{
- volatile int length = len;
- int interactive_receive_mode;
-
- if (len == 0) {
- return EC_SUCCESS;
- }
-
- if (len > 255) {
- return EC_ERROR_INVAL;
- }
-
- /* Clear the interrupt flag. */
- i2c->int_fl0 = i2c->int_fl0;
-
- /* Make sure the I2C has been initialized. */
- if (!(i2c->ctrl & MXC_F_I2C_CTRL_I2C_EN)) {
- return EC_ERROR_UNKNOWN;
- }
-
- /* Enable master mode. */
- i2c->ctrl |= MXC_F_I2C_CTRL_MST;
-
- if (stop) {
- /* Set receive count. */
- i2c->ctrl &= ~MXC_F_I2C_CTRL_RX_MODE;
- i2c->rx_ctrl1 = len;
- interactive_receive_mode = 0;
- } else {
- i2c->ctrl |= MXC_F_I2C_CTRL_RX_MODE;
- i2c->rx_ctrl1 = 1;
- interactive_receive_mode = 1;
- }
-
- /* Load FIFO with slave address. */
- if (start) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_START;
- while (i2c->status & MXC_F_I2C_STATUS_TX_FULL) {
- }
- /**
- * The slave address is right-aligned, bits 6 to 0, shift
- * to the left and make room for the read bit.
- */
- i2c->fifo = ((addr << 1) | 1);
- }
-
- /* Wait for all data to be received or error. */
- while (length > 0) {
- /* Check for errors */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit. */
- i2c->master_ctrl &= ~(MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
-
- /* If in interactive receive mode then ack each received byte. */
- if (interactive_receive_mode) {
- while (!(i2c->int_fl0 & MXC_F_I2C_INT_EN0_RX_MODE))
- ;
- if (i2c->int_fl0 & MXC_F_I2C_INT_EN0_RX_MODE) {
- /* Read the data. */
- *data++ = i2c->fifo;
- length--;
- /* Clear the bit. */
- if (length != 1) {
- i2c->int_fl0 =
- MXC_F_I2C_INT_EN0_RX_MODE;
- }
- }
- } else {
- if (!(i2c->status & MXC_F_I2C_STATUS_RX_EMPTY)) {
- *data++ = i2c->fifo;
- length--;
- }
- }
- }
-
- if (restart) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_RESTART;
- } else {
- if (stop) {
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- }
- }
-
- /* Wait for Done. */
- if (stop) {
- while (!(i2c->int_fl0 & MXC_F_I2C_INT_FL0_DONE)) {
- /* Check for errors. */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit. */
- i2c->master_ctrl &=
- ~(MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |= MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
- }
- /* Clear Done interrupt flag. */
- i2c->int_fl0 = MXC_F_I2C_INT_FL0_DONE;
- }
-
- /* Wait for Stop. */
- if (!restart) {
- if (stop) {
- while (!(i2c->int_fl0 & MXC_F_I2C_INT_FL0_STOP)) {
- /* Check for errors. */
- if (i2c->int_fl0 & I2C_ERROR) {
- /* Set the stop bit. */
- i2c->master_ctrl &= ~(
- MXC_F_I2C_MASTER_CTRL_RESTART);
- i2c->master_ctrl |=
- MXC_F_I2C_MASTER_CTRL_STOP;
- return EC_ERROR_UNKNOWN;
- }
- }
- /* Clear Stop interrupt flag. */
- i2c->int_fl0 = MXC_F_I2C_INT_FL0_STOP;
- }
- }
-
- /* Check for errors. */
- if (i2c->int_fl0 & I2C_ERROR) {
- return EC_ERROR_UNKNOWN;
- }
- return EC_SUCCESS;
-}
diff --git a/chip/max32660/i2c_regs.h b/chip/max32660/i2c_regs.h
deleted file mode 100644
index 8cd2fd8868..0000000000
--- a/chip/max32660/i2c_regs.h
+++ /dev/null
@@ -1,1627 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the I2C Peripheral */
-
-#ifndef _I2C_REGS_H_
-#define _I2C_REGS_H_
-
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/**
- * Registers, Bit Masks and Bit Positions for the I2C Peripheral Module.
- */
-
-/**
- * typedef mxc_i2c_regs_t - Structure type to access the I2C Registers.
- */
-typedef struct {
- __IO uint32_t ctrl; /**< <tt>\b 0x00:</tt> I2C CTRL Register */
- __IO uint32_t status; /**< <tt>\b 0x04:</tt> I2C STATUS Register */
- __IO uint32_t int_fl0; /**< <tt>\b 0x08:</tt> I2C INT_FL0 Register */
- __IO uint32_t int_en0; /**< <tt>\b 0x0C:</tt> I2C INT_EN0 Register */
- __IO uint32_t int_fl1; /**< <tt>\b 0x10:</tt> I2C INT_FL1 Register */
- __IO uint32_t int_en1; /**< <tt>\b 0x14:</tt> I2C INT_EN1 Register */
- __IO uint32_t fifo_len; /**< <tt>\b 0x18:</tt> I2C FIFO_LEN Register */
- __IO uint32_t rx_ctrl0; /**< <tt>\b 0x1C:</tt> I2C RX_CTRL0 Register */
- __IO uint32_t rx_ctrl1; /**< <tt>\b 0x20:</tt> I2C RX_CTRL1 Register */
- __IO uint32_t tx_ctrl0; /**< <tt>\b 0x24:</tt> I2C TX_CTRL0 Register */
- __IO uint32_t tx_ctrl1; /**< <tt>\b 0x28:</tt> I2C TX_CTRL1 Register */
- __IO uint32_t fifo; /**< <tt>\b 0x2C:</tt> I2C FIFO Register */
- __IO uint32_t
- master_ctrl; /**< <tt>\b 0x30:</tt> I2C MASTER_CTRL Register */
- __IO uint32_t clk_lo; /**< <tt>\b 0x34:</tt> I2C CLK_LO Register */
- __IO uint32_t clk_hi; /**< <tt>\b 0x38:</tt> I2C CLK_HI Register */
- __IO uint32_t hs_clk; /**< <tt>\b 0x3C:</tt> I2C HS_CLK Register */
- __IO uint32_t timeout; /**< <tt>\b 0x40:</tt> I2C TIMEOUT Register */
- __IO uint32_t
- slave_addr; /**< <tt>\b 0x44:</tt> I2C SLAVE_ADDR Register */
- __IO uint32_t dma; /**< <tt>\b 0x48:</tt> I2C DMA Register */
-} mxc_i2c_regs_t;
-
-/* Register offsets for module I2C */
-/**
- * I2C Peripheral Register Offsets from the I2C Base Peripheral Address.
- */
-#define MXC_R_I2C_CTRL \
- ((uint32_t)0x00000000UL) /**< Offset from I2C Base Address: <tt> \
- 0x0000</tt> */
-#define MXC_R_I2C_STATUS \
- ((uint32_t)0x00000004UL) /**< Offset from I2C Base Address: <tt> \
- 0x0004</tt> */
-#define MXC_R_I2C_INT_FL0 \
- ((uint32_t)0x00000008UL) /**< Offset from I2C Base Address: <tt> \
- 0x0008</tt> */
-#define MXC_R_I2C_INT_EN0 \
- ((uint32_t)0x0000000CUL) /**< Offset from I2C Base Address: <tt> \
- 0x000C</tt> */
-#define MXC_R_I2C_INT_FL1 \
- ((uint32_t)0x00000010UL) /**< Offset from I2C Base Address: <tt> \
- 0x0010</tt> */
-#define MXC_R_I2C_INT_EN1 \
- ((uint32_t)0x00000014UL) /**< Offset from I2C Base Address: <tt> \
- 0x0014</tt> */
-#define MXC_R_I2C_FIFO_LEN \
- ((uint32_t)0x00000018UL) /**< Offset from I2C Base Address: <tt> \
- 0x0018</tt> */
-#define MXC_R_I2C_RX_CTRL0 \
- ((uint32_t)0x0000001CUL) /**< Offset from I2C Base Address: <tt> \
- 0x001C</tt> */
-#define MXC_R_I2C_RX_CTRL1 \
- ((uint32_t)0x00000020UL) /**< Offset from I2C Base Address: <tt> \
- 0x0020</tt> */
-#define MXC_R_I2C_TX_CTRL0 \
- ((uint32_t)0x00000024UL) /**< Offset from I2C Base Address: <tt> \
- 0x0024</tt> */
-#define MXC_R_I2C_TX_CTRL1 \
- ((uint32_t)0x00000028UL) /**< Offset from I2C Base Address: <tt> \
- 0x0028</tt> */
-#define MXC_R_I2C_FIFO \
- ((uint32_t)0x0000002CUL) /**< Offset from I2C Base Address: <tt> \
- 0x002C</tt> */
-#define MXC_R_I2C_MASTER_CTRL \
- ((uint32_t)0x00000030UL) /**< Offset from I2C Base Address: <tt> \
- 0x0030</tt> */
-#define MXC_R_I2C_CLK_LO \
- ((uint32_t)0x00000034UL) /**< Offset from I2C Base Address: <tt> \
- 0x0034</tt> */
-#define MXC_R_I2C_CLK_HI \
- ((uint32_t)0x00000038UL) /**< Offset from I2C Base Address: <tt> \
- 0x0038</tt> */
-#define MXC_R_I2C_HS_CLK \
- ((uint32_t)0x0000003CUL) /**< Offset from I2C Base Address: <tt> \
- 0x003C</tt> */
-#define MXC_R_I2C_TIMEOUT \
- ((uint32_t)0x00000040UL) /**< Offset from I2C Base Address: <tt> \
- 0x0040</tt> */
-#define MXC_R_I2C_SLAVE_ADDR \
- ((uint32_t)0x00000044UL) /**< Offset from I2C Base Address: <tt> \
- 0x0044</tt> */
-#define MXC_R_I2C_DMA \
- ((uint32_t)0x00000048UL) /**< Offset from I2C Base Address: <tt> \
- 0x0048</tt> */
-
-/**
- * Control Register0.
- */
-#define MXC_F_I2C_CTRL_I2C_EN_POS 0 /**< CTRL_I2C_EN Position */
-#define MXC_F_I2C_CTRL_I2C_EN \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_CTRL_I2C_EN_POS)) /**< CTRL_I2C_EN Mask */
-#define MXC_V_I2C_CTRL_I2C_EN_DIS \
- ((uint32_t)0x0UL) /**< CTRL_I2C_EN_DIS Value */
-#define MXC_S_I2C_CTRL_I2C_EN_DIS \
- (MXC_V_I2C_CTRL_I2C_EN_DIS \
- << MXC_F_I2C_CTRL_I2C_EN_POS) /**< CTRL_I2C_EN_DIS Setting */
-#define MXC_V_I2C_CTRL_I2C_EN_EN \
- ((uint32_t)0x1UL) /**< CTRL_I2C_EN_EN Value \
- */
-#define MXC_S_I2C_CTRL_I2C_EN_EN \
- (MXC_V_I2C_CTRL_I2C_EN_EN \
- << MXC_F_I2C_CTRL_I2C_EN_POS) /**< CTRL_I2C_EN_EN Setting */
-
-#define MXC_F_I2C_CTRL_MST_POS 1 /**< CTRL_MST Position */
-#define MXC_F_I2C_CTRL_MST \
- ((uint32_t)(0x1UL << MXC_F_I2C_CTRL_MST_POS)) /**< CTRL_MST Mask */
-#define MXC_V_I2C_CTRL_MST_SLAVE_MODE \
- ((uint32_t)0x0UL) /**< CTRL_MST_SLAVE_MODE Value */
-#define MXC_S_I2C_CTRL_MST_SLAVE_MODE \
- (MXC_V_I2C_CTRL_MST_SLAVE_MODE \
- << MXC_F_I2C_CTRL_MST_POS) /**< CTRL_MST_SLAVE_MODE Setting */
-#define MXC_V_I2C_CTRL_MST_MASTER_MODE \
- ((uint32_t)0x1UL) /**< CTRL_MST_MASTER_MODE Value */
-#define MXC_S_I2C_CTRL_MST_MASTER_MODE \
- (MXC_V_I2C_CTRL_MST_MASTER_MODE \
- << MXC_F_I2C_CTRL_MST_POS) /**< CTRL_MST_MASTER_MODE Setting */
-
-#define MXC_F_I2C_CTRL_GEN_CALL_ADDR_POS 2 /**< CTRL_GEN_CALL_ADDR Position */
-#define MXC_F_I2C_CTRL_GEN_CALL_ADDR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_CTRL_GEN_CALL_ADDR_POS)) /**< CTRL_GEN_CALL_ADDR \
- Mask */
-#define MXC_V_I2C_CTRL_GEN_CALL_ADDR_DIS \
- ((uint32_t)0x0UL) /**< CTRL_GEN_CALL_ADDR_DIS Value */
-#define MXC_S_I2C_CTRL_GEN_CALL_ADDR_DIS \
- (MXC_V_I2C_CTRL_GEN_CALL_ADDR_DIS \
- << MXC_F_I2C_CTRL_GEN_CALL_ADDR_POS) /**< CTRL_GEN_CALL_ADDR_DIS \
- Setting */
-#define MXC_V_I2C_CTRL_GEN_CALL_ADDR_EN \
- ((uint32_t)0x1UL) /**< CTRL_GEN_CALL_ADDR_EN Value */
-#define MXC_S_I2C_CTRL_GEN_CALL_ADDR_EN \
- (MXC_V_I2C_CTRL_GEN_CALL_ADDR_EN \
- << MXC_F_I2C_CTRL_GEN_CALL_ADDR_POS) /**< CTRL_GEN_CALL_ADDR_EN \
- Setting */
-
-#define MXC_F_I2C_CTRL_RX_MODE_POS 3 /**< CTRL_RX_MODE Position */
-#define MXC_F_I2C_CTRL_RX_MODE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_CTRL_RX_MODE_POS)) /**< CTRL_RX_MODE Mask */
-#define MXC_V_I2C_CTRL_RX_MODE_DIS \
- ((uint32_t)0x0UL) /**< CTRL_RX_MODE_DIS Value */
-#define MXC_S_I2C_CTRL_RX_MODE_DIS \
- (MXC_V_I2C_CTRL_RX_MODE_DIS \
- << MXC_F_I2C_CTRL_RX_MODE_POS) /**< CTRL_RX_MODE_DIS Setting */
-#define MXC_V_I2C_CTRL_RX_MODE_EN \
- ((uint32_t)0x1UL) /**< CTRL_RX_MODE_EN Value */
-#define MXC_S_I2C_CTRL_RX_MODE_EN \
- (MXC_V_I2C_CTRL_RX_MODE_EN \
- << MXC_F_I2C_CTRL_RX_MODE_POS) /**< CTRL_RX_MODE_EN Setting */
-
-#define MXC_F_I2C_CTRL_RX_MODE_ACK_POS 4 /**< CTRL_RX_MODE_ACK Position */
-#define MXC_F_I2C_CTRL_RX_MODE_ACK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_CTRL_RX_MODE_ACK_POS)) /**< CTRL_RX_MODE_ACK \
- Mask */
-#define MXC_V_I2C_CTRL_RX_MODE_ACK_ACK \
- ((uint32_t)0x0UL) /**< CTRL_RX_MODE_ACK_ACK Value */
-#define MXC_S_I2C_CTRL_RX_MODE_ACK_ACK \
- (MXC_V_I2C_CTRL_RX_MODE_ACK_ACK \
- << MXC_F_I2C_CTRL_RX_MODE_ACK_POS) /**< CTRL_RX_MODE_ACK_ACK Setting \
- */
-#define MXC_V_I2C_CTRL_RX_MODE_ACK_NACK \
- ((uint32_t)0x1UL) /**< CTRL_RX_MODE_ACK_NACK Value */
-#define MXC_S_I2C_CTRL_RX_MODE_ACK_NACK \
- (MXC_V_I2C_CTRL_RX_MODE_ACK_NACK \
- << MXC_F_I2C_CTRL_RX_MODE_ACK_POS) /**< CTRL_RX_MODE_ACK_NACK Setting \
- */
-
-#define MXC_F_I2C_CTRL_SCL_OUT_POS 6 /**< CTRL_SCL_OUT Position */
-#define MXC_F_I2C_CTRL_SCL_OUT \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_CTRL_SCL_OUT_POS)) /**< CTRL_SCL_OUT Mask */
-#define MXC_V_I2C_CTRL_SCL_OUT_DRIVE_SCL_LOW \
- ((uint32_t)0x0UL) /**< CTRL_SCL_OUT_DRIVE_SCL_LOW Value */
-#define MXC_S_I2C_CTRL_SCL_OUT_DRIVE_SCL_LOW \
- (MXC_V_I2C_CTRL_SCL_OUT_DRIVE_SCL_LOW \
- << MXC_F_I2C_CTRL_SCL_OUT_POS) /**< CTRL_SCL_OUT_DRIVE_SCL_LOW \
- Setting */
-#define MXC_V_I2C_CTRL_SCL_OUT_RELEASE_SCL \
- ((uint32_t)0x1UL) /**< CTRL_SCL_OUT_RELEASE_SCL Value */
-#define MXC_S_I2C_CTRL_SCL_OUT_RELEASE_SCL \
- (MXC_V_I2C_CTRL_SCL_OUT_RELEASE_SCL \
- << MXC_F_I2C_CTRL_SCL_OUT_POS) /**< CTRL_SCL_OUT_RELEASE_SCL Setting \
- */
-
-#define MXC_F_I2C_CTRL_SDA_OUT_POS 7 /**< CTRL_SDA_OUT Position */
-#define MXC_F_I2C_CTRL_SDA_OUT \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_CTRL_SDA_OUT_POS)) /**< CTRL_SDA_OUT Mask */
-#define MXC_V_I2C_CTRL_SDA_OUT_DRIVE_SDA_LOW \
- ((uint32_t)0x0UL) /**< CTRL_SDA_OUT_DRIVE_SDA_LOW Value */
-#define MXC_S_I2C_CTRL_SDA_OUT_DRIVE_SDA_LOW \
- (MXC_V_I2C_CTRL_SDA_OUT_DRIVE_SDA_LOW \
- << MXC_F_I2C_CTRL_SDA_OUT_POS) /**< CTRL_SDA_OUT_DRIVE_SDA_LOW \
- Setting */
-#define MXC_V_I2C_CTRL_SDA_OUT_RELEASE_SDA \
- ((uint32_t)0x1UL) /**< CTRL_SDA_OUT_RELEASE_SDA Value */
-#define MXC_S_I2C_CTRL_SDA_OUT_RELEASE_SDA \
- (MXC_V_I2C_CTRL_SDA_OUT_RELEASE_SDA \
- << MXC_F_I2C_CTRL_SDA_OUT_POS) /**< CTRL_SDA_OUT_RELEASE_SDA Setting \
- */
-
-#define MXC_F_I2C_CTRL_SCL_POS 8 /**< CTRL_SCL Position */
-#define MXC_F_I2C_CTRL_SCL \
- ((uint32_t)(0x1UL << MXC_F_I2C_CTRL_SCL_POS)) /**< CTRL_SCL Mask */
-
-#define MXC_F_I2C_CTRL_SDA_POS 9 /**< CTRL_SDA Position */
-#define MXC_F_I2C_CTRL_SDA \
- ((uint32_t)(0x1UL << MXC_F_I2C_CTRL_SDA_POS)) /**< CTRL_SDA Mask */
-
-#define MXC_F_I2C_CTRL_SW_OUT_EN_POS 10 /**< CTRL_SW_OUT_EN Position */
-#define MXC_F_I2C_CTRL_SW_OUT_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_CTRL_SW_OUT_EN_POS)) /**< CTRL_SW_OUT_EN Mask */
-#define MXC_V_I2C_CTRL_SW_OUT_EN_OUTPUTS_DISABLE \
- ((uint32_t)0x0UL) /**< CTRL_SW_OUT_EN_OUTPUTS_DISABLE Value */
-#define MXC_S_I2C_CTRL_SW_OUT_EN_OUTPUTS_DISABLE \
- (MXC_V_I2C_CTRL_SW_OUT_EN_OUTPUTS_DISABLE \
- << MXC_F_I2C_CTRL_SW_OUT_EN_POS) /**< CTRL_SW_OUT_EN_OUTPUTS_DISABLE \
- Setting */
-#define MXC_V_I2C_CTRL_SW_OUT_EN_OUTPUTS_ENABLE \
- ((uint32_t)0x1UL) /**< CTRL_SW_OUT_EN_OUTPUTS_ENABLE Value */
-#define MXC_S_I2C_CTRL_SW_OUT_EN_OUTPUTS_ENABLE \
- (MXC_V_I2C_CTRL_SW_OUT_EN_OUTPUTS_ENABLE \
- << MXC_F_I2C_CTRL_SW_OUT_EN_POS) /**< CTRL_SW_OUT_EN_OUTPUTS_ENABLE \
- Setting */
-
-#define MXC_F_I2C_CTRL_READ_POS 11 /**< CTRL_READ Position */
-#define MXC_F_I2C_CTRL_READ \
- ((uint32_t)(0x1UL << MXC_F_I2C_CTRL_READ_POS)) /**< CTRL_READ Mask */
-#define MXC_V_I2C_CTRL_READ_WRITE \
- ((uint32_t)0x0UL) /**< CTRL_READ_WRITE Value */
-#define MXC_S_I2C_CTRL_READ_WRITE \
- (MXC_V_I2C_CTRL_READ_WRITE \
- << MXC_F_I2C_CTRL_READ_POS) /**< CTRL_READ_WRITE Setting */
-#define MXC_V_I2C_CTRL_READ_READ \
- ((uint32_t)0x1UL) /**< CTRL_READ_READ Value \
- */
-#define MXC_S_I2C_CTRL_READ_READ \
- (MXC_V_I2C_CTRL_READ_READ \
- << MXC_F_I2C_CTRL_READ_POS) /**< CTRL_READ_READ Setting */
-
-#define MXC_F_I2C_CTRL_SCL_CLK_STRECH_DIS_POS \
- 12 /**< CTRL_SCL_CLK_STRECH_DIS Position */
-#define MXC_F_I2C_CTRL_SCL_CLK_STRECH_DIS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_CTRL_SCL_CLK_STRECH_DIS_POS)) /**< \
- CTRL_SCL_CLK_STRECH_DIS \
- Mask */
-#define MXC_V_I2C_CTRL_SCL_CLK_STRECH_DIS_EN \
- ((uint32_t)0x0UL) /**< CTRL_SCL_CLK_STRECH_DIS_EN Value */
-#define MXC_S_I2C_CTRL_SCL_CLK_STRECH_DIS_EN \
- (MXC_V_I2C_CTRL_SCL_CLK_STRECH_DIS_EN \
- << MXC_F_I2C_CTRL_SCL_CLK_STRECH_DIS_POS) /**< \
- CTRL_SCL_CLK_STRECH_DIS_EN \
- Setting */
-#define MXC_V_I2C_CTRL_SCL_CLK_STRECH_DIS_DIS \
- ((uint32_t)0x1UL) /**< CTRL_SCL_CLK_STRECH_DIS_DIS Value */
-#define MXC_S_I2C_CTRL_SCL_CLK_STRECH_DIS_DIS \
- (MXC_V_I2C_CTRL_SCL_CLK_STRECH_DIS_DIS \
- << MXC_F_I2C_CTRL_SCL_CLK_STRECH_DIS_POS) /**< \
- CTRL_SCL_CLK_STRECH_DIS_DIS \
- Setting */
-
-#define MXC_F_I2C_CTRL_SCL_PP_MODE_POS 13 /**< CTRL_SCL_PP_MODE Position */
-#define MXC_F_I2C_CTRL_SCL_PP_MODE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_CTRL_SCL_PP_MODE_POS)) /**< CTRL_SCL_PP_MODE \
- Mask */
-#define MXC_V_I2C_CTRL_SCL_PP_MODE_DIS \
- ((uint32_t)0x0UL) /**< CTRL_SCL_PP_MODE_DIS Value */
-#define MXC_S_I2C_CTRL_SCL_PP_MODE_DIS \
- (MXC_V_I2C_CTRL_SCL_PP_MODE_DIS \
- << MXC_F_I2C_CTRL_SCL_PP_MODE_POS) /**< CTRL_SCL_PP_MODE_DIS Setting \
- */
-#define MXC_V_I2C_CTRL_SCL_PP_MODE_EN \
- ((uint32_t)0x1UL) /**< CTRL_SCL_PP_MODE_EN Value */
-#define MXC_S_I2C_CTRL_SCL_PP_MODE_EN \
- (MXC_V_I2C_CTRL_SCL_PP_MODE_EN \
- << MXC_F_I2C_CTRL_SCL_PP_MODE_POS) /**< CTRL_SCL_PP_MODE_EN Setting \
- */
-
-#define MXC_F_I2C_CTRL_HS_MODE_POS 15 /**< CTRL_HS_MODE Position */
-#define MXC_F_I2C_CTRL_HS_MODE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_CTRL_HS_MODE_POS)) /**< CTRL_HS_MODE Mask */
-#define MXC_V_I2C_CTRL_HS_MODE_DIS \
- ((uint32_t)0x0UL) /**< CTRL_HS_MODE_DIS Value */
-#define MXC_S_I2C_CTRL_HS_MODE_DIS \
- (MXC_V_I2C_CTRL_HS_MODE_DIS \
- << MXC_F_I2C_CTRL_HS_MODE_POS) /**< CTRL_HS_MODE_DIS Setting */
-#define MXC_V_I2C_CTRL_HS_MODE_EN \
- ((uint32_t)0x1UL) /**< CTRL_HS_MODE_EN Value */
-#define MXC_S_I2C_CTRL_HS_MODE_EN \
- (MXC_V_I2C_CTRL_HS_MODE_EN \
- << MXC_F_I2C_CTRL_HS_MODE_POS) /**< CTRL_HS_MODE_EN Setting */
-
-/**
- * I2C_STATUS I2C_STATUS
- */
-#define MXC_F_I2C_STATUS_BUS_POS 0 /**< STATUS_BUS Position */
-#define MXC_F_I2C_STATUS_BUS \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_STATUS_BUS_POS)) /**< STATUS_BUS Mask \
- */
-#define MXC_V_I2C_STATUS_BUS_IDLE \
- ((uint32_t)0x0UL) /**< STATUS_BUS_IDLE Value */
-#define MXC_S_I2C_STATUS_BUS_IDLE \
- (MXC_V_I2C_STATUS_BUS_IDLE \
- << MXC_F_I2C_STATUS_BUS_POS) /**< STATUS_BUS_IDLE Setting */
-#define MXC_V_I2C_STATUS_BUS_BUSY \
- ((uint32_t)0x1UL) /**< STATUS_BUS_BUSY Value */
-#define MXC_S_I2C_STATUS_BUS_BUSY \
- (MXC_V_I2C_STATUS_BUS_BUSY \
- << MXC_F_I2C_STATUS_BUS_POS) /**< STATUS_BUS_BUSY Setting */
-
-#define MXC_F_I2C_STATUS_RX_EMPTY_POS 1 /**< STATUS_RX_EMPTY Position */
-#define MXC_F_I2C_STATUS_RX_EMPTY \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_STATUS_RX_EMPTY_POS)) /**< STATUS_RX_EMPTY \
- Mask */
-#define MXC_V_I2C_STATUS_RX_EMPTY_NOT_EMPTY \
- ((uint32_t)0x0UL) /**< STATUS_RX_EMPTY_NOT_EMPTY Value */
-#define MXC_S_I2C_STATUS_RX_EMPTY_NOT_EMPTY \
- (MXC_V_I2C_STATUS_RX_EMPTY_NOT_EMPTY \
- << MXC_F_I2C_STATUS_RX_EMPTY_POS) /**< STATUS_RX_EMPTY_NOT_EMPTY \
- Setting */
-#define MXC_V_I2C_STATUS_RX_EMPTY_EMPTY \
- ((uint32_t)0x1UL) /**< STATUS_RX_EMPTY_EMPTY Value */
-#define MXC_S_I2C_STATUS_RX_EMPTY_EMPTY \
- (MXC_V_I2C_STATUS_RX_EMPTY_EMPTY \
- << MXC_F_I2C_STATUS_RX_EMPTY_POS) /**< STATUS_RX_EMPTY_EMPTY Setting \
- */
-
-#define MXC_F_I2C_STATUS_RX_FULL_POS 2 /**< STATUS_RX_FULL Position */
-#define MXC_F_I2C_STATUS_RX_FULL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_STATUS_RX_FULL_POS)) /**< STATUS_RX_FULL Mask */
-#define MXC_V_I2C_STATUS_RX_FULL_NOT_FULL \
- ((uint32_t)0x0UL) /**< STATUS_RX_FULL_NOT_FULL Value */
-#define MXC_S_I2C_STATUS_RX_FULL_NOT_FULL \
- (MXC_V_I2C_STATUS_RX_FULL_NOT_FULL \
- << MXC_F_I2C_STATUS_RX_FULL_POS) /**< STATUS_RX_FULL_NOT_FULL Setting \
- */
-#define MXC_V_I2C_STATUS_RX_FULL_FULL \
- ((uint32_t)0x1UL) /**< STATUS_RX_FULL_FULL Value */
-#define MXC_S_I2C_STATUS_RX_FULL_FULL \
- (MXC_V_I2C_STATUS_RX_FULL_FULL \
- << MXC_F_I2C_STATUS_RX_FULL_POS) /**< STATUS_RX_FULL_FULL Setting */
-
-#define MXC_F_I2C_STATUS_TX_EMPTY_POS 3 /**< STATUS_TX_EMPTY Position */
-#define MXC_F_I2C_STATUS_TX_EMPTY \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_STATUS_TX_EMPTY_POS)) /**< STATUS_TX_EMPTY \
- Mask */
-#define MXC_V_I2C_STATUS_TX_EMPTY_NOT_EMPTY \
- ((uint32_t)0x0UL) /**< STATUS_TX_EMPTY_NOT_EMPTY Value */
-#define MXC_S_I2C_STATUS_TX_EMPTY_NOT_EMPTY \
- (MXC_V_I2C_STATUS_TX_EMPTY_NOT_EMPTY \
- << MXC_F_I2C_STATUS_TX_EMPTY_POS) /**< STATUS_TX_EMPTY_NOT_EMPTY \
- Setting */
-#define MXC_V_I2C_STATUS_TX_EMPTY_EMPTY \
- ((uint32_t)0x1UL) /**< STATUS_TX_EMPTY_EMPTY Value */
-#define MXC_S_I2C_STATUS_TX_EMPTY_EMPTY \
- (MXC_V_I2C_STATUS_TX_EMPTY_EMPTY \
- << MXC_F_I2C_STATUS_TX_EMPTY_POS) /**< STATUS_TX_EMPTY_EMPTY Setting \
- */
-
-#define MXC_F_I2C_STATUS_TX_FULL_POS 4 /**< STATUS_TX_FULL Position */
-#define MXC_F_I2C_STATUS_TX_FULL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_STATUS_TX_FULL_POS)) /**< STATUS_TX_FULL Mask */
-#define MXC_V_I2C_STATUS_TX_FULL_NOT_EMPTY \
- ((uint32_t)0x0UL) /**< STATUS_TX_FULL_NOT_EMPTY Value */
-#define MXC_S_I2C_STATUS_TX_FULL_NOT_EMPTY \
- (MXC_V_I2C_STATUS_TX_FULL_NOT_EMPTY \
- << MXC_F_I2C_STATUS_TX_FULL_POS) /**< STATUS_TX_FULL_NOT_EMPTY \
- Setting */
-#define MXC_V_I2C_STATUS_TX_FULL_EMPTY \
- ((uint32_t)0x1UL) /**< STATUS_TX_FULL_EMPTY Value */
-#define MXC_S_I2C_STATUS_TX_FULL_EMPTY \
- (MXC_V_I2C_STATUS_TX_FULL_EMPTY \
- << MXC_F_I2C_STATUS_TX_FULL_POS) /**< STATUS_TX_FULL_EMPTY Setting */
-
-#define MXC_F_I2C_STATUS_CLK_MODE_POS 5 /**< STATUS_CLK_MODE Position */
-#define MXC_F_I2C_STATUS_CLK_MODE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_STATUS_CLK_MODE_POS)) /**< STATUS_CLK_MODE \
- Mask */
-#define MXC_V_I2C_STATUS_CLK_MODE_NOT_ACTIVELY_DRIVING_SCL_CLOCK \
- ((uint32_t)0x0UL) /**< STATUS_CLK_MODE_NOT_ACTIVELY_DRIVING_SCL_CLOCK \
- Value */
-#define MXC_S_I2C_STATUS_CLK_MODE_NOT_ACTIVELY_DRIVING_SCL_CLOCK \
- (MXC_V_I2C_STATUS_CLK_MODE_NOT_ACTIVELY_DRIVING_SCL_CLOCK \
- << MXC_F_I2C_STATUS_CLK_MODE_POS) /**< \
- STATUS_CLK_MODE_NOT_ACTIVELY_DRIVING_SCL_CLOCK \
- Setting */
-#define MXC_V_I2C_STATUS_CLK_MODE_ACTIVELY_DRIVING_SCL_CLOCK \
- ((uint32_t)0x1UL) /**< STATUS_CLK_MODE_ACTIVELY_DRIVING_SCL_CLOCK \
- Value */
-#define MXC_S_I2C_STATUS_CLK_MODE_ACTIVELY_DRIVING_SCL_CLOCK \
- (MXC_V_I2C_STATUS_CLK_MODE_ACTIVELY_DRIVING_SCL_CLOCK \
- << MXC_F_I2C_STATUS_CLK_MODE_POS) /**< \
- STATUS_CLK_MODE_ACTIVELY_DRIVING_SCL_CLOCK \
- Setting */
-
-#define MXC_F_I2C_STATUS_STATUS_POS 8 /**< STATUS_STATUS Position */
-#define MXC_F_I2C_STATUS_STATUS \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_STATUS_STATUS_POS)) /**< STATUS_STATUS Mask */
-#define MXC_V_I2C_STATUS_STATUS_IDLE \
- ((uint32_t)0x0UL) /**< STATUS_STATUS_IDLE Value */
-#define MXC_S_I2C_STATUS_STATUS_IDLE \
- (MXC_V_I2C_STATUS_STATUS_IDLE \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_IDLE Setting */
-#define MXC_V_I2C_STATUS_STATUS_MTX_ADDR \
- ((uint32_t)0x1UL) /**< STATUS_STATUS_MTX_ADDR Value */
-#define MXC_S_I2C_STATUS_STATUS_MTX_ADDR \
- (MXC_V_I2C_STATUS_STATUS_MTX_ADDR \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_MTX_ADDR Setting \
- */
-#define MXC_V_I2C_STATUS_STATUS_MRX_ADDR_ACK \
- ((uint32_t)0x2UL) /**< STATUS_STATUS_MRX_ADDR_ACK Value */
-#define MXC_S_I2C_STATUS_STATUS_MRX_ADDR_ACK \
- (MXC_V_I2C_STATUS_STATUS_MRX_ADDR_ACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_MRX_ADDR_ACK \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_MTX_EX_ADDR \
- ((uint32_t)0x3UL) /**< STATUS_STATUS_MTX_EX_ADDR Value */
-#define MXC_S_I2C_STATUS_STATUS_MTX_EX_ADDR \
- (MXC_V_I2C_STATUS_STATUS_MTX_EX_ADDR \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_MTX_EX_ADDR \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_MRX_EX_ADDR \
- ((uint32_t)0x4UL) /**< STATUS_STATUS_MRX_EX_ADDR Value */
-#define MXC_S_I2C_STATUS_STATUS_MRX_EX_ADDR \
- (MXC_V_I2C_STATUS_STATUS_MRX_EX_ADDR \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_MRX_EX_ADDR \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_SRX_ADDR \
- ((uint32_t)0x5UL) /**< STATUS_STATUS_SRX_ADDR Value */
-#define MXC_S_I2C_STATUS_STATUS_SRX_ADDR \
- (MXC_V_I2C_STATUS_STATUS_SRX_ADDR \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_SRX_ADDR Setting \
- */
-#define MXC_V_I2C_STATUS_STATUS_STX_ADDR_ACK \
- ((uint32_t)0x6UL) /**< STATUS_STATUS_STX_ADDR_ACK Value */
-#define MXC_S_I2C_STATUS_STATUS_STX_ADDR_ACK \
- (MXC_V_I2C_STATUS_STATUS_STX_ADDR_ACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_STX_ADDR_ACK \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_SRX_EX_ADDR \
- ((uint32_t)0x7UL) /**< STATUS_STATUS_SRX_EX_ADDR Value */
-#define MXC_S_I2C_STATUS_STATUS_SRX_EX_ADDR \
- (MXC_V_I2C_STATUS_STATUS_SRX_EX_ADDR \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_SRX_EX_ADDR \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_STX_EX_ADDR_ACK \
- ((uint32_t)0x8UL) /**< STATUS_STATUS_STX_EX_ADDR_ACK Value */
-#define MXC_S_I2C_STATUS_STATUS_STX_EX_ADDR_ACK \
- (MXC_V_I2C_STATUS_STATUS_STX_EX_ADDR_ACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_STX_EX_ADDR_ACK \
- Setting */
-#define MXC_V_I2C_STATUS_STATUS_TX \
- ((uint32_t)0x9UL) /**< STATUS_STATUS_TX Value */
-#define MXC_S_I2C_STATUS_STATUS_TX \
- (MXC_V_I2C_STATUS_STATUS_TX \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_TX Setting */
-#define MXC_V_I2C_STATUS_STATUS_RX_ACK \
- ((uint32_t)0xAUL) /**< STATUS_STATUS_RX_ACK Value */
-#define MXC_S_I2C_STATUS_STATUS_RX_ACK \
- (MXC_V_I2C_STATUS_STATUS_RX_ACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_RX_ACK Setting */
-#define MXC_V_I2C_STATUS_STATUS_RX \
- ((uint32_t)0xBUL) /**< STATUS_STATUS_RX Value */
-#define MXC_S_I2C_STATUS_STATUS_RX \
- (MXC_V_I2C_STATUS_STATUS_RX \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_RX Setting */
-#define MXC_V_I2C_STATUS_STATUS_TX_ACK \
- ((uint32_t)0xCUL) /**< STATUS_STATUS_TX_ACK Value */
-#define MXC_S_I2C_STATUS_STATUS_TX_ACK \
- (MXC_V_I2C_STATUS_STATUS_TX_ACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_TX_ACK Setting */
-#define MXC_V_I2C_STATUS_STATUS_NACK \
- ((uint32_t)0xDUL) /**< STATUS_STATUS_NACK Value */
-#define MXC_S_I2C_STATUS_STATUS_NACK \
- (MXC_V_I2C_STATUS_STATUS_NACK \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_NACK Setting */
-#define MXC_V_I2C_STATUS_STATUS_BY_ST \
- ((uint32_t)0xFUL) /**< STATUS_STATUS_BY_ST Value */
-#define MXC_S_I2C_STATUS_STATUS_BY_ST \
- (MXC_V_I2C_STATUS_STATUS_BY_ST \
- << MXC_F_I2C_STATUS_STATUS_POS) /**< STATUS_STATUS_BY_ST Setting */
-
-/**
- * Interrupt Status Register.
- */
-#define MXC_F_I2C_INT_FL0_DONE_POS 0 /**< INT_FL0_DONE Position */
-#define MXC_F_I2C_INT_FL0_DONE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_FL0_DONE_POS)) /**< INT_FL0_DONE Mask */
-#define MXC_V_I2C_INT_FL0_DONE_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_DONE_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_DONE_INACTIVE \
- (MXC_V_I2C_INT_FL0_DONE_INACTIVE \
- << MXC_F_I2C_INT_FL0_DONE_POS) /**< INT_FL0_DONE_INACTIVE Setting */
-#define MXC_V_I2C_INT_FL0_DONE_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_DONE_PENDING Value */
-#define MXC_S_I2C_INT_FL0_DONE_PENDING \
- (MXC_V_I2C_INT_FL0_DONE_PENDING \
- << MXC_F_I2C_INT_FL0_DONE_POS) /**< INT_FL0_DONE_PENDING Setting */
-
-#define MXC_F_I2C_INT_FL0_RX_MODE_POS 1 /**< INT_FL0_RX_MODE Position */
-#define MXC_F_I2C_INT_FL0_RX_MODE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_FL0_RX_MODE_POS)) /**< INT_FL0_RX_MODE \
- Mask */
-#define MXC_V_I2C_INT_FL0_RX_MODE_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_RX_MODE_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_RX_MODE_INACTIVE \
- (MXC_V_I2C_INT_FL0_RX_MODE_INACTIVE \
- << MXC_F_I2C_INT_FL0_RX_MODE_POS) /**< INT_FL0_RX_MODE_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_RX_MODE_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_RX_MODE_PENDING Value */
-#define MXC_S_I2C_INT_FL0_RX_MODE_PENDING \
- (MXC_V_I2C_INT_FL0_RX_MODE_PENDING \
- << MXC_F_I2C_INT_FL0_RX_MODE_POS) /**< INT_FL0_RX_MODE_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_GEN_CALL_ADDR_POS \
- 2 /**< INT_FL0_GEN_CALL_ADDR Position */
-#define MXC_F_I2C_INT_FL0_GEN_CALL_ADDR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_GEN_CALL_ADDR_POS)) /**< \
- INT_FL0_GEN_CALL_ADDR \
- Mask */
-#define MXC_V_I2C_INT_FL0_GEN_CALL_ADDR_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_GEN_CALL_ADDR_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_GEN_CALL_ADDR_INACTIVE \
- (MXC_V_I2C_INT_FL0_GEN_CALL_ADDR_INACTIVE \
- << MXC_F_I2C_INT_FL0_GEN_CALL_ADDR_POS) /**< \
- INT_FL0_GEN_CALL_ADDR_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_GEN_CALL_ADDR_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_GEN_CALL_ADDR_PENDING Value */
-#define MXC_S_I2C_INT_FL0_GEN_CALL_ADDR_PENDING \
- (MXC_V_I2C_INT_FL0_GEN_CALL_ADDR_PENDING \
- << MXC_F_I2C_INT_FL0_GEN_CALL_ADDR_POS) /**< \
- INT_FL0_GEN_CALL_ADDR_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_ADDR_MATCH_POS 3 /**< INT_FL0_ADDR_MATCH Position */
-#define MXC_F_I2C_INT_FL0_ADDR_MATCH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_ADDR_MATCH_POS)) /**< INT_FL0_ADDR_MATCH \
- Mask */
-#define MXC_V_I2C_INT_FL0_ADDR_MATCH_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_ADDR_MATCH_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_ADDR_MATCH_INACTIVE \
- (MXC_V_I2C_INT_FL0_ADDR_MATCH_INACTIVE \
- << MXC_F_I2C_INT_FL0_ADDR_MATCH_POS) /**< INT_FL0_ADDR_MATCH_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_ADDR_MATCH_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_ADDR_MATCH_PENDING Value */
-#define MXC_S_I2C_INT_FL0_ADDR_MATCH_PENDING \
- (MXC_V_I2C_INT_FL0_ADDR_MATCH_PENDING \
- << MXC_F_I2C_INT_FL0_ADDR_MATCH_POS) /**< INT_FL0_ADDR_MATCH_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_RX_THRESH_POS 4 /**< INT_FL0_RX_THRESH Position */
-#define MXC_F_I2C_INT_FL0_RX_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_RX_THRESH_POS)) /**< INT_FL0_RX_THRESH \
- Mask */
-#define MXC_V_I2C_INT_FL0_RX_THRESH_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_RX_THRESH_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_RX_THRESH_INACTIVE \
- (MXC_V_I2C_INT_FL0_RX_THRESH_INACTIVE \
- << MXC_F_I2C_INT_FL0_RX_THRESH_POS) /**< INT_FL0_RX_THRESH_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_RX_THRESH_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_RX_THRESH_PENDING Value */
-#define MXC_S_I2C_INT_FL0_RX_THRESH_PENDING \
- (MXC_V_I2C_INT_FL0_RX_THRESH_PENDING \
- << MXC_F_I2C_INT_FL0_RX_THRESH_POS) /**< INT_FL0_RX_THRESH_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_TX_THRESH_POS 5 /**< INT_FL0_TX_THRESH Position */
-#define MXC_F_I2C_INT_FL0_TX_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_TX_THRESH_POS)) /**< INT_FL0_TX_THRESH \
- Mask */
-#define MXC_V_I2C_INT_FL0_TX_THRESH_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_TX_THRESH_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_TX_THRESH_INACTIVE \
- (MXC_V_I2C_INT_FL0_TX_THRESH_INACTIVE \
- << MXC_F_I2C_INT_FL0_TX_THRESH_POS) /**< INT_FL0_TX_THRESH_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_TX_THRESH_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_TX_THRESH_PENDING Value */
-#define MXC_S_I2C_INT_FL0_TX_THRESH_PENDING \
- (MXC_V_I2C_INT_FL0_TX_THRESH_PENDING \
- << MXC_F_I2C_INT_FL0_TX_THRESH_POS) /**< INT_FL0_TX_THRESH_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_STOP_POS 6 /**< INT_FL0_STOP Position */
-#define MXC_F_I2C_INT_FL0_STOP \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_FL0_STOP_POS)) /**< INT_FL0_STOP Mask */
-#define MXC_V_I2C_INT_FL0_STOP_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_STOP_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_STOP_INACTIVE \
- (MXC_V_I2C_INT_FL0_STOP_INACTIVE \
- << MXC_F_I2C_INT_FL0_STOP_POS) /**< INT_FL0_STOP_INACTIVE Setting */
-#define MXC_V_I2C_INT_FL0_STOP_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_STOP_PENDING Value */
-#define MXC_S_I2C_INT_FL0_STOP_PENDING \
- (MXC_V_I2C_INT_FL0_STOP_PENDING \
- << MXC_F_I2C_INT_FL0_STOP_POS) /**< INT_FL0_STOP_PENDING Setting */
-
-#define MXC_F_I2C_INT_FL0_ADDR_ACK_POS 7 /**< INT_FL0_ADDR_ACK Position */
-#define MXC_F_I2C_INT_FL0_ADDR_ACK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_ADDR_ACK_POS)) /**< INT_FL0_ADDR_ACK \
- Mask */
-#define MXC_V_I2C_INT_FL0_ADDR_ACK_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_ADDR_ACK_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_ADDR_ACK_INACTIVE \
- (MXC_V_I2C_INT_FL0_ADDR_ACK_INACTIVE \
- << MXC_F_I2C_INT_FL0_ADDR_ACK_POS) /**< INT_FL0_ADDR_ACK_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_ADDR_ACK_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_ADDR_ACK_PENDING Value */
-#define MXC_S_I2C_INT_FL0_ADDR_ACK_PENDING \
- (MXC_V_I2C_INT_FL0_ADDR_ACK_PENDING \
- << MXC_F_I2C_INT_FL0_ADDR_ACK_POS) /**< INT_FL0_ADDR_ACK_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_ARB_ER_POS 8 /**< INT_FL0_ARB_ER Position */
-#define MXC_F_I2C_INT_FL0_ARB_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_ARB_ER_POS)) /**< INT_FL0_ARB_ER Mask */
-#define MXC_V_I2C_INT_FL0_ARB_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_ARB_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_ARB_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_ARB_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_ARB_ER_POS) /**< INT_FL0_ARB_ER_INACTIVE Setting \
- */
-#define MXC_V_I2C_INT_FL0_ARB_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_ARB_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_ARB_ER_PENDING \
- (MXC_V_I2C_INT_FL0_ARB_ER_PENDING \
- << MXC_F_I2C_INT_FL0_ARB_ER_POS) /**< INT_FL0_ARB_ER_PENDING Setting \
- */
-
-#define MXC_F_I2C_INT_FL0_TO_ER_POS 9 /**< INT_FL0_TO_ER Position */
-#define MXC_F_I2C_INT_FL0_TO_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_TO_ER_POS)) /**< INT_FL0_TO_ER Mask */
-#define MXC_V_I2C_INT_FL0_TO_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_TO_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_TO_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_TO_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_TO_ER_POS) /**< INT_FL0_TO_ER_INACTIVE Setting \
- */
-#define MXC_V_I2C_INT_FL0_TO_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_TO_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_TO_ER_PENDING \
- (MXC_V_I2C_INT_FL0_TO_ER_PENDING \
- << MXC_F_I2C_INT_FL0_TO_ER_POS) /**< INT_FL0_TO_ER_PENDING Setting */
-
-#define MXC_F_I2C_INT_FL0_ADDR_NACK_ER_POS \
- 10 /**< INT_FL0_ADDR_NACK_ER Position */
-#define MXC_F_I2C_INT_FL0_ADDR_NACK_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_ADDR_NACK_ER_POS)) /**< \
- INT_FL0_ADDR_NACK_ER \
- Mask */
-#define MXC_V_I2C_INT_FL0_ADDR_NACK_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_ADDR_NACK_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_ADDR_NACK_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_ADDR_NACK_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_ADDR_NACK_ER_POS) /**< \
- INT_FL0_ADDR_NACK_ER_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_ADDR_NACK_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_ADDR_NACK_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_ADDR_NACK_ER_PENDING \
- (MXC_V_I2C_INT_FL0_ADDR_NACK_ER_PENDING \
- << MXC_F_I2C_INT_FL0_ADDR_NACK_ER_POS) /**< \
- INT_FL0_ADDR_NACK_ER_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_DATA_ER_POS 11 /**< INT_FL0_DATA_ER Position */
-#define MXC_F_I2C_INT_FL0_DATA_ER \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_FL0_DATA_ER_POS)) /**< INT_FL0_DATA_ER \
- Mask */
-#define MXC_V_I2C_INT_FL0_DATA_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_DATA_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_DATA_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_DATA_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_DATA_ER_POS) /**< INT_FL0_DATA_ER_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_DATA_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_DATA_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_DATA_ER_PENDING \
- (MXC_V_I2C_INT_FL0_DATA_ER_PENDING \
- << MXC_F_I2C_INT_FL0_DATA_ER_POS) /**< INT_FL0_DATA_ER_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER_POS \
- 12 /**< INT_FL0_DO_NOT_RESP_ER Position */
-#define MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER_POS)) /**< \
- INT_FL0_DO_NOT_RESP_ER \
- Mask */
-#define MXC_V_I2C_INT_FL0_DO_NOT_RESP_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_DO_NOT_RESP_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_DO_NOT_RESP_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_DO_NOT_RESP_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER_POS) /**< \
- INT_FL0_DO_NOT_RESP_ER_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_DO_NOT_RESP_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_DO_NOT_RESP_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_DO_NOT_RESP_ER_PENDING \
- (MXC_V_I2C_INT_FL0_DO_NOT_RESP_ER_PENDING \
- << MXC_F_I2C_INT_FL0_DO_NOT_RESP_ER_POS) /**< \
- INT_FL0_DO_NOT_RESP_ER_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_START_ER_POS 13 /**< INT_FL0_START_ER Position */
-#define MXC_F_I2C_INT_FL0_START_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_START_ER_POS)) /**< INT_FL0_START_ER \
- Mask */
-#define MXC_V_I2C_INT_FL0_START_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_START_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_START_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_START_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_START_ER_POS) /**< INT_FL0_START_ER_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_START_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_START_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_START_ER_PENDING \
- (MXC_V_I2C_INT_FL0_START_ER_PENDING \
- << MXC_F_I2C_INT_FL0_START_ER_POS) /**< INT_FL0_START_ER_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_STOP_ER_POS 14 /**< INT_FL0_STOP_ER Position */
-#define MXC_F_I2C_INT_FL0_STOP_ER \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_FL0_STOP_ER_POS)) /**< INT_FL0_STOP_ER \
- Mask */
-#define MXC_V_I2C_INT_FL0_STOP_ER_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL0_STOP_ER_INACTIVE Value */
-#define MXC_S_I2C_INT_FL0_STOP_ER_INACTIVE \
- (MXC_V_I2C_INT_FL0_STOP_ER_INACTIVE \
- << MXC_F_I2C_INT_FL0_STOP_ER_POS) /**< INT_FL0_STOP_ER_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL0_STOP_ER_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL0_STOP_ER_PENDING Value */
-#define MXC_S_I2C_INT_FL0_STOP_ER_PENDING \
- (MXC_V_I2C_INT_FL0_STOP_ER_PENDING \
- << MXC_F_I2C_INT_FL0_STOP_ER_POS) /**< INT_FL0_STOP_ER_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL0_TX_LOCK_OUT_POS \
- 15 /**< INT_FL0_TX_LOCK_OUT Position */
-#define MXC_F_I2C_INT_FL0_TX_LOCK_OUT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL0_TX_LOCK_OUT_POS)) /**< \
- INT_FL0_TX_LOCK_OUT \
- Mask */
-
-#define MXC_F_I2C_INT_FL0_MAMI_POS 16 /**< INT_FL0_MAMI Position */
-/* INT_FL0_MAMI Mask */
-#define MXC_F_I2C_INT_FL0_MAMI_MASK \
- ((uint32_t)(0xFUL << MXC_F_I2C_INT_FL0_MAMI_POS))
-/* INT_FL0_MAMI Address Match 0 */
-#define MXC_F_I2C_INT_FL0_MAMI_MATCH_0 \
- ((uint32_t)(0x1UL << MXC_F_I2C_INT_FL0_MAMI_POS))
-/* INT_FL0_MAMI Address Match 1 */
-#define MXC_F_I2C_INT_FL0_MAMI_MATCH_1 \
- ((uint32_t)(0x2UL << MXC_F_I2C_INT_FL0_MAMI_POS))
-/* INT_FL0_MAMI Address Match 2 */
-#define MXC_F_I2C_INT_FL0_MAMI_MATCH_2 \
- ((uint32_t)(0x4UL << MXC_F_I2C_INT_FL0_MAMI_POS))
-/* INT_FL0_MAMI Address Match 3 */
-#define MXC_F_I2C_INT_FL0_MAMI_MATCH_3 \
- ((uint32_t)(0x8UL << MXC_F_I2C_INT_FL0_MAMI_POS))
-
-/**
- * Interrupt Enable Register.
- */
-#define MXC_F_I2C_INT_EN0_DONE_POS 0 /**< INT_EN0_DONE Position */
-#define MXC_F_I2C_INT_EN0_DONE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_DONE_POS)) /**< INT_EN0_DONE Mask */
-#define MXC_V_I2C_INT_EN0_DONE_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_DONE_DIS Value */
-#define MXC_S_I2C_INT_EN0_DONE_DIS \
- (MXC_V_I2C_INT_EN0_DONE_DIS \
- << MXC_F_I2C_INT_EN0_DONE_POS) /**< INT_EN0_DONE_DIS Setting */
-#define MXC_V_I2C_INT_EN0_DONE_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_DONE_EN Value */
-#define MXC_S_I2C_INT_EN0_DONE_EN \
- (MXC_V_I2C_INT_EN0_DONE_EN \
- << MXC_F_I2C_INT_EN0_DONE_POS) /**< INT_EN0_DONE_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_RX_MODE_POS 1 /**< INT_EN0_RX_MODE Position */
-#define MXC_F_I2C_INT_EN0_RX_MODE \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_RX_MODE_POS)) /**< INT_EN0_RX_MODE \
- Mask */
-#define MXC_V_I2C_INT_EN0_RX_MODE_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_RX_MODE_DIS Value */
-#define MXC_S_I2C_INT_EN0_RX_MODE_DIS \
- (MXC_V_I2C_INT_EN0_RX_MODE_DIS \
- << MXC_F_I2C_INT_EN0_RX_MODE_POS) /**< INT_EN0_RX_MODE_DIS Setting */
-#define MXC_V_I2C_INT_EN0_RX_MODE_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_RX_MODE_EN Value */
-#define MXC_S_I2C_INT_EN0_RX_MODE_EN \
- (MXC_V_I2C_INT_EN0_RX_MODE_EN \
- << MXC_F_I2C_INT_EN0_RX_MODE_POS) /**< INT_EN0_RX_MODE_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_GEN_CTRL_ADDR_POS \
- 2 /**< INT_EN0_GEN_CTRL_ADDR Position */
-#define MXC_F_I2C_INT_EN0_GEN_CTRL_ADDR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_GEN_CTRL_ADDR_POS)) /**< \
- INT_EN0_GEN_CTRL_ADDR \
- Mask */
-#define MXC_V_I2C_INT_EN0_GEN_CTRL_ADDR_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_GEN_CTRL_ADDR_DIS Value */
-#define MXC_S_I2C_INT_EN0_GEN_CTRL_ADDR_DIS \
- (MXC_V_I2C_INT_EN0_GEN_CTRL_ADDR_DIS \
- << MXC_F_I2C_INT_EN0_GEN_CTRL_ADDR_POS) /**< \
- INT_EN0_GEN_CTRL_ADDR_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_GEN_CTRL_ADDR_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_GEN_CTRL_ADDR_EN Value */
-#define MXC_S_I2C_INT_EN0_GEN_CTRL_ADDR_EN \
- (MXC_V_I2C_INT_EN0_GEN_CTRL_ADDR_EN \
- << MXC_F_I2C_INT_EN0_GEN_CTRL_ADDR_POS) /**< INT_EN0_GEN_CTRL_ADDR_EN \
- Setting */
-
-#define MXC_F_I2C_INT_EN0_ADDR_MATCH_POS 3 /**< INT_EN0_ADDR_MATCH Position */
-#define MXC_F_I2C_INT_EN0_ADDR_MATCH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_ADDR_MATCH_POS)) /**< INT_EN0_ADDR_MATCH \
- Mask */
-#define MXC_V_I2C_INT_EN0_ADDR_MATCH_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_ADDR_MATCH_DIS Value */
-#define MXC_S_I2C_INT_EN0_ADDR_MATCH_DIS \
- (MXC_V_I2C_INT_EN0_ADDR_MATCH_DIS \
- << MXC_F_I2C_INT_EN0_ADDR_MATCH_POS) /**< INT_EN0_ADDR_MATCH_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_ADDR_MATCH_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_ADDR_MATCH_EN Value */
-#define MXC_S_I2C_INT_EN0_ADDR_MATCH_EN \
- (MXC_V_I2C_INT_EN0_ADDR_MATCH_EN \
- << MXC_F_I2C_INT_EN0_ADDR_MATCH_POS) /**< INT_EN0_ADDR_MATCH_EN \
- Setting */
-
-#define MXC_F_I2C_INT_EN0_RX_THRESH_POS 4 /**< INT_EN0_RX_THRESH Position */
-#define MXC_F_I2C_INT_EN0_RX_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_RX_THRESH_POS)) /**< INT_EN0_RX_THRESH \
- Mask */
-#define MXC_V_I2C_INT_EN0_RX_THRESH_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_RX_THRESH_DIS Value */
-#define MXC_S_I2C_INT_EN0_RX_THRESH_DIS \
- (MXC_V_I2C_INT_EN0_RX_THRESH_DIS \
- << MXC_F_I2C_INT_EN0_RX_THRESH_POS) /**< INT_EN0_RX_THRESH_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_RX_THRESH_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_RX_THRESH_EN Value */
-#define MXC_S_I2C_INT_EN0_RX_THRESH_EN \
- (MXC_V_I2C_INT_EN0_RX_THRESH_EN \
- << MXC_F_I2C_INT_EN0_RX_THRESH_POS) /**< INT_EN0_RX_THRESH_EN Setting \
- */
-
-#define MXC_F_I2C_INT_EN0_TX_THRESH_POS 5 /**< INT_EN0_TX_THRESH Position */
-#define MXC_F_I2C_INT_EN0_TX_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_TX_THRESH_POS)) /**< INT_EN0_TX_THRESH \
- Mask */
-#define MXC_V_I2C_INT_EN0_TX_THRESH_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_TX_THRESH_DIS Value */
-#define MXC_S_I2C_INT_EN0_TX_THRESH_DIS \
- (MXC_V_I2C_INT_EN0_TX_THRESH_DIS \
- << MXC_F_I2C_INT_EN0_TX_THRESH_POS) /**< INT_EN0_TX_THRESH_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_TX_THRESH_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_TX_THRESH_EN Value */
-#define MXC_S_I2C_INT_EN0_TX_THRESH_EN \
- (MXC_V_I2C_INT_EN0_TX_THRESH_EN \
- << MXC_F_I2C_INT_EN0_TX_THRESH_POS) /**< INT_EN0_TX_THRESH_EN Setting \
- */
-
-#define MXC_F_I2C_INT_EN0_STOP_POS 6 /**< INT_EN0_STOP Position */
-#define MXC_F_I2C_INT_EN0_STOP \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_STOP_POS)) /**< INT_EN0_STOP Mask */
-#define MXC_V_I2C_INT_EN0_STOP_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_STOP_DIS Value */
-#define MXC_S_I2C_INT_EN0_STOP_DIS \
- (MXC_V_I2C_INT_EN0_STOP_DIS \
- << MXC_F_I2C_INT_EN0_STOP_POS) /**< INT_EN0_STOP_DIS Setting */
-#define MXC_V_I2C_INT_EN0_STOP_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_STOP_EN Value */
-#define MXC_S_I2C_INT_EN0_STOP_EN \
- (MXC_V_I2C_INT_EN0_STOP_EN \
- << MXC_F_I2C_INT_EN0_STOP_POS) /**< INT_EN0_STOP_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_ADDR_ACK_POS 7 /**< INT_EN0_ADDR_ACK Position */
-#define MXC_F_I2C_INT_EN0_ADDR_ACK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_ADDR_ACK_POS)) /**< INT_EN0_ADDR_ACK \
- Mask */
-#define MXC_V_I2C_INT_EN0_ADDR_ACK_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_ADDR_ACK_DIS Value */
-#define MXC_S_I2C_INT_EN0_ADDR_ACK_DIS \
- (MXC_V_I2C_INT_EN0_ADDR_ACK_DIS \
- << MXC_F_I2C_INT_EN0_ADDR_ACK_POS) /**< INT_EN0_ADDR_ACK_DIS Setting \
- */
-#define MXC_V_I2C_INT_EN0_ADDR_ACK_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_ADDR_ACK_EN Value */
-#define MXC_S_I2C_INT_EN0_ADDR_ACK_EN \
- (MXC_V_I2C_INT_EN0_ADDR_ACK_EN \
- << MXC_F_I2C_INT_EN0_ADDR_ACK_POS) /**< INT_EN0_ADDR_ACK_EN Setting \
- */
-
-#define MXC_F_I2C_INT_EN0_ARB_ER_POS 8 /**< INT_EN0_ARB_ER Position */
-#define MXC_F_I2C_INT_EN0_ARB_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_ARB_ER_POS)) /**< INT_EN0_ARB_ER Mask */
-#define MXC_V_I2C_INT_EN0_ARB_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_ARB_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_ARB_ER_DIS \
- (MXC_V_I2C_INT_EN0_ARB_ER_DIS \
- << MXC_F_I2C_INT_EN0_ARB_ER_POS) /**< INT_EN0_ARB_ER_DIS Setting */
-#define MXC_V_I2C_INT_EN0_ARB_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_ARB_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_ARB_ER_EN \
- (MXC_V_I2C_INT_EN0_ARB_ER_EN \
- << MXC_F_I2C_INT_EN0_ARB_ER_POS) /**< INT_EN0_ARB_ER_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_TO_ER_POS 9 /**< INT_EN0_TO_ER Position */
-#define MXC_F_I2C_INT_EN0_TO_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_TO_ER_POS)) /**< INT_EN0_TO_ER Mask */
-#define MXC_V_I2C_INT_EN0_TO_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_TO_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_TO_ER_DIS \
- (MXC_V_I2C_INT_EN0_TO_ER_DIS \
- << MXC_F_I2C_INT_EN0_TO_ER_POS) /**< INT_EN0_TO_ER_DIS Setting */
-#define MXC_V_I2C_INT_EN0_TO_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_TO_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_TO_ER_EN \
- (MXC_V_I2C_INT_EN0_TO_ER_EN \
- << MXC_F_I2C_INT_EN0_TO_ER_POS) /**< INT_EN0_TO_ER_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_ADDR_ER_POS 10 /**< INT_EN0_ADDR_ER Position */
-#define MXC_F_I2C_INT_EN0_ADDR_ER \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_ADDR_ER_POS)) /**< INT_EN0_ADDR_ER \
- Mask */
-#define MXC_V_I2C_INT_EN0_ADDR_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_ADDR_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_ADDR_ER_DIS \
- (MXC_V_I2C_INT_EN0_ADDR_ER_DIS \
- << MXC_F_I2C_INT_EN0_ADDR_ER_POS) /**< INT_EN0_ADDR_ER_DIS Setting */
-#define MXC_V_I2C_INT_EN0_ADDR_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_ADDR_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_ADDR_ER_EN \
- (MXC_V_I2C_INT_EN0_ADDR_ER_EN \
- << MXC_F_I2C_INT_EN0_ADDR_ER_POS) /**< INT_EN0_ADDR_ER_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_DATA_ER_POS 11 /**< INT_EN0_DATA_ER Position */
-#define MXC_F_I2C_INT_EN0_DATA_ER \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_DATA_ER_POS)) /**< INT_EN0_DATA_ER \
- Mask */
-#define MXC_V_I2C_INT_EN0_DATA_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_DATA_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_DATA_ER_DIS \
- (MXC_V_I2C_INT_EN0_DATA_ER_DIS \
- << MXC_F_I2C_INT_EN0_DATA_ER_POS) /**< INT_EN0_DATA_ER_DIS Setting */
-#define MXC_V_I2C_INT_EN0_DATA_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_DATA_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_DATA_ER_EN \
- (MXC_V_I2C_INT_EN0_DATA_ER_EN \
- << MXC_F_I2C_INT_EN0_DATA_ER_POS) /**< INT_EN0_DATA_ER_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_DO_NOT_RESP_ER_POS \
- 12 /**< INT_EN0_DO_NOT_RESP_ER Position */
-#define MXC_F_I2C_INT_EN0_DO_NOT_RESP_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_DO_NOT_RESP_ER_POS)) /**< \
- INT_EN0_DO_NOT_RESP_ER \
- Mask */
-#define MXC_V_I2C_INT_EN0_DO_NOT_RESP_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_DO_NOT_RESP_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_DO_NOT_RESP_ER_DIS \
- (MXC_V_I2C_INT_EN0_DO_NOT_RESP_ER_DIS \
- << MXC_F_I2C_INT_EN0_DO_NOT_RESP_ER_POS) /**< \
- INT_EN0_DO_NOT_RESP_ER_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_DO_NOT_RESP_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_DO_NOT_RESP_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_DO_NOT_RESP_ER_EN \
- (MXC_V_I2C_INT_EN0_DO_NOT_RESP_ER_EN \
- << MXC_F_I2C_INT_EN0_DO_NOT_RESP_ER_POS) /**< \
- INT_EN0_DO_NOT_RESP_ER_EN \
- Setting */
-
-#define MXC_F_I2C_INT_EN0_START_ER_POS 13 /**< INT_EN0_START_ER Position */
-#define MXC_F_I2C_INT_EN0_START_ER \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_START_ER_POS)) /**< INT_EN0_START_ER \
- Mask */
-#define MXC_V_I2C_INT_EN0_START_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_START_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_START_ER_DIS \
- (MXC_V_I2C_INT_EN0_START_ER_DIS \
- << MXC_F_I2C_INT_EN0_START_ER_POS) /**< INT_EN0_START_ER_DIS Setting \
- */
-#define MXC_V_I2C_INT_EN0_START_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_START_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_START_ER_EN \
- (MXC_V_I2C_INT_EN0_START_ER_EN \
- << MXC_F_I2C_INT_EN0_START_ER_POS) /**< INT_EN0_START_ER_EN Setting \
- */
-
-#define MXC_F_I2C_INT_EN0_STOP_ER_POS 14 /**< INT_EN0_STOP_ER Position */
-#define MXC_F_I2C_INT_EN0_STOP_ER \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_INT_EN0_STOP_ER_POS)) /**< INT_EN0_STOP_ER \
- Mask */
-#define MXC_V_I2C_INT_EN0_STOP_ER_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_STOP_ER_DIS Value */
-#define MXC_S_I2C_INT_EN0_STOP_ER_DIS \
- (MXC_V_I2C_INT_EN0_STOP_ER_DIS \
- << MXC_F_I2C_INT_EN0_STOP_ER_POS) /**< INT_EN0_STOP_ER_DIS Setting */
-#define MXC_V_I2C_INT_EN0_STOP_ER_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_STOP_ER_EN Value */
-#define MXC_S_I2C_INT_EN0_STOP_ER_EN \
- (MXC_V_I2C_INT_EN0_STOP_ER_EN \
- << MXC_F_I2C_INT_EN0_STOP_ER_POS) /**< INT_EN0_STOP_ER_EN Setting */
-
-#define MXC_F_I2C_INT_EN0_TX_LOCK_OUT_POS \
- 15 /**< INT_EN0_TX_LOCK_OUT Position */
-#define MXC_F_I2C_INT_EN0_TX_LOCK_OUT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN0_TX_LOCK_OUT_POS)) /**< \
- INT_EN0_TX_LOCK_OUT \
- Mask */
-#define MXC_V_I2C_INT_EN0_TX_LOCK_OUT_DIS \
- ((uint32_t)0x0UL) /**< INT_EN0_TX_LOCK_OUT_DIS Value */
-#define MXC_S_I2C_INT_EN0_TX_LOCK_OUT_DIS \
- (MXC_V_I2C_INT_EN0_TX_LOCK_OUT_DIS \
- << MXC_F_I2C_INT_EN0_TX_LOCK_OUT_POS) /**< INT_EN0_TX_LOCK_OUT_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN0_TX_LOCK_OUT_EN \
- ((uint32_t)0x1UL) /**< INT_EN0_TX_LOCK_OUT_EN Value */
-#define MXC_S_I2C_INT_EN0_TX_LOCK_OUT_EN \
- (MXC_V_I2C_INT_EN0_TX_LOCK_OUT_EN \
- << MXC_F_I2C_INT_EN0_TX_LOCK_OUT_POS) /**< INT_EN0_TX_LOCK_OUT_EN \
- Setting */
-
-/**
- * Interrupt Status Register 1.
- */
-#define MXC_F_I2C_INT_FL1_RX_OVERFLOW_POS \
- 0 /**< INT_FL1_RX_OVERFLOW Position \
- */
-#define MXC_F_I2C_INT_FL1_RX_OVERFLOW \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL1_RX_OVERFLOW_POS)) /**< \
- INT_FL1_RX_OVERFLOW \
- Mask */
-#define MXC_V_I2C_INT_FL1_RX_OVERFLOW_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL1_RX_OVERFLOW_INACTIVE Value */
-#define MXC_S_I2C_INT_FL1_RX_OVERFLOW_INACTIVE \
- (MXC_V_I2C_INT_FL1_RX_OVERFLOW_INACTIVE \
- << MXC_F_I2C_INT_FL1_RX_OVERFLOW_POS) /**< \
- INT_FL1_RX_OVERFLOW_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL1_RX_OVERFLOW_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL1_RX_OVERFLOW_PENDING Value */
-#define MXC_S_I2C_INT_FL1_RX_OVERFLOW_PENDING \
- (MXC_V_I2C_INT_FL1_RX_OVERFLOW_PENDING \
- << MXC_F_I2C_INT_FL1_RX_OVERFLOW_POS) /**< \
- INT_FL1_RX_OVERFLOW_PENDING \
- Setting */
-
-#define MXC_F_I2C_INT_FL1_TX_UNDERFLOW_POS \
- 1 /**< INT_FL1_TX_UNDERFLOW Position */
-#define MXC_F_I2C_INT_FL1_TX_UNDERFLOW \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_FL1_TX_UNDERFLOW_POS)) /**< \
- INT_FL1_TX_UNDERFLOW \
- Mask */
-#define MXC_V_I2C_INT_FL1_TX_UNDERFLOW_INACTIVE \
- ((uint32_t)0x0UL) /**< INT_FL1_TX_UNDERFLOW_INACTIVE Value */
-#define MXC_S_I2C_INT_FL1_TX_UNDERFLOW_INACTIVE \
- (MXC_V_I2C_INT_FL1_TX_UNDERFLOW_INACTIVE \
- << MXC_F_I2C_INT_FL1_TX_UNDERFLOW_POS) /**< \
- INT_FL1_TX_UNDERFLOW_INACTIVE \
- Setting */
-#define MXC_V_I2C_INT_FL1_TX_UNDERFLOW_PENDING \
- ((uint32_t)0x1UL) /**< INT_FL1_TX_UNDERFLOW_PENDING Value */
-#define MXC_S_I2C_INT_FL1_TX_UNDERFLOW_PENDING \
- (MXC_V_I2C_INT_FL1_TX_UNDERFLOW_PENDING \
- << MXC_F_I2C_INT_FL1_TX_UNDERFLOW_POS) /**< \
- INT_FL1_TX_UNDERFLOW_PENDING \
- Setting */
-
-/**
- * Interrupt Staus Register 1.
- */
-#define MXC_F_I2C_INT_EN1_RX_OVERFLOW_POS \
- 0 /**< INT_EN1_RX_OVERFLOW Position \
- */
-#define MXC_F_I2C_INT_EN1_RX_OVERFLOW \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN1_RX_OVERFLOW_POS)) /**< \
- INT_EN1_RX_OVERFLOW \
- Mask */
-#define MXC_V_I2C_INT_EN1_RX_OVERFLOW_DIS \
- ((uint32_t)0x0UL) /**< INT_EN1_RX_OVERFLOW_DIS Value */
-#define MXC_S_I2C_INT_EN1_RX_OVERFLOW_DIS \
- (MXC_V_I2C_INT_EN1_RX_OVERFLOW_DIS \
- << MXC_F_I2C_INT_EN1_RX_OVERFLOW_POS) /**< INT_EN1_RX_OVERFLOW_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN1_RX_OVERFLOW_EN \
- ((uint32_t)0x1UL) /**< INT_EN1_RX_OVERFLOW_EN Value */
-#define MXC_S_I2C_INT_EN1_RX_OVERFLOW_EN \
- (MXC_V_I2C_INT_EN1_RX_OVERFLOW_EN \
- << MXC_F_I2C_INT_EN1_RX_OVERFLOW_POS) /**< INT_EN1_RX_OVERFLOW_EN \
- Setting */
-
-#define MXC_F_I2C_INT_EN1_TX_UNDERFLOW_POS \
- 1 /**< INT_EN1_TX_UNDERFLOW Position */
-#define MXC_F_I2C_INT_EN1_TX_UNDERFLOW \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_INT_EN1_TX_UNDERFLOW_POS)) /**< \
- INT_EN1_TX_UNDERFLOW \
- Mask */
-#define MXC_V_I2C_INT_EN1_TX_UNDERFLOW_DIS \
- ((uint32_t)0x0UL) /**< INT_EN1_TX_UNDERFLOW_DIS Value */
-#define MXC_S_I2C_INT_EN1_TX_UNDERFLOW_DIS \
- (MXC_V_I2C_INT_EN1_TX_UNDERFLOW_DIS \
- << MXC_F_I2C_INT_EN1_TX_UNDERFLOW_POS) /**< INT_EN1_TX_UNDERFLOW_DIS \
- Setting */
-#define MXC_V_I2C_INT_EN1_TX_UNDERFLOW_EN \
- ((uint32_t)0x1UL) /**< INT_EN1_TX_UNDERFLOW_EN Value */
-#define MXC_S_I2C_INT_EN1_TX_UNDERFLOW_EN \
- (MXC_V_I2C_INT_EN1_TX_UNDERFLOW_EN \
- << MXC_F_I2C_INT_EN1_TX_UNDERFLOW_POS) /**< INT_EN1_TX_UNDERFLOW_EN \
- Setting */
-
-/**
- * FIFO Configuration Register.
- */
-#define MXC_F_I2C_FIFO_LEN_RX_LEN_POS 0 /**< FIFO_LEN_RX_LEN Position */
-#define MXC_F_I2C_FIFO_LEN_RX_LEN \
- ((uint32_t)(0xFFUL \
- << MXC_F_I2C_FIFO_LEN_RX_LEN_POS)) /**< FIFO_LEN_RX_LEN \
- Mask */
-
-#define MXC_F_I2C_FIFO_LEN_TX_LEN_POS 8 /**< FIFO_LEN_TX_LEN Position */
-#define MXC_F_I2C_FIFO_LEN_TX_LEN \
- ((uint32_t)(0xFFUL \
- << MXC_F_I2C_FIFO_LEN_TX_LEN_POS)) /**< FIFO_LEN_TX_LEN \
- Mask */
-
-/**
- * Receive Control Register 0.
- */
-#define MXC_F_I2C_RX_CTRL0_DNR_POS 0 /**< RX_CTRL0_DNR Position */
-#define MXC_F_I2C_RX_CTRL0_DNR \
- ((uint32_t)(0x1UL \
- << MXC_F_I2C_RX_CTRL0_DNR_POS)) /**< RX_CTRL0_DNR Mask */
-#define MXC_V_I2C_RX_CTRL0_DNR_RESPOND \
- ((uint32_t)0x0UL) /**< RX_CTRL0_DNR_RESPOND Value */
-#define MXC_S_I2C_RX_CTRL0_DNR_RESPOND \
- (MXC_V_I2C_RX_CTRL0_DNR_RESPOND \
- << MXC_F_I2C_RX_CTRL0_DNR_POS) /**< RX_CTRL0_DNR_RESPOND Setting */
-#define MXC_V_I2C_RX_CTRL0_DNR_NOT_RESPOND_RX_FIFO_EMPTY \
- ((uint32_t)0x1UL) /**< RX_CTRL0_DNR_NOT_RESPOND_RX_FIFO_EMPTY Value */
-#define MXC_S_I2C_RX_CTRL0_DNR_NOT_RESPOND_RX_FIFO_EMPTY \
- (MXC_V_I2C_RX_CTRL0_DNR_NOT_RESPOND_RX_FIFO_EMPTY \
- << MXC_F_I2C_RX_CTRL0_DNR_POS) /**< \
- RX_CTRL0_DNR_NOT_RESPOND_RX_FIFO_EMPTY \
- Setting */
-
-#define MXC_F_I2C_RX_CTRL0_RX_FLUSH_POS 7 /**< RX_CTRL0_RX_FLUSH Position */
-#define MXC_F_I2C_RX_CTRL0_RX_FLUSH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_RX_CTRL0_RX_FLUSH_POS)) /**< RX_CTRL0_RX_FLUSH \
- Mask */
-#define MXC_V_I2C_RX_CTRL0_RX_FLUSH_NOT_FLUSHED \
- ((uint32_t)0x0UL) /**< RX_CTRL0_RX_FLUSH_NOT_FLUSHED Value */
-#define MXC_S_I2C_RX_CTRL0_RX_FLUSH_NOT_FLUSHED \
- (MXC_V_I2C_RX_CTRL0_RX_FLUSH_NOT_FLUSHED \
- << MXC_F_I2C_RX_CTRL0_RX_FLUSH_POS) /**< \
- RX_CTRL0_RX_FLUSH_NOT_FLUSHED \
- Setting */
-#define MXC_V_I2C_RX_CTRL0_RX_FLUSH_FLUSH \
- ((uint32_t)0x1UL) /**< RX_CTRL0_RX_FLUSH_FLUSH Value */
-#define MXC_S_I2C_RX_CTRL0_RX_FLUSH_FLUSH \
- (MXC_V_I2C_RX_CTRL0_RX_FLUSH_FLUSH \
- << MXC_F_I2C_RX_CTRL0_RX_FLUSH_POS) /**< RX_CTRL0_RX_FLUSH_FLUSH \
- Setting */
-
-#define MXC_F_I2C_RX_CTRL0_RX_THRESH_POS 8 /**< RX_CTRL0_RX_THRESH Position */
-#define MXC_F_I2C_RX_CTRL0_RX_THRESH \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_RX_CTRL0_RX_THRESH_POS)) /**< RX_CTRL0_RX_THRESH \
- Mask */
-
-/**
- * Receive Control Register 1.
- */
-#define MXC_F_I2C_RX_CTRL1_RX_CNT_POS 0 /**< RX_CTRL1_RX_CNT Position */
-#define MXC_F_I2C_RX_CTRL1_RX_CNT \
- ((uint32_t)(0xFFUL \
- << MXC_F_I2C_RX_CTRL1_RX_CNT_POS)) /**< RX_CTRL1_RX_CNT \
- Mask */
-
-#define MXC_F_I2C_RX_CTRL1_RX_FIFO_POS 8 /**< RX_CTRL1_RX_FIFO Position */
-#define MXC_F_I2C_RX_CTRL1_RX_FIFO \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_RX_CTRL1_RX_FIFO_POS)) /**< RX_CTRL1_RX_FIFO \
- Mask */
-
-/**
- * Transmit Control Register 0.
- */
-#define MXC_F_I2C_TX_CTRL0_TX_PRELOAD_POS \
- 0 /**< TX_CTRL0_TX_PRELOAD Position \
- */
-#define MXC_F_I2C_TX_CTRL0_TX_PRELOAD \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_TX_CTRL0_TX_PRELOAD_POS)) /**< \
- TX_CTRL0_TX_PRELOAD \
- Mask */
-
-#define MXC_F_I2C_TX_CTRL0_TX_READY_MODE_POS \
- 1 /**< TX_CTRL0_TX_READY_MODE Position */
-#define MXC_F_I2C_TX_CTRL0_TX_READY_MODE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_TX_CTRL0_TX_READY_MODE_POS)) /**< \
- TX_CTRL0_TX_READY_MODE \
- Mask */
-#define MXC_V_I2C_TX_CTRL0_TX_READY_MODE_EN \
- ((uint32_t)0x0UL) /**< TX_CTRL0_TX_READY_MODE_EN Value */
-#define MXC_S_I2C_TX_CTRL0_TX_READY_MODE_EN \
- (MXC_V_I2C_TX_CTRL0_TX_READY_MODE_EN \
- << MXC_F_I2C_TX_CTRL0_TX_READY_MODE_POS) /**< \
- TX_CTRL0_TX_READY_MODE_EN \
- Setting */
-#define MXC_V_I2C_TX_CTRL0_TX_READY_MODE_DIS \
- ((uint32_t)0x1UL) /**< TX_CTRL0_TX_READY_MODE_DIS Value */
-#define MXC_S_I2C_TX_CTRL0_TX_READY_MODE_DIS \
- (MXC_V_I2C_TX_CTRL0_TX_READY_MODE_DIS \
- << MXC_F_I2C_TX_CTRL0_TX_READY_MODE_POS) /**< \
- TX_CTRL0_TX_READY_MODE_DIS \
- Setting */
-
-#define MXC_F_I2C_TX_CTRL0_TX_FLUSH_POS 7 /**< TX_CTRL0_TX_FLUSH Position */
-#define MXC_F_I2C_TX_CTRL0_TX_FLUSH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_TX_CTRL0_TX_FLUSH_POS)) /**< TX_CTRL0_TX_FLUSH \
- Mask */
-#define MXC_V_I2C_TX_CTRL0_TX_FLUSH_NOT_FLUSHED \
- ((uint32_t)0x0UL) /**< TX_CTRL0_TX_FLUSH_NOT_FLUSHED Value */
-#define MXC_S_I2C_TX_CTRL0_TX_FLUSH_NOT_FLUSHED \
- (MXC_V_I2C_TX_CTRL0_TX_FLUSH_NOT_FLUSHED \
- << MXC_F_I2C_TX_CTRL0_TX_FLUSH_POS) /**< \
- TX_CTRL0_TX_FLUSH_NOT_FLUSHED \
- Setting */
-#define MXC_V_I2C_TX_CTRL0_TX_FLUSH_FLUSH \
- ((uint32_t)0x1UL) /**< TX_CTRL0_TX_FLUSH_FLUSH Value */
-#define MXC_S_I2C_TX_CTRL0_TX_FLUSH_FLUSH \
- (MXC_V_I2C_TX_CTRL0_TX_FLUSH_FLUSH \
- << MXC_F_I2C_TX_CTRL0_TX_FLUSH_POS) /**< TX_CTRL0_TX_FLUSH_FLUSH \
- Setting */
-
-#define MXC_F_I2C_TX_CTRL0_TX_THRESH_POS 8 /**< TX_CTRL0_TX_THRESH Position */
-#define MXC_F_I2C_TX_CTRL0_TX_THRESH \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_TX_CTRL0_TX_THRESH_POS)) /**< TX_CTRL0_TX_THRESH \
- Mask */
-
-/**
- * Transmit Control Register 1.
- */
-#define MXC_F_I2C_TX_CTRL1_TX_READY_POS 0 /**< TX_CTRL1_TX_READY Position */
-#define MXC_F_I2C_TX_CTRL1_TX_READY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_TX_CTRL1_TX_READY_POS)) /**< TX_CTRL1_TX_READY \
- Mask */
-
-#define MXC_F_I2C_TX_CTRL1_TX_LAST_POS 1 /**< TX_CTRL1_TX_LAST Position */
-#define MXC_F_I2C_TX_CTRL1_TX_LAST \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_TX_CTRL1_TX_LAST_POS)) /**< TX_CTRL1_TX_LAST \
- Mask */
-#define MXC_V_I2C_TX_CTRL1_TX_LAST_HOLD_SCL_LOW \
- ((uint32_t)0x0UL) /**< TX_CTRL1_TX_LAST_HOLD_SCL_LOW Value */
-#define MXC_S_I2C_TX_CTRL1_TX_LAST_HOLD_SCL_LOW \
- (MXC_V_I2C_TX_CTRL1_TX_LAST_HOLD_SCL_LOW \
- << MXC_F_I2C_TX_CTRL1_TX_LAST_POS) /**< TX_CTRL1_TX_LAST_HOLD_SCL_LOW \
- Setting */
-#define MXC_V_I2C_TX_CTRL1_TX_LAST_END_TRANSACTION \
- ((uint32_t)0x1UL) /**< TX_CTRL1_TX_LAST_END_TRANSACTION Value */
-#define MXC_S_I2C_TX_CTRL1_TX_LAST_END_TRANSACTION \
- (MXC_V_I2C_TX_CTRL1_TX_LAST_END_TRANSACTION \
- << MXC_F_I2C_TX_CTRL1_TX_LAST_POS) /**< \
- TX_CTRL1_TX_LAST_END_TRANSACTION \
- Setting */
-
-#define MXC_F_I2C_TX_CTRL1_TX_FIFO_POS 8 /**< TX_CTRL1_TX_FIFO Position */
-#define MXC_F_I2C_TX_CTRL1_TX_FIFO \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_TX_CTRL1_TX_FIFO_POS)) /**< TX_CTRL1_TX_FIFO \
- Mask */
-
-/**
- * Data Register.
- */
-#define MXC_F_I2C_FIFO_DATA_POS 0 /**< FIFO_DATA Position */
-#define MXC_F_I2C_FIFO_DATA \
- ((uint32_t)(0xFFUL << MXC_F_I2C_FIFO_DATA_POS)) /**< FIFO_DATA Mask */
-
-/**
- * Master Control Register.
- */
-#define MXC_F_I2C_MASTER_CTRL_START_POS 0 /**< MASTER_CTRL_START Position */
-#define MXC_F_I2C_MASTER_CTRL_START \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_MASTER_CTRL_START_POS)) /**< MASTER_CTRL_START \
- Mask */
-
-#define MXC_F_I2C_MASTER_CTRL_RESTART_POS \
- 1 /**< MASTER_CTRL_RESTART Position \
- */
-#define MXC_F_I2C_MASTER_CTRL_RESTART \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_MASTER_CTRL_RESTART_POS)) /**< \
- MASTER_CTRL_RESTART \
- Mask */
-
-#define MXC_F_I2C_MASTER_CTRL_STOP_POS 2 /**< MASTER_CTRL_STOP Position */
-#define MXC_F_I2C_MASTER_CTRL_STOP \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_MASTER_CTRL_STOP_POS)) /**< MASTER_CTRL_STOP \
- Mask */
-
-#define MXC_F_I2C_MASTER_CTRL_SL_EX_ADDR_POS \
- 7 /**< MASTER_CTRL_SL_EX_ADDR Position */
-#define MXC_F_I2C_MASTER_CTRL_SL_EX_ADDR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_MASTER_CTRL_SL_EX_ADDR_POS)) /**< \
- MASTER_CTRL_SL_EX_ADDR \
- Mask */
-#define MXC_V_I2C_MASTER_CTRL_SL_EX_ADDR_7_BITS_ADDRESS \
- ((uint32_t)0x0UL) /**< MASTER_CTRL_SL_EX_ADDR_7_BITS_ADDRESS Value */
-#define MXC_S_I2C_MASTER_CTRL_SL_EX_ADDR_7_BITS_ADDRESS \
- (MXC_V_I2C_MASTER_CTRL_SL_EX_ADDR_7_BITS_ADDRESS \
- << MXC_F_I2C_MASTER_CTRL_SL_EX_ADDR_POS) /**< \
- MASTER_CTRL_SL_EX_ADDR_7_BITS_ADDRESS \
- Setting */
-#define MXC_V_I2C_MASTER_CTRL_SL_EX_ADDR_10_BITS_ADDRESS \
- ((uint32_t)0x1UL) /**< MASTER_CTRL_SL_EX_ADDR_10_BITS_ADDRESS Value */
-#define MXC_S_I2C_MASTER_CTRL_SL_EX_ADDR_10_BITS_ADDRESS \
- (MXC_V_I2C_MASTER_CTRL_SL_EX_ADDR_10_BITS_ADDRESS \
- << MXC_F_I2C_MASTER_CTRL_SL_EX_ADDR_POS) /**< \
- MASTER_CTRL_SL_EX_ADDR_10_BITS_ADDRESS \
- Setting */
-
-#define MXC_F_I2C_MASTER_CTRL_MASTER_CODE_POS \
- 8 /**< MASTER_CTRL_MASTER_CODE Position */
-#define MXC_F_I2C_MASTER_CTRL_MASTER_CODE \
- ((uint32_t)( \
- 0x7UL \
- << MXC_F_I2C_MASTER_CTRL_MASTER_CODE_POS)) /**< \
- MASTER_CTRL_MASTER_CODE \
- Mask */
-
-#define MXC_F_I2C_MASTER_CTRL_SCL_SPEED_UP_POS \
- 11 /**< MASTER_CTRL_SCL_SPEED_UP Position */
-#define MXC_F_I2C_MASTER_CTRL_SCL_SPEED_UP \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_MASTER_CTRL_SCL_SPEED_UP_POS)) /**< \
- MASTER_CTRL_SCL_SPEED_UP \
- Mask */
-#define MXC_V_I2C_MASTER_CTRL_SCL_SPEED_UP_EN \
- ((uint32_t)0x0UL) /**< MASTER_CTRL_SCL_SPEED_UP_EN Value */
-#define MXC_S_I2C_MASTER_CTRL_SCL_SPEED_UP_EN \
- (MXC_V_I2C_MASTER_CTRL_SCL_SPEED_UP_EN \
- << MXC_F_I2C_MASTER_CTRL_SCL_SPEED_UP_POS) /**< \
- MASTER_CTRL_SCL_SPEED_UP_EN \
- Setting */
-#define MXC_V_I2C_MASTER_CTRL_SCL_SPEED_UP_DIS \
- ((uint32_t)0x1UL) /**< MASTER_CTRL_SCL_SPEED_UP_DIS Value */
-#define MXC_S_I2C_MASTER_CTRL_SCL_SPEED_UP_DIS \
- (MXC_V_I2C_MASTER_CTRL_SCL_SPEED_UP_DIS \
- << MXC_F_I2C_MASTER_CTRL_SCL_SPEED_UP_POS) /**< \
- MASTER_CTRL_SCL_SPEED_UP_DIS \
- Setting */
-
-/**
- * Clock Low Register.
- */
-#define MXC_F_I2C_CLK_LO_CLK_LO_POS 0 /**< CLK_LO_CLK_LO Position */
-#define MXC_F_I2C_CLK_LO_CLK_LO \
- ((uint32_t)( \
- 0x1FFUL \
- << MXC_F_I2C_CLK_LO_CLK_LO_POS)) /**< CLK_LO_CLK_LO Mask */
-
-/**
- * Clock high Register.
- */
-#define MXC_F_I2C_CLK_HI_CKH_POS 0 /**< CLK_HI_CKH Position */
-#define MXC_F_I2C_CLK_HI_CKH \
- ((uint32_t)(0x1FFUL \
- << MXC_F_I2C_CLK_HI_CKH_POS)) /**< CLK_HI_CKH Mask */
-
-/**
- * HS-Mode Clock Control Register
- */
-#define MXC_F_I2C_HS_CLK_HS_CLK_LO_POS 0 /**< HS_CLK_HS_CLK_LO Position */
-#define MXC_F_I2C_HS_CLK_HS_CLK_LO \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_I2C_HS_CLK_HS_CLK_LO_POS)) /**< HS_CLK_HS_CLK_LO \
- Mask */
-
-#define MXC_F_I2C_HS_CLK_HS_CLK_HI_POS 8 /**< HS_CLK_HS_CLK_HI Position */
-#define MXC_F_I2C_HS_CLK_HS_CLK_HI \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_I2C_HS_CLK_HS_CLK_HI_POS)) /**< HS_CLK_HS_CLK_HI \
- Mask */
-
-/**
- * Timeout Register
- */
-#define MXC_F_I2C_TIMEOUT_TO_POS 0 /**< TIMEOUT_TO Position */
-#define MXC_F_I2C_TIMEOUT_TO \
- ((uint32_t)(0xFFFFUL \
- << MXC_F_I2C_TIMEOUT_TO_POS)) /**< TIMEOUT_TO Mask */
-
-/**
- * Slave Address Register.
- */
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_POS \
- 0 /**< SLAVE_ADDR_SLAVE_ADDR Position */
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR \
- ((uint32_t)( \
- 0x3FFUL \
- << MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_POS)) /**< \
- SLAVE_ADDR_SLAVE_ADDR \
- Mask */
-
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_DIS_POS \
- 10 /**< SLAVE_ADDR_SLAVE_ADDR_DIS Position */
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_DIS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_DIS_POS)) /**< \
- SLAVE_ADDR_SLAVE_ADDR_DIS \
- Mask */
-
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX_POS \
- 11 /**< SLAVE_ADDR_SLAVE_ADDR_IDX Position */
-#define MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX \
- ((uint32_t)( \
- 0xFUL \
- << MXC_F_I2C_SLAVE_ADDR_SLAVE_ADDR_IDX_POS)) /**< \
- SLAVE_ADDR_SLAVE_ADDR_IDX \
- Mask */
-
-#define MXC_F_I2C_SLAVE_ADDR_EX_ADDR_POS \
- 15 /**< SLAVE_ADDR_EX_ADDR Position \
- */
-#define MXC_F_I2C_SLAVE_ADDR_EX_ADDR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_I2C_SLAVE_ADDR_EX_ADDR_POS)) /**< SLAVE_ADDR_EX_ADDR \
- Mask */
-#define MXC_V_I2C_SLAVE_ADDR_EX_ADDR_7_BITS_ADDRESS \
- ((uint32_t)0x0UL) /**< SLAVE_ADDR_EX_ADDR_7_BITS_ADDRESS Value */
-#define MXC_S_I2C_SLAVE_ADDR_EX_ADDR_7_BITS_ADDRESS \
- (MXC_V_I2C_SLAVE_ADDR_EX_ADDR_7_BITS_ADDRESS \
- << MXC_F_I2C_SLAVE_ADDR_EX_ADDR_POS) /**< \
- SLAVE_ADDR_EX_ADDR_7_BITS_ADDRESS \
- Setting */
-#define MXC_V_I2C_SLAVE_ADDR_EX_ADDR_10_BITS_ADDRESS \
- ((uint32_t)0x1UL) /**< SLAVE_ADDR_EX_ADDR_10_BITS_ADDRESS Value */
-#define MXC_S_I2C_SLAVE_ADDR_EX_ADDR_10_BITS_ADDRESS \
- (MXC_V_I2C_SLAVE_ADDR_EX_ADDR_10_BITS_ADDRESS \
- << MXC_F_I2C_SLAVE_ADDR_EX_ADDR_POS) /**< \
- SLAVE_ADDR_EX_ADDR_10_BITS_ADDRESS \
- Setting */
-
-/**
- * DMA Register.
- */
-#define MXC_F_I2C_DMA_TX_EN_POS 0 /**< DMA_TX_EN Position */
-#define MXC_F_I2C_DMA_TX_EN \
- ((uint32_t)(0x1UL << MXC_F_I2C_DMA_TX_EN_POS)) /**< DMA_TX_EN Mask */
-#define MXC_V_I2C_DMA_TX_EN_DIS ((uint32_t)0x0UL) /**< DMA_TX_EN_DIS Value */
-#define MXC_S_I2C_DMA_TX_EN_DIS \
- (MXC_V_I2C_DMA_TX_EN_DIS \
- << MXC_F_I2C_DMA_TX_EN_POS) /**< DMA_TX_EN_DIS Setting */
-#define MXC_V_I2C_DMA_TX_EN_EN ((uint32_t)0x1UL) /**< DMA_TX_EN_EN Value */
-#define MXC_S_I2C_DMA_TX_EN_EN \
- (MXC_V_I2C_DMA_TX_EN_EN \
- << MXC_F_I2C_DMA_TX_EN_POS) /**< DMA_TX_EN_EN Setting */
-
-#define MXC_F_I2C_DMA_RX_EN_POS 1 /**< DMA_RX_EN Position */
-#define MXC_F_I2C_DMA_RX_EN \
- ((uint32_t)(0x1UL << MXC_F_I2C_DMA_RX_EN_POS)) /**< DMA_RX_EN Mask */
-#define MXC_V_I2C_DMA_RX_EN_DIS ((uint32_t)0x0UL) /**< DMA_RX_EN_DIS Value */
-#define MXC_S_I2C_DMA_RX_EN_DIS \
- (MXC_V_I2C_DMA_RX_EN_DIS \
- << MXC_F_I2C_DMA_RX_EN_POS) /**< DMA_RX_EN_DIS Setting */
-#define MXC_V_I2C_DMA_RX_EN_EN ((uint32_t)0x1UL) /**< DMA_RX_EN_EN Value */
-#define MXC_S_I2C_DMA_RX_EN_EN \
- (MXC_V_I2C_DMA_RX_EN_EN \
- << MXC_F_I2C_DMA_RX_EN_POS) /**< DMA_RX_EN_EN Setting */
-
-#endif /* _I2C_REGS_H_ */
diff --git a/chip/max32660/icc_regs.h b/chip/max32660/icc_regs.h
deleted file mode 100644
index 5f40e4203d..0000000000
--- a/chip/max32660/icc_regs.h
+++ /dev/null
@@ -1,143 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the ICC */
-
-#ifndef _ICC_REGS_H_
-#define _ICC_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/**
- * Structure type to access the ICC Registers.
- */
-typedef struct {
- __I uint32_t cache_id; /**< <tt>\b 0x0000:<\tt> ICC CACHE_ID Register */
- __I uint32_t memcfg; /**< <tt>\b 0x0004:<\tt> ICC MEMCFG Register */
- __R uint32_t rsv_0x8_0xff[62];
- __IO uint32_t
- cache_ctrl; /**< <tt>\b 0x0100:<\tt> ICC CACHE_CTRL Register */
- __R uint32_t rsv_0x104_0x6ff[383];
- __IO uint32_t
- invalidate; /**< <tt>\b 0x0700:<\tt> ICC INVALIDATE Register */
-} mxc_icc_regs_t;
-
-/**
- * ICC Peripheral Register Offsets from the ICC Base Peripheral
- * Address.
- */
-#define MXC_R_ICC_CACHE_ID \
- ((uint32_t)0x00000000UL) /**< Offset from ICC Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_ICC_MEMCFG \
- ((uint32_t)0x00000004UL) /**< Offset from ICC Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_ICC_CACHE_CTRL \
- ((uint32_t)0x00000100UL) /**< Offset from ICC Base Address: <tt> \
- 0x0x100 */
-#define MXC_R_ICC_INVALIDATE \
- ((uint32_t)0x00000700UL) /**< Offset from ICC Base Address: <tt> \
- 0x0x700 */
-
-/**
- * Cache ID Register.
- */
-#define MXC_F_ICC_CACHE_ID_RELNUM_POS 0 /**< CACHE_ID_RELNUM Position */
-#define MXC_F_ICC_CACHE_ID_RELNUM \
- ((uint32_t)( \
- 0x3FUL << MXC_F_ICC_CACHE_ID_RELNUM_POS)) /**< CACHE_ID_RELNUM \
- Mask */
-
-#define MXC_F_ICC_CACHE_ID_PARTNUM_POS 6 /**< CACHE_ID_PARTNUM Position */
-#define MXC_F_ICC_CACHE_ID_PARTNUM \
- ((uint32_t)(0xFUL \
- << MXC_F_ICC_CACHE_ID_PARTNUM_POS)) /**< CACHE_ID_PARTNUM \
- Mask */
-
-#define MXC_F_ICC_CACHE_ID_CCHID_POS 10 /**< CACHE_ID_CCHID Position */
-#define MXC_F_ICC_CACHE_ID_CCHID \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_ICC_CACHE_ID_CCHID_POS)) /**< CACHE_ID_CCHID Mask */
-
-/**
- * Memory Configuration Register.
- */
-#define MXC_F_ICC_MEMCFG_CCHSZ_POS 0 /**< MEMCFG_CCHSZ Position */
-#define MXC_F_ICC_MEMCFG_CCHSZ \
- ((uint32_t)(0xFFFFUL \
- << MXC_F_ICC_MEMCFG_CCHSZ_POS)) /**< MEMCFG_CCHSZ Mask */
-
-#define MXC_F_ICC_MEMCFG_MEMSZ_POS 16 /**< MEMCFG_MEMSZ Position */
-#define MXC_F_ICC_MEMCFG_MEMSZ \
- ((uint32_t)(0xFFFFUL \
- << MXC_F_ICC_MEMCFG_MEMSZ_POS)) /**< MEMCFG_MEMSZ Mask */
-
-/**
- * Cache Control and Status Register.
- */
-#define MXC_F_ICC_CACHE_CTRL_CACHE_EN_POS \
- 0 /**< CACHE_CTRL_CACHE_EN Position \
- */
-#define MXC_F_ICC_CACHE_CTRL_CACHE_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_ICC_CACHE_CTRL_CACHE_EN_POS)) /**< \
- CACHE_CTRL_CACHE_EN \
- Mask */
-#define MXC_V_ICC_CACHE_CTRL_CACHE_EN_DIS \
- ((uint32_t)0x0UL) /**< CACHE_CTRL_CACHE_EN_DIS Value */
-#define MXC_S_ICC_CACHE_CTRL_CACHE_EN_DIS \
- (MXC_V_ICC_CACHE_CTRL_CACHE_EN_DIS \
- << MXC_F_ICC_CACHE_CTRL_CACHE_EN_POS) /**< CACHE_CTRL_CACHE_EN_DIS \
- Setting */
-#define MXC_V_ICC_CACHE_CTRL_CACHE_EN_EN \
- ((uint32_t)0x1UL) /**< CACHE_CTRL_CACHE_EN_EN Value */
-#define MXC_S_ICC_CACHE_CTRL_CACHE_EN_EN \
- (MXC_V_ICC_CACHE_CTRL_CACHE_EN_EN \
- << MXC_F_ICC_CACHE_CTRL_CACHE_EN_POS) /**< CACHE_CTRL_CACHE_EN_EN \
- Setting */
-
-#define MXC_F_ICC_CACHE_CTRL_CACHE_RDY_POS \
- 16 /**< CACHE_CTRL_CACHE_RDY Position */
-#define MXC_F_ICC_CACHE_CTRL_CACHE_RDY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_ICC_CACHE_CTRL_CACHE_RDY_POS)) /**< \
- CACHE_CTRL_CACHE_RDY \
- Mask */
-#define MXC_V_ICC_CACHE_CTRL_CACHE_RDY_NOTREADY \
- ((uint32_t)0x0UL) /**< CACHE_CTRL_CACHE_RDY_NOTREADY Value */
-#define MXC_S_ICC_CACHE_CTRL_CACHE_RDY_NOTREADY \
- (MXC_V_ICC_CACHE_CTRL_CACHE_RDY_NOTREADY \
- << MXC_F_ICC_CACHE_CTRL_CACHE_RDY_POS) /**< \
- CACHE_CTRL_CACHE_RDY_NOTREADY \
- Setting */
-#define MXC_V_ICC_CACHE_CTRL_CACHE_RDY_READY \
- ((uint32_t)0x1UL) /**< CACHE_CTRL_CACHE_RDY_READY Value */
-#define MXC_S_ICC_CACHE_CTRL_CACHE_RDY_READY \
- (MXC_V_ICC_CACHE_CTRL_CACHE_RDY_READY \
- << MXC_F_ICC_CACHE_CTRL_CACHE_RDY_POS) /**< \
- CACHE_CTRL_CACHE_RDY_READY \
- Setting */
-
-#endif /* _ICC_REGS_H_ */
diff --git a/chip/max32660/pwrseq_regs.h b/chip/max32660/pwrseq_regs.h
deleted file mode 100644
index f323b4568c..0000000000
--- a/chip/max32660/pwrseq_regs.h
+++ /dev/null
@@ -1,489 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the PWRSEQ Peripheral */
-
-#ifndef _PWRSEQ_REGS_H_
-#define _PWRSEQ_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#if defined(__ICCARM__)
-#pragma system_include
-#endif
-
-#if defined(__CC_ARM)
-#pragma anon_unions
-#endif
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/* **** Definitions **** */
-
-/**
- * mxc_pwrseq_regs_t
- * Registers, Bit Masks and Bit Positions for the PWRSEQ Peripheral
- * Module.
- */
-
-/**
- * pwrseq_registers
- * Structure type to access the PWRSEQ Registers.
- */
-typedef struct {
- __IO uint32_t lp_ctrl; /**< <tt>\b 0x00:</tt> PWRSEQ LP_CTRL Register */
- __IO uint32_t
- lp_wakefl; /**< <tt>\b 0x04:</tt> PWRSEQ LP_WAKEFL Register */
- __IO uint32_t lpwk_en; /**< <tt>\b 0x08:</tt> PWRSEQ LPWK_EN Register */
- __R uint32_t rsv_0xc_0x3f[13];
- __IO uint32_t lpmemsd; /**< <tt>\b 0x40:</tt> PWRSEQ LPMEMSD Register */
-} mxc_pwrseq_regs_t;
-
-/**
- * Register offsets for module PWRSEQ
- * PWRSEQ Peripheral Register Offsets from the PWRSEQ Base
- */
-#define MXC_R_PWRSEQ_LP_CTRL \
- ((uint32_t)0x00000000UL) /**< Offset from PWRSEQ Base Address: <tt> \ \
- \ \ \ 0x0000</tt> */
-#define MXC_R_PWRSEQ_LP_WAKEFL \
- ((uint32_t)0x00000004UL) /**< Offset from PWRSEQ Base Address: <tt> \ \
- \ \ \ 0x0004</tt> */
-#define MXC_R_PWRSEQ_LPWK_EN \
- ((uint32_t)0x00000008UL) /**< Offset from PWRSEQ Base Address: <tt> \ \
- \ \ \ 0x0008</tt> */
-#define MXC_R_PWRSEQ_LPMEMSD \
- ((uint32_t)0x00000040UL) /**< Offset from PWRSEQ Base Address: <tt> \ \
- \ \ \ 0x0040</tt> */
-
-/**
- * pwrseq_registers
- * Low Power Control Register.
- */
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL0_POS \
- 0 /**< LP_CTRL_RAMRET_SEL0 Position */
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL0 \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL0_POS)) /**< \ \ \ \ \
- LP_CTRL_RAMRET_SEL0 \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL0_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_RAMRET_SEL0_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL0_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL0_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL0_POS) /**< LP_CTRL_RAMRET_SEL0_DIS \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL0_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_RAMRET_SEL0_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL0_EN \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL0_EN \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL0_POS) /**< LP_CTRL_RAMRET_SEL0_EN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL1_POS \
- 1 /**< LP_CTRL_RAMRET_SEL1 Position */
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL1 \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL1_POS)) /**< \ \ \ \ \
- LP_CTRL_RAMRET_SEL1 \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL1_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_RAMRET_SEL1_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL1_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL1_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL1_POS) /**< LP_CTRL_RAMRET_SEL1_DIS \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL1_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_RAMRET_SEL1_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL1_EN \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL1_EN \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL1_POS) /**< LP_CTRL_RAMRET_SEL1_EN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL2_POS \
- 2 /**< LP_CTRL_RAMRET_SEL2 Position */
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL2 \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL2_POS)) /**< \ \ \ \ \
- LP_CTRL_RAMRET_SEL2 \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL2_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_RAMRET_SEL2_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL2_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL2_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL2_POS) /**< LP_CTRL_RAMRET_SEL2_DIS \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL2_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_RAMRET_SEL2_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL2_EN \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL2_EN \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL2_POS) /**< LP_CTRL_RAMRET_SEL2_EN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL3_POS \
- 3 /**< LP_CTRL_RAMRET_SEL3 Position */
-#define MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL3 \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL3_POS)) /**< \ \ \ \ \
- LP_CTRL_RAMRET_SEL3 \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL3_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_RAMRET_SEL3_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL3_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL3_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL3_POS) /**< LP_CTRL_RAMRET_SEL3_DIS \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL3_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_RAMRET_SEL3_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RAMRET_SEL3_EN \
- (MXC_V_PWRSEQ_LP_CTRL_RAMRET_SEL3_EN \
- << MXC_F_PWRSEQ_LP_CTRL_RAMRET_SEL3_POS) /**< LP_CTRL_RAMRET_SEL3_EN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_OVR_POS 4 /**< LP_CTRL_OVR Position */
-#define MXC_F_PWRSEQ_LP_CTRL_OVR \
- ((uint32_t)(0x3UL \
- << MXC_F_PWRSEQ_LP_CTRL_OVR_POS)) /**< LP_CTRL_OVR Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_OVR_0_9V \
- ((uint32_t)0x0UL) /**< LP_CTRL_OVR_0_9V Value */
-#define MXC_S_PWRSEQ_LP_CTRL_OVR_0_9V \
- (MXC_V_PWRSEQ_LP_CTRL_OVR_0_9V \
- << MXC_F_PWRSEQ_LP_CTRL_OVR_POS) /**< LP_CTRL_OVR_0_9V Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_OVR_1_0V \
- ((uint32_t)0x1UL) /**< LP_CTRL_OVR_1_0V Value */
-#define MXC_S_PWRSEQ_LP_CTRL_OVR_1_0V \
- (MXC_V_PWRSEQ_LP_CTRL_OVR_1_0V \
- << MXC_F_PWRSEQ_LP_CTRL_OVR_POS) /**< LP_CTRL_OVR_1_0V Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_OVR_1_1V \
- ((uint32_t)0x2UL) /**< LP_CTRL_OVR_1_1V Value */
-#define MXC_S_PWRSEQ_LP_CTRL_OVR_1_1V \
- (MXC_V_PWRSEQ_LP_CTRL_OVR_1_1V \
- << MXC_F_PWRSEQ_LP_CTRL_OVR_POS) /**< LP_CTRL_OVR_1_1V Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_POS \
- 6 /**< LP_CTRL_VCORE_DET_BYPASS Position */
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_POS)) /**< \ \ \ \ \
- LP_CTRL_VCORE_DET_BYPASS \
- \ \
- \ \ \ \ \
- Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_ENABLED \
- ((uint32_t)0x0UL) /**< LP_CTRL_VCORE_DET_BYPASS_ENABLED Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_ENABLED \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_ENABLED \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_DET_BYPASS_ENABLED \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_DISABLE \
- ((uint32_t)0x1UL) /**< LP_CTRL_VCORE_DET_BYPASS_DISABLE Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_DISABLE \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_DISABLE \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_DET_BYPASS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_DET_BYPASS_DISABLE \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_RETREG_EN_POS \
- 8 /**< LP_CTRL_RETREG_EN Position \ \ \ \ \
- */
-#define MXC_F_PWRSEQ_LP_CTRL_RETREG_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_RETREG_EN_POS)) /**< LP_CTRL_RETREG_EN \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_RETREG_EN_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_RETREG_EN_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RETREG_EN_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_RETREG_EN_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_RETREG_EN_POS) /**< LP_CTRL_RETREG_EN_DIS \ \ \
- \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_RETREG_EN_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_RETREG_EN_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_RETREG_EN_EN \
- (MXC_V_PWRSEQ_LP_CTRL_RETREG_EN_EN \
- << MXC_F_PWRSEQ_LP_CTRL_RETREG_EN_POS) /**< LP_CTRL_RETREG_EN_EN \ \ \
- \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_FAST_WK_EN_POS \
- 10 /**< LP_CTRL_FAST_WK_EN Position */
-#define MXC_F_PWRSEQ_LP_CTRL_FAST_WK_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_FAST_WK_EN_POS)) /**< \ \ \ \ \
- LP_CTRL_FAST_WK_EN \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_FAST_WK_EN_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_FAST_WK_EN_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_FAST_WK_EN_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_FAST_WK_EN_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_FAST_WK_EN_POS) /**< LP_CTRL_FAST_WK_EN_DIS \ \
- \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_FAST_WK_EN_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_FAST_WK_EN_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_FAST_WK_EN_EN \
- (MXC_V_PWRSEQ_LP_CTRL_FAST_WK_EN_EN \
- << MXC_F_PWRSEQ_LP_CTRL_FAST_WK_EN_POS) /**< LP_CTRL_FAST_WK_EN_EN \ \
- \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_BG_OFF_POS 11 /**< LP_CTRL_BG_OFF Position */
-#define MXC_F_PWRSEQ_LP_CTRL_BG_OFF \
- ((uint32_t)( \
- 0x1UL << MXC_F_PWRSEQ_LP_CTRL_BG_OFF_POS)) /**< LP_CTRL_BG_OFF \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_BG_OFF_ON \
- ((uint32_t)0x0UL) /**< LP_CTRL_BG_OFF_ON Value */
-#define MXC_S_PWRSEQ_LP_CTRL_BG_OFF_ON \
- (MXC_V_PWRSEQ_LP_CTRL_BG_OFF_ON \
- << MXC_F_PWRSEQ_LP_CTRL_BG_OFF_POS) /**< LP_CTRL_BG_OFF_ON Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_BG_OFF_OFF \
- ((uint32_t)0x1UL) /**< LP_CTRL_BG_OFF_OFF Value */
-#define MXC_S_PWRSEQ_LP_CTRL_BG_OFF_OFF \
- (MXC_V_PWRSEQ_LP_CTRL_BG_OFF_OFF \
- << MXC_F_PWRSEQ_LP_CTRL_BG_OFF_POS) /**< LP_CTRL_BG_OFF_OFF Setting \ \
- * \ \
- * \ \ \
- * \ \ \ \
- */
-
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_POR_DIS_POS \
- 12 /**< LP_CTRL_VCORE_POR_DIS Position */
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_POR_DIS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_POR_DIS_POS)) /**< \ \ \ \ \
- LP_CTRL_VCORE_POR_DIS \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_POR_DIS_DIS \
- ((uint32_t)0x0UL) /**< LP_CTRL_VCORE_POR_DIS_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_POR_DIS_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_POR_DIS_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_POR_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_POR_DIS_DIS \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_POR_DIS_EN \
- ((uint32_t)0x1UL) /**< LP_CTRL_VCORE_POR_DIS_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_POR_DIS_EN \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_POR_DIS_EN \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_POR_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_POR_DIS_EN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_LDO_DIS_POS 16 /**< LP_CTRL_LDO_DIS Position */
-#define MXC_F_PWRSEQ_LP_CTRL_LDO_DIS \
- ((uint32_t)(0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_LDO_DIS_POS)) /**< LP_CTRL_LDO_DIS \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_LDO_DIS_EN \
- ((uint32_t)0x0UL) /**< LP_CTRL_LDO_DIS_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_LDO_DIS_EN \
- (MXC_V_PWRSEQ_LP_CTRL_LDO_DIS_EN \
- << MXC_F_PWRSEQ_LP_CTRL_LDO_DIS_POS) /**< LP_CTRL_LDO_DIS_EN Setting \
- * \ \
- * \ \ \
- * \ \ \ \
- * \ \ \ \ \
- */
-#define MXC_V_PWRSEQ_LP_CTRL_LDO_DIS_DIS \
- ((uint32_t)0x1UL) /**< LP_CTRL_LDO_DIS_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_LDO_DIS_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_LDO_DIS_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_LDO_DIS_POS) /**< LP_CTRL_LDO_DIS_DIS Setting \
- * \ \
- * \ \ \
- * \ \ \ \
- * \ \ \ \ \
- */
-
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_POS \
- 20 /**< LP_CTRL_VCORE_SVM_DIS Position */
-#define MXC_F_PWRSEQ_LP_CTRL_VCORE_SVM_DIS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_POS)) /**< \ \ \ \ \
- LP_CTRL_VCORE_SVM_DIS \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_EN \
- ((uint32_t)0x0UL) /**< LP_CTRL_VCORE_SVM_DIS_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_EN \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_EN \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_SVM_DIS_EN \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_DIS \
- ((uint32_t)0x1UL) /**< LP_CTRL_VCORE_SVM_DIS_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_VCORE_SVM_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VCORE_SVM_DIS_DIS \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_POS \
- 25 /**< LP_CTRL_VDDIO_POR_DIS Position */
-#define MXC_F_PWRSEQ_LP_CTRL_VDDIO_POR_DIS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_POS)) /**< \ \ \ \ \
- LP_CTRL_VDDIO_POR_DIS \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_EN \
- ((uint32_t)0x0UL) /**< LP_CTRL_VDDIO_POR_DIS_EN Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_EN \
- (MXC_V_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_EN \
- << MXC_F_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VDDIO_POR_DIS_EN \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_DIS \
- ((uint32_t)0x1UL) /**< LP_CTRL_VDDIO_POR_DIS_DIS Value */
-#define MXC_S_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_DIS \
- (MXC_V_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_DIS \
- << MXC_F_PWRSEQ_LP_CTRL_VDDIO_POR_DIS_POS) /**< \ \ \ \ \
- LP_CTRL_VDDIO_POR_DIS_DIS \
- \ \ \ \ Setting */
-
-/**
- * pwrseq_registers
- * Low Power Mode Wakeup Flags for GPIO0
- */
-#define MXC_F_PWRSEQ_LP_WAKEFL_WAKEST_POS 0 /**< LP_WAKEFL_WAKEST Position */
-#define MXC_F_PWRSEQ_LP_WAKEFL_WAKEST \
- ((uint32_t)( \
- 0x3FFFUL \
- << MXC_F_PWRSEQ_LP_WAKEFL_WAKEST_POS)) /**< LP_WAKEFL_WAKEST \ \
- \ \ \ Mask */
-
-/**
- * pwrseq_registers
- * Low Power I/O Wakeup Enable Register 0. This register enables low
- * power wakeup functionality for GPIO0.
- */
-#define MXC_F_PWRSEQ_LPWK_EN_WAKEEN_POS 0 /**< LPWK_EN_WAKEEN Position */
-#define MXC_F_PWRSEQ_LPWK_EN_WAKEEN \
- ((uint32_t)(0x3FFFUL \
- << MXC_F_PWRSEQ_LPWK_EN_WAKEEN_POS)) /**< LPWK_EN_WAKEEN \ \
- \ \ \ Mask */
-
-/**
- * pwrseq_registers
- * Low Power Memory Shutdown Control.
- */
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM0_OFF_POS \
- 0 /**< LPMEMSD_SRAM0_OFF Position \ \ \ \ \
- */
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM0_OFF \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM0_OFF_POS)) /**< LPMEMSD_SRAM0_OFF \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM0_OFF_NORMAL \
- ((uint32_t)0x0UL) /**< LPMEMSD_SRAM0_OFF_NORMAL Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM0_OFF_NORMAL \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM0_OFF_NORMAL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM0_OFF_POS) /**< LPMEMSD_SRAM0_OFF_NORMAL \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM0_OFF_SHUTDOWN \
- ((uint32_t)0x1UL) /**< LPMEMSD_SRAM0_OFF_SHUTDOWN Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM0_OFF_SHUTDOWN \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM0_OFF_SHUTDOWN \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM0_OFF_POS) /**< \ \ \ \ \
- LPMEMSD_SRAM0_OFF_SHUTDOWN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM1_OFF_POS \
- 1 /**< LPMEMSD_SRAM1_OFF Position \ \ \ \ \
- */
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM1_OFF \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM1_OFF_POS)) /**< LPMEMSD_SRAM1_OFF \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM1_OFF_NORMAL \
- ((uint32_t)0x0UL) /**< LPMEMSD_SRAM1_OFF_NORMAL Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM1_OFF_NORMAL \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM1_OFF_NORMAL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM1_OFF_POS) /**< LPMEMSD_SRAM1_OFF_NORMAL \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM1_OFF_SHUTDOWN \
- ((uint32_t)0x1UL) /**< LPMEMSD_SRAM1_OFF_SHUTDOWN Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM1_OFF_SHUTDOWN \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM1_OFF_SHUTDOWN \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM1_OFF_POS) /**< \ \ \ \ \
- LPMEMSD_SRAM1_OFF_SHUTDOWN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM2_OFF_POS \
- 2 /**< LPMEMSD_SRAM2_OFF Position \ \ \ \ \
- */
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM2_OFF \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM2_OFF_POS)) /**< LPMEMSD_SRAM2_OFF \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM2_OFF_NORMAL \
- ((uint32_t)0x0UL) /**< LPMEMSD_SRAM2_OFF_NORMAL Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM2_OFF_NORMAL \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM2_OFF_NORMAL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM2_OFF_POS) /**< LPMEMSD_SRAM2_OFF_NORMAL \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM2_OFF_SHUTDOWN \
- ((uint32_t)0x1UL) /**< LPMEMSD_SRAM2_OFF_SHUTDOWN Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM2_OFF_SHUTDOWN \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM2_OFF_SHUTDOWN \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM2_OFF_POS) /**< \ \ \ \ \
- LPMEMSD_SRAM2_OFF_SHUTDOWN \
- \ \ \ \ Setting */
-
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM3_OFF_POS \
- 3 /**< LPMEMSD_SRAM3_OFF Position \ \ \ \ \
- */
-#define MXC_F_PWRSEQ_LPMEMSD_SRAM3_OFF \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM3_OFF_POS)) /**< LPMEMSD_SRAM3_OFF \
- \ \ \ \ Mask */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM3_OFF_NORMAL \
- ((uint32_t)0x0UL) /**< LPMEMSD_SRAM3_OFF_NORMAL Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM3_OFF_NORMAL \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM3_OFF_NORMAL \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM3_OFF_POS) /**< LPMEMSD_SRAM3_OFF_NORMAL \
- \ \ \ \ Setting */
-#define MXC_V_PWRSEQ_LPMEMSD_SRAM3_OFF_SHUTDOWN \
- ((uint32_t)0x1UL) /**< LPMEMSD_SRAM3_OFF_SHUTDOWN Value */
-#define MXC_S_PWRSEQ_LPMEMSD_SRAM3_OFF_SHUTDOWN \
- (MXC_V_PWRSEQ_LPMEMSD_SRAM3_OFF_SHUTDOWN \
- << MXC_F_PWRSEQ_LPMEMSD_SRAM3_OFF_POS) /**< \ \ \ \ \
- LPMEMSD_SRAM3_OFF_SHUTDOWN \
- \ \ \ \ Setting */
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* _PWRSEQ_REGS_H_ */
diff --git a/chip/max32660/registers.h b/chip/max32660/registers.h
deleted file mode 100644
index e444888fa0..0000000000
--- a/chip/max32660/registers.h
+++ /dev/null
@@ -1,224 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Register map, needed for a common include file */
-
-#ifndef __CROS_EC_REGISTERS_H
-#define __CROS_EC_REGISTERS_H
-
-#include <stdint.h>
-
-#define EC_PF_IRQn 0 /* 0x10 0x0040 16: Power Fail */
-#define EC_WDT0_IRQn 1 /* 0x11 0x0044 17: Watchdog 0 */
-#define EC_RSV00_IRQn 2 /* 0x12 0x0048 18: RSV00 */
-#define EC_RTC_IRQn 3 /* 0x13 0x004C 19: RTC */
-#define EC_RSV1_IRQn 4 /* 0x14 0x0050 20: RSV1 */
-#define EC_TMR0_IRQn 5 /* 0x15 0x0054 21: Timer 0 */
-#define EC_TMR1_IRQn 6 /* 0x16 0x0058 22: Timer 1 */
-#define EC_TMR2_IRQn 7 /* 0x17 0x005C 23: Timer 2 */
-#define EC_RSV02_IRQn 8 /* 0x18 0x0060 24: RSV02 */
-#define EC_RSV03_IRQn 9 /* 0x19 0x0064 25: RSV03 */
-#define EC_RSV04_IRQn 10 /* 0x1A 0x0068 26: RSV04 */
-#define EC_RSV05_IRQn 11 /* 0x1B 0x006C 27: RSV05 */
-#define EC_RSV06_IRQn 12 /* 0x1C 0x0070 28: RSV06 */
-#define EC_I2C0_IRQn 13 /* 0x1D 0x0074 29: I2C0 */
-#define EC_UART0_IRQn 14 /* 0x1E 0x0078 30: UART 0 */
-#define EC_UART1_IRQn 15 /* 0x1F 0x007C 31: UART 1 */
-#define EC_SPI17Y_IRQn 16 /* 0x20 0x0080 32: SPI17Y */
-#define EC_SPIMSS_IRQn 17 /* 0x21 0x0084 33: SPIMSS */
-#define EC_RSV07_IRQn 18 /* 0x22 0x0088 34: RSV07 */
-#define EC_RSV08_IRQn 19 /* 0x23 0x008C 35: RSV08 */
-#define EC_RSV09_IRQn 20 /* 0x24 0x0090 36: RSV09 */
-#define EC_RSV10_IRQn 21 /* 0x25 0x0094 37: RSV10 */
-#define EC_RSV11_IRQn 22 /* 0x26 0x0098 38: RSV11 */
-#define EC_FLC_IRQn 23 /* 0x27 0x009C 39: FLC */
-#define EC_GPIO0_IRQn 24 /* 0x28 0x00A0 40: GPIO0 */
-#define EC_RSV12_IRQn 25 /* 0x29 0x00A4 41: RSV12 */
-#define EC_RSV13_IRQn 26 /* 0x2A 0x00A8 42: RSV13 */
-#define EC_RSV14_IRQn 27 /* 0x2B 0x00AC 43: RSV14 */
-#define EC_DMA0_IRQn 28 /* 0x2C 0x00B0 44: DMA0 */
-#define EC_DMA1_IRQn 29 /* 0x2D 0x00B4 45: DMA1 */
-#define EC_DMA2_IRQn 30 /* 0x2E 0x00B8 46: DMA2 */
-#define EC_DMA3_IRQn 31 /* 0x2F 0x00BC 47: DMA3 */
-#define EC_RSV15_IRQn 32 /* 0x30 0x00C0 48: RSV15 */
-#define EC_RSV16_IRQn 33 /* 0x31 0x00C4 49: RSV16 */
-#define EC_RSV17_IRQn 34 /* 0x32 0x00C8 50: RSV17 */
-#define EC_RSV18_IRQn 35 /* 0x33 0x00CC 51: RSV18 */
-#define EC_I2C1_IRQn 36 /* 0x34 0x00D0 52: I2C1 */
-#define EC_RSV19_IRQn 37 /* 0x35 0x00D4 53: RSV19 */
-#define EC_RSV20_IRQn 38 /* 0x36 0x00D8 54: RSV20 */
-#define EC_RSV21_IRQn 39 /* 0x37 0x00DC 55: RSV21 */
-#define EC_RSV22_IRQn 40 /* 0x38 0x00E0 56: RSV22 */
-#define EC_RSV23_IRQn 41 /* 0x39 0x00E4 57: RSV23 */
-#define EC_RSV24_IRQn 42 /* 0x3A 0x00E8 58: RSV24 */
-#define EC_RSV25_IRQn 43 /* 0x3B 0x00EC 59: RSV25 */
-#define EC_RSV26_IRQn 44 /* 0x3C 0x00F0 60: RSV26 */
-#define EC_RSV27_IRQn 45 /* 0x3D 0x00F4 61: RSV27 */
-#define EC_RSV28_IRQn 46 /* 0x3E 0x00F8 62: RSV28 */
-#define EC_RSV29_IRQn 47 /* 0x3F 0x00FC 63: RSV29 */
-#define EC_RSV30_IRQn 48 /* 0x40 0x0100 64: RSV30 */
-#define EC_RSV31_IRQn 49 /* 0x41 0x0104 65: RSV31 */
-#define EC_RSV32_IRQn 50 /* 0x42 0x0108 66: RSV32 */
-#define EC_RSV33_IRQn 51 /* 0x43 0x010C 67: RSV33 */
-#define EC_RSV34_IRQn 52 /* 0x44 0x0110 68: RSV34 */
-#define EC_RSV35_IRQn 53 /* 0x45 0x0114 69: RSV35 */
-#define EC_GPIOWAKE_IRQn 54 /* 0x46 0x0118 70: GPIO Wakeup */
-
-#ifndef HIRC96_FREQ
-#define HIRC96_FREQ 96000000
-#endif
-
-extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
-#ifndef PeripheralClock
-#define PeripheralClock \
- (SystemCoreClock / \
- 2) /*!< Peripheral Clock Frequency \
- */
-#endif
-
-#define MXC_FLASH_MEM_BASE 0x00000000UL
-#define MXC_FLASH_PAGE_SIZE 0x00002000UL
-#define MXC_FLASH_MEM_SIZE 0x00040000UL
-#define MXC_INFO_MEM_BASE 0x00040000UL
-#define MXC_INFO_MEM_SIZE 0x00001000UL
-#define MXC_SRAM_MEM_BASE 0x20000000UL
-#define MXC_SRAM_MEM_SIZE 0x00018000UL
-
-/*
- Base addresses and configuration settings for all MAX32660 peripheral
- modules.
-*/
-
-/******************************************************************************/
-/* Global control */
-#define MXC_BASE_GCR ((uint32_t)0x40000000UL)
-#define MXC_GCR ((mxc_gcr_regs_t *)MXC_BASE_GCR)
-
-/******************************************************************************/
-/* Non-battery backed SI Registers */
-#define MXC_BASE_SIR ((uint32_t)0x40000400UL)
-#define MXC_SIR ((mxc_sir_regs_t *)MXC_BASE_SIR)
-
-/******************************************************************************/
-/* Watchdog */
-#define MXC_BASE_WDT0 ((uint32_t)0x40003000UL)
-#define MXC_WDT0 ((mxc_wdt_regs_t *)MXC_BASE_WDT0)
-
-/******************************************************************************/
-/* Real Time Clock */
-#define MXC_BASE_RTC ((uint32_t)0x40006000UL)
-#define MXC_RTC ((mxc_rtc_regs_t *)MXC_BASE_RTC)
-
-/******************************************************************************/
-/* Power Sequencer */
-#define MXC_BASE_PWRSEQ ((uint32_t)0x40006800UL)
-#define MXC_PWRSEQ ((mxc_pwrseq_regs_t *)MXC_BASE_PWRSEQ)
-
-/******************************************************************************/
-/* GPIO */
-#define MXC_CFG_GPIO_INSTANCES (1)
-#define MXC_CFG_GPIO_PINS_PORT (14)
-
-#define MXC_BASE_GPIO0 ((uint32_t)0x40008000UL)
-#define MXC_GPIO0 ((mxc_gpio_regs_t *)MXC_BASE_GPIO0)
-
-#define MXC_GPIO_GET_IDX(p) ((p) == MXC_GPIO0 ? 0 : -1)
-
-#define MXC_GPIO_GET_GPIO(i) ((i) == 0 ? MXC_GPIO0 : 0)
-
-#define MXC_GPIO_GET_IRQ(i) ((i) == 0 ? GPIO0_IRQn : 0)
-
-#define PORT_0 ((uint32_t)(0UL)) /**< Port 0 Define*/
-#define PORT_1 ((uint32_t)(1UL)) /**< Port 1 Define*/
-#define PORT_2 ((uint32_t)(2UL)) /**< Port 2 Define*/
-#define PORT_3 ((uint32_t)(3UL)) /**< Port 3 Define*/
-#define PORT_4 ((uint32_t)(4UL)) /**< Port 4 Define*/
-
-#define GPIO_0 PORT_0 /**< Port 0 Define*/
-#define GPIO_1 PORT_1 /**< Port 1 Define*/
-#define GPIO_2 PORT_2 /**< Port 2 Define*/
-#define GPIO_3 PORT_3 /**< Port 3 Define*/
-#define GPIO_4 PORT_4 /**< Port 4 Define*/
-
-#define UNIMPLEMENTED_GPIO_BANK GPIO_0
-
-/******************************************************************************/
-/* I2C */
-#define MXC_I2C_INSTANCES (2)
-#define MXC_I2C_FIFO_DEPTH (8)
-
-#define MXC_BASE_I2C0 ((uint32_t)0x4001D000UL)
-#define MXC_I2C0 ((mxc_i2c_regs_t *)MXC_BASE_I2C0)
-#define MXC_BASE_I2C1 ((uint32_t)0x4001E000UL)
-#define MXC_I2C1 ((mxc_i2c_regs_t *)MXC_BASE_I2C1)
-
-#define MXC_I2C_GET_IRQ(i) \
- (IRQn_Type)((i) == 0 ? I2C0_IRQn : (i) == 1 ? I2C1_IRQn : 0)
-
-#define MXC_I2C_GET_BASE(i) \
- ((i) == 0 ? MXC_BASE_I2C0 : (i) == 1 ? MXC_BASE_I2C1 : 0)
-
-#define MXC_I2C_GET_I2C(i) ((i) == 0 ? MXC_I2C0 : (i) == 1 ? MXC_I2C1 : 0)
-
-#define MXC_I2C_GET_IDX(p) ((p) == MXC_I2C0 ? 0 : (p) == MXC_I2C1 ? 1 : -1)
-
-#define MXC_CFG_TMR_INSTANCES (3)
-
-#define MXC_BASE_TMR0 ((uint32_t)0x40010000UL)
-#define MXC_TMR0 ((mxc_tmr_regs_t *)MXC_BASE_TMR0)
-#define MXC_BASE_TMR1 ((uint32_t)0x40011000UL)
-#define MXC_TMR1 ((mxc_tmr_regs_t *)MXC_BASE_TMR1)
-#define MXC_BASE_TMR2 ((uint32_t)0x40012000UL)
-#define MXC_TMR2 ((mxc_tmr_regs_t *)MXC_BASE_TMR2)
-
-#define MXC_TMR_GET_IRQ(i) \
- (IRQn_Type)((i) == 0 ? \
- TMR0_IRQn : \
- (i) == 1 ? TMR1_IRQn : (i) == 2 ? TMR2_IRQn : 0)
-
-#define MXC_TMR_GET_BASE(i) \
- ((i) == 0 ? MXC_BASE_TMR0 : \
- (i) == 1 ? MXC_BASE_TMR1 : (i) == 2 ? MXC_BASE_TMR2 : 0)
-
-#define MXC_TMR_GET_TMR(i) \
- ((i) == 0 ? MXC_TMR0 : (i) == 1 ? MXC_TMR1 : (i) == 2 ? MXC_TMR2 : 0)
-
-#define MXC_TMR_GET_IDX(p) \
- ((p) == MXC_TMR0 ? 0 : (p) == MXC_TMR1 ? 1 : (p) == MXC_TMR2 ? 2 : -1)
-
-/******************************************************************************/
-/* FLC */
-#define MXC_BASE_FLC ((uint32_t)0x40029000UL)
-#define MXC_FLC ((mxc_flc_regs_t *)MXC_BASE_FLC)
-
-/******************************************************************************/
-/* Instruction Cache */
-#define MXC_BASE_ICC ((uint32_t)0x4002A000UL)
-#define MXC_ICC ((mxc_icc_regs_t *)MXC_BASE_ICC)
-
-/******************************************************************************/
-/* UART / Serial Port Interface */
-
-#define MXC_UART_INSTANCES (2)
-#define MXC_UART_FIFO_DEPTH (8)
-
-#define MXC_BASE_UART0 ((uint32_t)0x40042000UL)
-#define MXC_UART0 ((mxc_uart_regs_t *)MXC_BASE_UART0)
-#define MXC_BASE_UART1 ((uint32_t)0x40043000UL)
-#define MXC_UART1 ((mxc_uart_regs_t *)MXC_BASE_UART1)
-
-#define MXC_UART_GET_IRQ(i) \
- (IRQn_Type)((i) == 0 ? UART0_IRQn : (i) == 1 ? UART1_IRQn : 0)
-
-#define MXC_UART_GET_BASE(i) \
- ((i) == 0 ? MXC_BASE_UART0 : (i) == 1 ? MXC_BASE_UART1 : 0)
-
-#define MXC_UART_GET_UART(i) ((i) == 0 ? MXC_UART0 : (i) == 1 ? MXC_UART1 : 0)
-
-#define MXC_UART_GET_IDX(p) ((p) == MXC_UART0 ? 0 : (p) == MXC_UART1 ? 1 : -1)
-
-#define MXC_SETFIELD(reg, mask, value) (reg = (reg & ~mask) | (value & mask))
-
-#endif /* __CROS_EC_REGISTERS_H */
diff --git a/chip/max32660/system_chip.c b/chip/max32660/system_chip.c
deleted file mode 100644
index 07127dc8c5..0000000000
--- a/chip/max32660/system_chip.c
+++ /dev/null
@@ -1,64 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 System module for Chrome EC */
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "cpu.h"
-#include "host_command.h"
-#include "panic.h"
-#include "system.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-#include "registers.h"
-#include "gcr_regs.h"
-
-/* Console output macros */
-#define CPUTS(outstr) cputs(CC_SYSTEM, outstr)
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ##args)
-
-void chip_pre_init(void)
-{
-}
-
-void system_pre_init(void)
-{
-}
-
-void system_reset(int flags)
-{
- MXC_GCR->rstr0 = MXC_F_GCR_RSTR0_SYSTEM;
- while (1)
- ;
-}
-
-void system_hibernate(uint32_t seconds, uint32_t microseconds)
-{
- /* chip specific standby mode */
- CPRINTS("TODO: implement %s()", __func__);
-}
-
-const char *system_get_chip_vendor(void)
-{
- return "maxim";
-}
-
-const char *system_get_chip_name(void)
-{
- return "max32660";
-}
-
-const char *system_get_chip_revision(void)
-{
- return "A1";
-}
-
-int system_get_bbram(enum system_bbram_idx idx, uint8_t *value)
-{
- return EC_ERROR_UNIMPLEMENTED;
-}
diff --git a/chip/max32660/tmr_regs.h b/chip/max32660/tmr_regs.h
deleted file mode 100644
index 946cacbc50..0000000000
--- a/chip/max32660/tmr_regs.h
+++ /dev/null
@@ -1,279 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the TMR Peripheral */
-
-#ifndef _TMR_REGS_H_
-#define _TMR_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/* **** Definitions **** */
-
-/**
- * 32-bit reloadable timer that can be used for timing and event
- * counting.
- */
-
-/**
- * Structure type to access the TMR Registers.
- */
-typedef struct {
- __IO uint32_t cnt; /**< <tt>\b 0x00:<\tt> TMR CNT Register */
- __IO uint32_t cmp; /**< <tt>\b 0x04:<\tt> TMR CMP Register */
- __IO uint32_t pwm; /**< <tt>\b 0x08:<\tt> TMR PWM Register */
- __IO uint32_t intr; /**< <tt>\b 0x0C:<\tt> TMR INTR Register */
- __IO uint32_t cn; /**< <tt>\b 0x10:<\tt> TMR CN Register */
- __IO uint32_t nolcmp; /**< <tt>\b 0x14:<\tt> TMR NOLCMP Register */
-} mxc_tmr_regs_t;
-
-/**
- * TMR Peripheral Register Offsets from the TMR Base Peripheral
- * Address.
- */
-#define MXC_R_TMR_CNT \
- ((uint32_t)0x00000000UL) /**< Offset from TMR Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_TMR_CMP \
- ((uint32_t)0x00000004UL) /**< Offset from TMR Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_TMR_PWM \
- ((uint32_t)0x00000008UL) /**< Offset from TMR Base Address: <tt> \
- 0x0x008 */
-#define MXC_R_TMR_INTR \
- ((uint32_t)0x0000000CUL) /**< Offset from TMR Base Address: <tt> \
- 0x0x00C */
-#define MXC_R_TMR_CN \
- ((uint32_t)0x00000010UL) /**< Offset from TMR Base Address: <tt> \
- 0x0x010 */
-#define MXC_R_TMR_NOLCMP \
- ((uint32_t)0x00000014UL) /**< Offset from TMR Base Address: <tt> \
- 0x0x014 */
-
-/**
- * Clear Interrupt. Writing a value (0 or 1) to a bit in this register
- * clears the associated interrupt.
- */
-#define MXC_F_TMR_INTR_IRQ_CLR_POS 0 /**< INTR_IRQ_CLR Position */
-#define MXC_F_TMR_INTR_IRQ_CLR \
- ((uint32_t)(0x1UL \
- << MXC_F_TMR_INTR_IRQ_CLR_POS)) /**< INTR_IRQ_CLR Mask */
-
-/**
- * Timer Control Register.
- */
-#define MXC_F_TMR_CN_TMODE_POS 0 /**< CN_TMODE Position */
-#define MXC_F_TMR_CN_TMODE \
- ((uint32_t)(0x7UL << MXC_F_TMR_CN_TMODE_POS)) /**< CN_TMODE Mask */
-#define MXC_V_TMR_CN_TMODE_ONESHOT \
- ((uint32_t)0x0UL) /**< CN_TMODE_ONESHOT Value */
-#define MXC_S_TMR_CN_TMODE_ONESHOT \
- (MXC_V_TMR_CN_TMODE_ONESHOT \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_ONESHOT Setting */
-#define MXC_V_TMR_CN_TMODE_CONTINUOUS \
- ((uint32_t)0x1UL) /**< CN_TMODE_CONTINUOUS Value */
-#define MXC_S_TMR_CN_TMODE_CONTINUOUS \
- (MXC_V_TMR_CN_TMODE_CONTINUOUS \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_CONTINUOUS Setting */
-#define MXC_V_TMR_CN_TMODE_COUNTER \
- ((uint32_t)0x2UL) /**< CN_TMODE_COUNTER Value */
-#define MXC_S_TMR_CN_TMODE_COUNTER \
- (MXC_V_TMR_CN_TMODE_COUNTER \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_COUNTER Setting */
-#define MXC_V_TMR_CN_TMODE_PWM ((uint32_t)0x3UL) /**< CN_TMODE_PWM Value */
-#define MXC_S_TMR_CN_TMODE_PWM \
- (MXC_V_TMR_CN_TMODE_PWM \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_PWM Setting */
-#define MXC_V_TMR_CN_TMODE_CAPTURE \
- ((uint32_t)0x4UL) /**< CN_TMODE_CAPTURE Value */
-#define MXC_S_TMR_CN_TMODE_CAPTURE \
- (MXC_V_TMR_CN_TMODE_CAPTURE \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_CAPTURE Setting */
-#define MXC_V_TMR_CN_TMODE_COMPARE \
- ((uint32_t)0x5UL) /**< CN_TMODE_COMPARE Value */
-#define MXC_S_TMR_CN_TMODE_COMPARE \
- (MXC_V_TMR_CN_TMODE_COMPARE \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_COMPARE Setting */
-#define MXC_V_TMR_CN_TMODE_GATED \
- ((uint32_t)0x6UL) /**< CN_TMODE_GATED Value \
- */
-#define MXC_S_TMR_CN_TMODE_GATED \
- (MXC_V_TMR_CN_TMODE_GATED \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_GATED Setting */
-#define MXC_V_TMR_CN_TMODE_CAPTURECOMPARE \
- ((uint32_t)0x7UL) /**< CN_TMODE_CAPTURECOMPARE Value */
-#define MXC_S_TMR_CN_TMODE_CAPTURECOMPARE \
- (MXC_V_TMR_CN_TMODE_CAPTURECOMPARE \
- << MXC_F_TMR_CN_TMODE_POS) /**< CN_TMODE_CAPTURECOMPARE Setting */
-
-#define MXC_F_TMR_CN_PRES_POS 3 /**< CN_PRES Position */
-#define MXC_F_TMR_CN_PRES \
- ((uint32_t)(0x7UL << MXC_F_TMR_CN_PRES_POS)) /**< CN_PRES Mask */
-#define MXC_V_TMR_CN_PRES_DIV1 ((uint32_t)0x0UL) /**< CN_PRES_DIV1 Value */
-#define MXC_S_TMR_CN_PRES_DIV1 \
- (MXC_V_TMR_CN_PRES_DIV1 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV1 Setting */
-#define MXC_V_TMR_CN_PRES_DIV2 ((uint32_t)0x1UL) /**< CN_PRES_DIV2 Value */
-#define MXC_S_TMR_CN_PRES_DIV2 \
- (MXC_V_TMR_CN_PRES_DIV2 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV2 Setting */
-#define MXC_V_TMR_CN_PRES_DIV4 ((uint32_t)0x2UL) /**< CN_PRES_DIV4 Value */
-#define MXC_S_TMR_CN_PRES_DIV4 \
- (MXC_V_TMR_CN_PRES_DIV4 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV4 Setting */
-#define MXC_V_TMR_CN_PRES_DIV8 ((uint32_t)0x3UL) /**< CN_PRES_DIV8 Value */
-#define MXC_S_TMR_CN_PRES_DIV8 \
- (MXC_V_TMR_CN_PRES_DIV8 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV8 Setting */
-#define MXC_V_TMR_CN_PRES_DIV16 ((uint32_t)0x4UL) /**< CN_PRES_DIV16 Value */
-#define MXC_S_TMR_CN_PRES_DIV16 \
- (MXC_V_TMR_CN_PRES_DIV16 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV16 Setting */
-#define MXC_V_TMR_CN_PRES_DIV32 ((uint32_t)0x5UL) /**< CN_PRES_DIV32 Value */
-#define MXC_S_TMR_CN_PRES_DIV32 \
- (MXC_V_TMR_CN_PRES_DIV32 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV32 Setting */
-#define MXC_V_TMR_CN_PRES_DIV64 ((uint32_t)0x6UL) /**< CN_PRES_DIV64 Value */
-#define MXC_S_TMR_CN_PRES_DIV64 \
- (MXC_V_TMR_CN_PRES_DIV64 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV64 Setting */
-#define MXC_V_TMR_CN_PRES_DIV128 \
- ((uint32_t)0x7UL) /**< CN_PRES_DIV128 Value \
- */
-#define MXC_S_TMR_CN_PRES_DIV128 \
- (MXC_V_TMR_CN_PRES_DIV128 \
- << MXC_F_TMR_CN_PRES_POS) /**< CN_PRES_DIV128 Setting */
-
-#define MXC_F_TMR_CN_TPOL_POS 6 /**< CN_TPOL Position */
-#define MXC_F_TMR_CN_TPOL \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_TPOL_POS)) /**< CN_TPOL Mask */
-#define MXC_V_TMR_CN_TPOL_ACTIVEHI \
- ((uint32_t)0x0UL) /**< CN_TPOL_ACTIVEHI Value */
-#define MXC_S_TMR_CN_TPOL_ACTIVEHI \
- (MXC_V_TMR_CN_TPOL_ACTIVEHI \
- << MXC_F_TMR_CN_TPOL_POS) /**< CN_TPOL_ACTIVEHI Setting */
-#define MXC_V_TMR_CN_TPOL_ACTIVELO \
- ((uint32_t)0x1UL) /**< CN_TPOL_ACTIVELO Value */
-#define MXC_S_TMR_CN_TPOL_ACTIVELO \
- (MXC_V_TMR_CN_TPOL_ACTIVELO \
- << MXC_F_TMR_CN_TPOL_POS) /**< CN_TPOL_ACTIVELO Setting */
-
-#define MXC_F_TMR_CN_TEN_POS 7 /**< CN_TEN Position */
-#define MXC_F_TMR_CN_TEN \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_TEN_POS)) /**< CN_TEN Mask */
-#define MXC_V_TMR_CN_TEN_DIS ((uint32_t)0x0UL) /**< CN_TEN_DIS Value */
-#define MXC_S_TMR_CN_TEN_DIS \
- (MXC_V_TMR_CN_TEN_DIS \
- << MXC_F_TMR_CN_TEN_POS) /**< CN_TEN_DIS Setting */
-#define MXC_V_TMR_CN_TEN_EN ((uint32_t)0x1UL) /**< CN_TEN_EN Value */
-#define MXC_S_TMR_CN_TEN_EN \
- (MXC_V_TMR_CN_TEN_EN << MXC_F_TMR_CN_TEN_POS) /**< CN_TEN_EN Setting \
- */
-
-#define MXC_F_TMR_CN_PRES3_POS 8 /**< CN_PRES3 Position */
-#define MXC_F_TMR_CN_PRES3 \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_PRES3_POS)) /**< CN_PRES3 Mask */
-
-#define MXC_F_TMR_CN_PWMSYNC_POS 9 /**< CN_PWMSYNC Position */
-#define MXC_F_TMR_CN_PWMSYNC \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_PWMSYNC_POS)) /**< CN_PWMSYNC Mask \
- */
-#define MXC_V_TMR_CN_PWMSYNC_DIS \
- ((uint32_t)0x0UL) /**< CN_PWMSYNC_DIS Value \
- */
-#define MXC_S_TMR_CN_PWMSYNC_DIS \
- (MXC_V_TMR_CN_PWMSYNC_DIS \
- << MXC_F_TMR_CN_PWMSYNC_POS) /**< CN_PWMSYNC_DIS Setting */
-#define MXC_V_TMR_CN_PWMSYNC_EN ((uint32_t)0x1UL) /**< CN_PWMSYNC_EN Value */
-#define MXC_S_TMR_CN_PWMSYNC_EN \
- (MXC_V_TMR_CN_PWMSYNC_EN \
- << MXC_F_TMR_CN_PWMSYNC_POS) /**< CN_PWMSYNC_EN Setting */
-
-#define MXC_F_TMR_CN_NOLHPOL_POS 10 /**< CN_NOLHPOL Position */
-#define MXC_F_TMR_CN_NOLHPOL \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_NOLHPOL_POS)) /**< CN_NOLHPOL Mask \
- */
-#define MXC_V_TMR_CN_NOLHPOL_DIS \
- ((uint32_t)0x0UL) /**< CN_NOLHPOL_DIS Value \
- */
-#define MXC_S_TMR_CN_NOLHPOL_DIS \
- (MXC_V_TMR_CN_NOLHPOL_DIS \
- << MXC_F_TMR_CN_NOLHPOL_POS) /**< CN_NOLHPOL_DIS Setting */
-#define MXC_V_TMR_CN_NOLHPOL_EN ((uint32_t)0x1UL) /**< CN_NOLHPOL_EN Value */
-#define MXC_S_TMR_CN_NOLHPOL_EN \
- (MXC_V_TMR_CN_NOLHPOL_EN \
- << MXC_F_TMR_CN_NOLHPOL_POS) /**< CN_NOLHPOL_EN Setting */
-
-#define MXC_F_TMR_CN_NOLLPOL_POS 11 /**< CN_NOLLPOL Position */
-#define MXC_F_TMR_CN_NOLLPOL \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_NOLLPOL_POS)) /**< CN_NOLLPOL Mask \
- */
-#define MXC_V_TMR_CN_NOLLPOL_DIS \
- ((uint32_t)0x0UL) /**< CN_NOLLPOL_DIS Value \
- */
-#define MXC_S_TMR_CN_NOLLPOL_DIS \
- (MXC_V_TMR_CN_NOLLPOL_DIS \
- << MXC_F_TMR_CN_NOLLPOL_POS) /**< CN_NOLLPOL_DIS Setting */
-#define MXC_V_TMR_CN_NOLLPOL_EN ((uint32_t)0x1UL) /**< CN_NOLLPOL_EN Value */
-#define MXC_S_TMR_CN_NOLLPOL_EN \
- (MXC_V_TMR_CN_NOLLPOL_EN \
- << MXC_F_TMR_CN_NOLLPOL_POS) /**< CN_NOLLPOL_EN Setting */
-
-#define MXC_F_TMR_CN_PWMCKBD_POS 12 /**< CN_PWMCKBD Position */
-#define MXC_F_TMR_CN_PWMCKBD \
- ((uint32_t)(0x1UL << MXC_F_TMR_CN_PWMCKBD_POS)) /**< CN_PWMCKBD Mask \
- */
-#define MXC_V_TMR_CN_PWMCKBD_DIS \
- ((uint32_t)0x1UL) /**< CN_PWMCKBD_DIS Value \
- */
-#define MXC_S_TMR_CN_PWMCKBD_DIS \
- (MXC_V_TMR_CN_PWMCKBD_DIS \
- << MXC_F_TMR_CN_PWMCKBD_POS) /**< CN_PWMCKBD_DIS Setting */
-#define MXC_V_TMR_CN_PWMCKBD_EN ((uint32_t)0x0UL) /**< CN_PWMCKBD_EN Value */
-#define MXC_S_TMR_CN_PWMCKBD_EN \
- (MXC_V_TMR_CN_PWMCKBD_EN \
- << MXC_F_TMR_CN_PWMCKBD_POS) /**< CN_PWMCKBD_EN Setting */
-
-/**
- * Timer Non-Overlapping Compare Register.
- */
-#define MXC_F_TMR_NOLCMP_NOLLCMP_POS 0 /**< NOLCMP_NOLLCMP Position */
-#define MXC_F_TMR_NOLCMP_NOLLCMP \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_TMR_NOLCMP_NOLLCMP_POS)) /**< NOLCMP_NOLLCMP Mask */
-
-#define MXC_F_TMR_NOLCMP_NOLHCMP_POS 8 /**< NOLCMP_NOLHCMP Position */
-#define MXC_F_TMR_NOLCMP_NOLHCMP \
- ((uint32_t)( \
- 0xFFUL \
- << MXC_F_TMR_NOLCMP_NOLHCMP_POS)) /**< NOLCMP_NOLHCMP Mask */
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* _TMR_REGS_H_ */
diff --git a/chip/max32660/uart_chip.c b/chip/max32660/uart_chip.c
deleted file mode 100644
index c30a6ebd45..0000000000
--- a/chip/max32660/uart_chip.c
+++ /dev/null
@@ -1,277 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Console UART Module for Chrome EC */
-
-#include <stdint.h>
-#include "system.h"
-#include "task.h"
-#include "uart.h"
-#include "registers.h"
-#include "tmr_regs.h"
-#include "gpio_regs.h"
-#include "common.h"
-#include "gcr_regs.h"
-#include "uart_regs.h"
-
-static int done_uart_init_yet;
-
-#ifndef UARTN
-#define UARTN CONFIG_UART_HOST
-#endif
-
-#if (UARTN == 0)
-#define MXC_UART MXC_UART0
-#define EC_UART_IRQn EC_UART0_IRQn
-#elif (UARTN == 1)
-#define MXC_UART MXC_UART1
-#define EC_UART_IRQn EC_UART1_IRQn
-#else
-#error "MAX32660 supports only UART 0 or 1 for EC console"
-#endif
-
-#define UART_BAUD 115200
-
-#define UART_ER_IF \
- (MXC_F_UART_INT_FL_RX_FRAME_ERROR | \
- MXC_F_UART_INT_FL_RX_PARITY_ERROR | MXC_F_UART_INT_FL_RX_OVERRUN)
-
-#define UART_ER_IE \
- (MXC_F_UART_INT_EN_RX_FRAME_ERROR | \
- MXC_F_UART_INT_EN_RX_PARITY_ERROR | MXC_F_UART_INT_EN_RX_OVERRUN)
-
-#define UART_RX_IF (UART_ER_IF | MXC_F_UART_INT_FL_RX_FIFO_THRESH)
-
-#define UART_RX_IE (UART_ER_IE | MXC_F_UART_INT_EN_RX_FIFO_THRESH)
-
-#define UART_TX_IF \
- (UART_ER_IF | MXC_F_UART_INT_FL_TX_FIFO_ALMOST_EMPTY | \
- MXC_F_UART_INT_FL_TX_FIFO_THRESH)
-
-#define UART_TX_IE \
- (UART_ER_IE | MXC_F_UART_INT_EN_TX_FIFO_ALMOST_EMPTY | \
- MXC_F_UART_INT_EN_TX_FIFO_THRESH)
-
-#define UART_RX_THRESHOLD_LEVEL 1
-
-/**
- * Alternate clock rate. (7.3728MHz) */
-#define UART_ALTERNATE_CLOCK_HZ 7372800
-
-/* ************************************************************************* */
-static unsigned int uart_number_write_available(mxc_uart_regs_t *uart)
-{
- return MXC_UART_FIFO_DEPTH -
- ((uart->status & MXC_F_UART_STATUS_TX_FIFO_CNT) >>
- MXC_F_UART_STATUS_TX_FIFO_CNT_POS);
-}
-
-/* ************************************************************************* */
-static unsigned int uart_number_read_available(mxc_uart_regs_t *uart)
-{
- return ((uart->status & MXC_F_UART_STATUS_RX_FIFO_CNT) >>
- MXC_F_UART_STATUS_RX_FIFO_CNT_POS);
-}
-
-static void uartn_enable_tx_interrupt(int uart_num)
-{
- // Enable the interrupts
- MXC_UART_GET_UART(uart_num)->int_en |= UART_TX_IE;
-}
-
-static void uartn_disable_tx_interrupt(int uart_num)
-{
- // Disable the interrupts
- MXC_UART_GET_UART(uart_num)->int_en &= ~UART_TX_IE;
-}
-
-static int uartn_tx_in_progress(int uart_num)
-{
- return ((MXC_UART_GET_UART(uart_num)->status &
- (MXC_F_UART_STATUS_TX_BUSY)) != 0);
-}
-
-static void uartn_tx_flush(int uart_num)
-{
- while (uartn_tx_in_progress(uart_num)) {
- }
-}
-
-static int uartn_tx_ready(int uart_num)
-{
- int avail;
- avail = uart_number_write_available(MXC_UART_GET_UART(uart_num));
- /* True if the TX buffer is not completely full */
- return (avail != 0);
-}
-
-static int uartn_rx_available(int uart_num)
-{
- int avail;
- /* True if the RX buffer is not completely empty. */
- avail = uart_number_read_available(MXC_UART_GET_UART(uart_num));
- return (avail != 0);
-}
-
-static void uartn_write_char(int uart_num, char c)
-{
- int avail;
- mxc_uart_regs_t *uart;
-
- uart = MXC_UART_GET_UART(uart_num);
- /* Refill the TX FIFO */
- avail = uart_number_write_available(uart);
-
- /* wait until there is room in the fifo */
- while (avail == 0) {
- avail = uart_number_write_available(uart);
- }
-
- /* stuff the fifo with the character */
- uart->fifo = c;
-}
-
-static int uartn_read_char(int uart_num)
-{
- int c;
- c = MXC_UART_GET_UART(uart_num)->fifo;
- return c;
-}
-
-static void uartn_clear_interrupt_flags(int uart_num)
-{
- uint32_t flags;
- // Read and clear interrupts
- // intst = MXC_UART_GET_UART(uart_num)->int_fl;
- // MXC_UART_GET_UART(uart_num)->int_fl = ~intst;
-
- flags = MXC_UART_GET_UART(uart_num)->int_fl;
- MXC_UART_GET_UART(uart_num)->int_fl = flags;
-}
-
-static inline int uartn_is_rx_interrupt(int uart_num)
-{
- return MXC_UART_GET_UART(uart_num)->int_fl & UART_RX_IF;
-}
-
-static inline int uartn_is_tx_interrupt(int uart_num)
-{
- return MXC_UART_GET_UART(uart_num)->int_fl & UART_TX_IF;
-}
-
-int uart_init_done(void)
-{
- return done_uart_init_yet;
-}
-
-void uart_tx_start(void)
-{
- /* Do not allow deep sleep while transmit in progress */
- disable_sleep(SLEEP_MASK_UART);
- /*
- * Re-enable the transmit interrupt, then forcibly trigger the
- * interrupt.
- */
- uartn_enable_tx_interrupt(UARTN);
- task_trigger_irq(EC_UART_IRQn);
-}
-
-void uart_tx_stop(void)
-{
- uartn_disable_tx_interrupt(UARTN);
- /* Re-allow deep sleep */
- enable_sleep(SLEEP_MASK_UART);
-}
-
-int uart_tx_in_progress(void)
-{
- return uartn_tx_in_progress(UARTN);
-}
-
-void uart_tx_flush(void)
-{
- uartn_tx_flush(UARTN);
-}
-
-int uart_tx_ready(void)
-{
- /* True if the TX buffer is not completely full */
- return uartn_tx_ready(UARTN);
-}
-
-int uart_rx_available(void)
-{
- /* True if the RX buffer is not completely empty. */
- return uartn_rx_available(UARTN);
-}
-
-void uart_write_char(char c)
-{
- /* write a character to the UART */
- uartn_write_char(UARTN, c);
-}
-
-int uart_read_char(void)
-{
- return uartn_read_char(UARTN);
-}
-
-/**
- * Interrupt handlers for UART
- */
-void uart_rxtx_interrupt(void)
-{
- /* Process the Console Input */
- uart_process_input();
- /* Process the Buffered Console Output */
- uart_process_output();
- uartn_clear_interrupt_flags(UARTN);
-}
-DECLARE_IRQ(EC_UART_IRQn, uart_rxtx_interrupt, 1);
-
-void uart_init(void)
-{
- uint32_t flags;
- uint32_t baud0 = 0, baud1 = 0, div;
- int32_t factor = -1;
-
- /* Init the GPIO Port Mapping */
- gpio_config_module(MODULE_UART, 1);
-
- /* Drain FIFOs and enable UART and set configuration */
- MXC_UART->ctrl = (MXC_F_UART_CTRL_ENABLE | MXC_S_UART_CTRL_CHAR_SIZE_8 | 1);
-
- /* Set the baud rate */
- div = PeripheralClock / (UART_BAUD); // constant part of DIV (i.e. DIV
- // * (Baudrate*factor_int))
-
- do {
- factor += 1;
- baud0 = div >> (7 - factor); // divide by 128,64,32,16 to
- // extract integer part
- baud1 = ((div << factor) -
- (baud0 << 7)); // subtract factor corrected div -
- // integer parts
-
- } while ((baud0 == 0) && (factor < 4));
-
- MXC_UART->baud0 = ((factor << MXC_F_UART_BAUD0_FACTOR_POS) | baud0);
- MXC_UART->baud1 = baud1;
-
- MXC_UART->thresh_ctrl = UART_RX_THRESHOLD_LEVEL
- << MXC_F_UART_THRESH_CTRL_RX_FIFO_THRESH_POS;
-
- /* Clear Interrupt Flags */
- flags = MXC_UART->int_fl;
- MXC_UART->int_fl = flags;
-
- /* Enable the RX interrupts */
- MXC_UART->int_en |= UART_RX_IE;
-
- /* Enable the IRQ */
- task_enable_irq(EC_UART_IRQn);
- /* Set a flag for the system that the UART has been initialized */
- done_uart_init_yet = 1;
-}
diff --git a/chip/max32660/uart_regs.h b/chip/max32660/uart_regs.h
deleted file mode 100644
index a2de0cc0a0..0000000000
--- a/chip/max32660/uart_regs.h
+++ /dev/null
@@ -1,677 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the UART Peripheral */
-
-#ifndef _UART_REGS_H_
-#define _UART_REGS_H_
-
-/* **** Includes **** */
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/**
- * Structure type to access the UART Registers.
- */
-typedef struct {
- __IO uint32_t ctrl; /**< <tt>\b 0x00:<\tt> UART CTRL Register */
- __IO uint32_t
- thresh_ctrl; /**< <tt>\b 0x04:<\tt> UART THRESH_CTRL Register */
- __I uint32_t status; /**< <tt>\b 0x08:<\tt> UART STATUS Register */
- __IO uint32_t int_en; /**< <tt>\b 0x0C:<\tt> UART INT_EN Register */
- __IO uint32_t int_fl; /**< <tt>\b 0x10:<\tt> UART INT_FL Register */
- __IO uint32_t baud0; /**< <tt>\b 0x14:<\tt> UART BAUD0 Register */
- __IO uint32_t baud1; /**< <tt>\b 0x18:<\tt> UART BAUD1 Register */
- __IO uint32_t fifo; /**< <tt>\b 0x1C:<\tt> UART FIFO Register */
- __IO uint32_t dma; /**< <tt>\b 0x20:<\tt> UART DMA Register */
- __IO uint32_t tx_fifo; /**< <tt>\b 0x24:<\tt> UART TX_FIFO Register */
-} mxc_uart_regs_t;
-
-/**
- * UART Peripheral Register Offsets from the UART Base Peripheral
- * Address.
- */
-#define MXC_R_UART_CTRL \
- ((uint32_t)0x00000000UL) /**< Offset from UART Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_UART_THRESH_CTRL \
- ((uint32_t)0x00000004UL) /**< Offset from UART Base Address: <tt> \
- 0x0x004 */
-#define MXC_R_UART_STATUS \
- ((uint32_t)0x00000008UL) /**< Offset from UART Base Address: <tt> \
- 0x0x008 */
-#define MXC_R_UART_INT_EN \
- ((uint32_t)0x0000000CUL) /**< Offset from UART Base Address: <tt> \
- 0x0x00C */
-#define MXC_R_UART_INT_FL \
- ((uint32_t)0x00000010UL) /**< Offset from UART Base Address: <tt> \
- 0x0x010 */
-#define MXC_R_UART_BAUD0 \
- ((uint32_t)0x00000014UL) /**< Offset from UART Base Address: <tt> \
- 0x0x014 */
-#define MXC_R_UART_BAUD1 \
- ((uint32_t)0x00000018UL) /**< Offset from UART Base Address: <tt> \
- 0x0x018 */
-#define MXC_R_UART_FIFO \
- ((uint32_t)0x0000001CUL) /**< Offset from UART Base Address: <tt> \
- 0x0x01C */
-#define MXC_R_UART_DMA \
- ((uint32_t)0x00000020UL) /**< Offset from UART Base Address: <tt> \
- 0x0x020 */
-#define MXC_R_UART_TX_FIFO \
- ((uint32_t)0x00000024UL) /**< Offset from UART Base Address: <tt> \
- 0x0x024 */
-
-/**
- * Control Register.
- */
-#define MXC_F_UART_CTRL_ENABLE_POS 0 /**< CTRL_ENABLE Position */
-#define MXC_F_UART_CTRL_ENABLE \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_CTRL_ENABLE_POS)) /**< CTRL_ENABLE Mask */
-#define MXC_V_UART_CTRL_ENABLE_DIS \
- ((uint32_t)0x0UL) /**< CTRL_ENABLE_DIS Value */
-#define MXC_S_UART_CTRL_ENABLE_DIS \
- (MXC_V_UART_CTRL_ENABLE_DIS \
- << MXC_F_UART_CTRL_ENABLE_POS) /**< CTRL_ENABLE_DIS Setting */
-#define MXC_V_UART_CTRL_ENABLE_EN \
- ((uint32_t)0x1UL) /**< CTRL_ENABLE_EN Value \
- */
-#define MXC_S_UART_CTRL_ENABLE_EN \
- (MXC_V_UART_CTRL_ENABLE_EN \
- << MXC_F_UART_CTRL_ENABLE_POS) /**< CTRL_ENABLE_EN Setting */
-
-#define MXC_F_UART_CTRL_PARITY_EN_POS 1 /**< CTRL_PARITY_EN Position */
-#define MXC_F_UART_CTRL_PARITY_EN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_PARITY_EN_POS)) /**< CTRL_PARITY_EN Mask */
-#define MXC_V_UART_CTRL_PARITY_EN_DIS \
- ((uint32_t)0x0UL) /**< CTRL_PARITY_EN_DIS Value */
-#define MXC_S_UART_CTRL_PARITY_EN_DIS \
- (MXC_V_UART_CTRL_PARITY_EN_DIS \
- << MXC_F_UART_CTRL_PARITY_EN_POS) /**< CTRL_PARITY_EN_DIS Setting */
-#define MXC_V_UART_CTRL_PARITY_EN_EN \
- ((uint32_t)0x1UL) /**< CTRL_PARITY_EN_EN Value */
-#define MXC_S_UART_CTRL_PARITY_EN_EN \
- (MXC_V_UART_CTRL_PARITY_EN_EN \
- << MXC_F_UART_CTRL_PARITY_EN_POS) /**< CTRL_PARITY_EN_EN Setting */
-
-#define MXC_F_UART_CTRL_PARITY_POS 2 /**< CTRL_PARITY Position */
-#define MXC_F_UART_CTRL_PARITY \
- ((uint32_t)( \
- 0x3UL << MXC_F_UART_CTRL_PARITY_POS)) /**< CTRL_PARITY Mask */
-#define MXC_V_UART_CTRL_PARITY_EVEN \
- ((uint32_t)0x0UL) /**< CTRL_PARITY_EVEN Value */
-#define MXC_S_UART_CTRL_PARITY_EVEN \
- (MXC_V_UART_CTRL_PARITY_EVEN \
- << MXC_F_UART_CTRL_PARITY_POS) /**< CTRL_PARITY_EVEN Setting */
-#define MXC_V_UART_CTRL_PARITY_ODD \
- ((uint32_t)0x1UL) /**< CTRL_PARITY_ODD Value */
-#define MXC_S_UART_CTRL_PARITY_ODD \
- (MXC_V_UART_CTRL_PARITY_ODD \
- << MXC_F_UART_CTRL_PARITY_POS) /**< CTRL_PARITY_ODD Setting */
-#define MXC_V_UART_CTRL_PARITY_MARK \
- ((uint32_t)0x2UL) /**< CTRL_PARITY_MARK Value */
-#define MXC_S_UART_CTRL_PARITY_MARK \
- (MXC_V_UART_CTRL_PARITY_MARK \
- << MXC_F_UART_CTRL_PARITY_POS) /**< CTRL_PARITY_MARK Setting */
-#define MXC_V_UART_CTRL_PARITY_SPACE \
- ((uint32_t)0x3UL) /**< CTRL_PARITY_SPACE Value */
-#define MXC_S_UART_CTRL_PARITY_SPACE \
- (MXC_V_UART_CTRL_PARITY_SPACE \
- << MXC_F_UART_CTRL_PARITY_POS) /**< CTRL_PARITY_SPACE Setting */
-
-#define MXC_F_UART_CTRL_PARMD_POS 4 /**< CTRL_PARMD Position */
-#define MXC_F_UART_CTRL_PARMD \
- ((uint32_t)(0x1UL << MXC_F_UART_CTRL_PARMD_POS)) /**< CTRL_PARMD Mask \
- */
-#define MXC_V_UART_CTRL_PARMD_1 ((uint32_t)0x0UL) /**< CTRL_PARMD_1 Value */
-#define MXC_S_UART_CTRL_PARMD_1 \
- (MXC_V_UART_CTRL_PARMD_1 \
- << MXC_F_UART_CTRL_PARMD_POS) /**< CTRL_PARMD_1 Setting */
-#define MXC_V_UART_CTRL_PARMD_0 ((uint32_t)0x1UL) /**< CTRL_PARMD_0 Value */
-#define MXC_S_UART_CTRL_PARMD_0 \
- (MXC_V_UART_CTRL_PARMD_0 \
- << MXC_F_UART_CTRL_PARMD_POS) /**< CTRL_PARMD_0 Setting */
-
-#define MXC_F_UART_CTRL_TX_FLUSH_POS 5 /**< CTRL_TX_FLUSH Position */
-#define MXC_F_UART_CTRL_TX_FLUSH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_TX_FLUSH_POS)) /**< CTRL_TX_FLUSH Mask */
-
-#define MXC_F_UART_CTRL_RX_FLUSH_POS 6 /**< CTRL_RX_FLUSH Position */
-#define MXC_F_UART_CTRL_RX_FLUSH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_RX_FLUSH_POS)) /**< CTRL_RX_FLUSH Mask */
-
-#define MXC_F_UART_CTRL_BITACC_POS 7 /**< CTRL_BITACC Position */
-#define MXC_F_UART_CTRL_BITACC \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_CTRL_BITACC_POS)) /**< CTRL_BITACC Mask */
-#define MXC_V_UART_CTRL_BITACC_FRAME \
- ((uint32_t)0x0UL) /**< CTRL_BITACC_FRAME Value */
-#define MXC_S_UART_CTRL_BITACC_FRAME \
- (MXC_V_UART_CTRL_BITACC_FRAME \
- << MXC_F_UART_CTRL_BITACC_POS) /**< CTRL_BITACC_FRAME Setting */
-#define MXC_V_UART_CTRL_BITACC_BIT \
- ((uint32_t)0x1UL) /**< CTRL_BITACC_BIT Value */
-#define MXC_S_UART_CTRL_BITACC_BIT \
- (MXC_V_UART_CTRL_BITACC_BIT \
- << MXC_F_UART_CTRL_BITACC_POS) /**< CTRL_BITACC_BIT Setting */
-
-#define MXC_F_UART_CTRL_CHAR_SIZE_POS 8 /**< CTRL_CHAR_SIZE Position */
-#define MXC_F_UART_CTRL_CHAR_SIZE \
- ((uint32_t)( \
- 0x3UL \
- << MXC_F_UART_CTRL_CHAR_SIZE_POS)) /**< CTRL_CHAR_SIZE Mask */
-#define MXC_V_UART_CTRL_CHAR_SIZE_5 \
- ((uint32_t)0x0UL) /**< CTRL_CHAR_SIZE_5 Value */
-#define MXC_S_UART_CTRL_CHAR_SIZE_5 \
- (MXC_V_UART_CTRL_CHAR_SIZE_5 \
- << MXC_F_UART_CTRL_CHAR_SIZE_POS) /**< CTRL_CHAR_SIZE_5 Setting */
-#define MXC_V_UART_CTRL_CHAR_SIZE_6 \
- ((uint32_t)0x1UL) /**< CTRL_CHAR_SIZE_6 Value */
-#define MXC_S_UART_CTRL_CHAR_SIZE_6 \
- (MXC_V_UART_CTRL_CHAR_SIZE_6 \
- << MXC_F_UART_CTRL_CHAR_SIZE_POS) /**< CTRL_CHAR_SIZE_6 Setting */
-#define MXC_V_UART_CTRL_CHAR_SIZE_7 \
- ((uint32_t)0x2UL) /**< CTRL_CHAR_SIZE_7 Value */
-#define MXC_S_UART_CTRL_CHAR_SIZE_7 \
- (MXC_V_UART_CTRL_CHAR_SIZE_7 \
- << MXC_F_UART_CTRL_CHAR_SIZE_POS) /**< CTRL_CHAR_SIZE_7 Setting */
-#define MXC_V_UART_CTRL_CHAR_SIZE_8 \
- ((uint32_t)0x3UL) /**< CTRL_CHAR_SIZE_8 Value */
-#define MXC_S_UART_CTRL_CHAR_SIZE_8 \
- (MXC_V_UART_CTRL_CHAR_SIZE_8 \
- << MXC_F_UART_CTRL_CHAR_SIZE_POS) /**< CTRL_CHAR_SIZE_8 Setting */
-
-#define MXC_F_UART_CTRL_STOPBITS_POS 10 /**< CTRL_STOPBITS Position */
-#define MXC_F_UART_CTRL_STOPBITS \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_STOPBITS_POS)) /**< CTRL_STOPBITS Mask */
-#define MXC_V_UART_CTRL_STOPBITS_1 \
- ((uint32_t)0x0UL) /**< CTRL_STOPBITS_1 Value */
-#define MXC_S_UART_CTRL_STOPBITS_1 \
- (MXC_V_UART_CTRL_STOPBITS_1 \
- << MXC_F_UART_CTRL_STOPBITS_POS) /**< CTRL_STOPBITS_1 Setting */
-#define MXC_V_UART_CTRL_STOPBITS_1_5 \
- ((uint32_t)0x1UL) /**< CTRL_STOPBITS_1_5 Value */
-#define MXC_S_UART_CTRL_STOPBITS_1_5 \
- (MXC_V_UART_CTRL_STOPBITS_1_5 \
- << MXC_F_UART_CTRL_STOPBITS_POS) /**< CTRL_STOPBITS_1_5 Setting */
-
-#define MXC_F_UART_CTRL_FLOW_CTRL_POS 11 /**< CTRL_FLOW_CTRL Position */
-#define MXC_F_UART_CTRL_FLOW_CTRL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_FLOW_CTRL_POS)) /**< CTRL_FLOW_CTRL Mask */
-#define MXC_V_UART_CTRL_FLOW_CTRL_EN \
- ((uint32_t)0x1UL) /**< CTRL_FLOW_CTRL_EN Value */
-#define MXC_S_UART_CTRL_FLOW_CTRL_EN \
- (MXC_V_UART_CTRL_FLOW_CTRL_EN \
- << MXC_F_UART_CTRL_FLOW_CTRL_POS) /**< CTRL_FLOW_CTRL_EN Setting */
-#define MXC_V_UART_CTRL_FLOW_CTRL_DIS \
- ((uint32_t)0x0UL) /**< CTRL_FLOW_CTRL_DIS Value */
-#define MXC_S_UART_CTRL_FLOW_CTRL_DIS \
- (MXC_V_UART_CTRL_FLOW_CTRL_DIS \
- << MXC_F_UART_CTRL_FLOW_CTRL_POS) /**< CTRL_FLOW_CTRL_DIS Setting */
-
-#define MXC_F_UART_CTRL_FLOW_POL_POS 12 /**< CTRL_FLOW_POL Position */
-#define MXC_F_UART_CTRL_FLOW_POL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_CTRL_FLOW_POL_POS)) /**< CTRL_FLOW_POL Mask */
-#define MXC_V_UART_CTRL_FLOW_POL_0 \
- ((uint32_t)0x0UL) /**< CTRL_FLOW_POL_0 Value */
-#define MXC_S_UART_CTRL_FLOW_POL_0 \
- (MXC_V_UART_CTRL_FLOW_POL_0 \
- << MXC_F_UART_CTRL_FLOW_POL_POS) /**< CTRL_FLOW_POL_0 Setting */
-#define MXC_V_UART_CTRL_FLOW_POL_1 \
- ((uint32_t)0x1UL) /**< CTRL_FLOW_POL_1 Value */
-#define MXC_S_UART_CTRL_FLOW_POL_1 \
- (MXC_V_UART_CTRL_FLOW_POL_1 \
- << MXC_F_UART_CTRL_FLOW_POL_POS) /**< CTRL_FLOW_POL_1 Setting */
-
-#define MXC_F_UART_CTRL_NULL_MODEM_POS 13 /**< CTRL_NULL_MODEM Position */
-#define MXC_F_UART_CTRL_NULL_MODEM \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_CTRL_NULL_MODEM_POS)) /**< CTRL_NULL_MODEM \
- Mask */
-#define MXC_V_UART_CTRL_NULL_MODEM_DIS \
- ((uint32_t)0x0UL) /**< CTRL_NULL_MODEM_DIS Value */
-#define MXC_S_UART_CTRL_NULL_MODEM_DIS \
- (MXC_V_UART_CTRL_NULL_MODEM_DIS \
- << MXC_F_UART_CTRL_NULL_MODEM_POS) /**< CTRL_NULL_MODEM_DIS Setting \
- */
-#define MXC_V_UART_CTRL_NULL_MODEM_EN \
- ((uint32_t)0x1UL) /**< CTRL_NULL_MODEM_EN Value */
-#define MXC_S_UART_CTRL_NULL_MODEM_EN \
- (MXC_V_UART_CTRL_NULL_MODEM_EN \
- << MXC_F_UART_CTRL_NULL_MODEM_POS) /**< CTRL_NULL_MODEM_EN Setting */
-
-#define MXC_F_UART_CTRL_BREAK_POS 14 /**< CTRL_BREAK Position */
-#define MXC_F_UART_CTRL_BREAK \
- ((uint32_t)(0x1UL << MXC_F_UART_CTRL_BREAK_POS)) /**< CTRL_BREAK Mask \
- */
-#define MXC_V_UART_CTRL_BREAK_DIS \
- ((uint32_t)0x0UL) /**< CTRL_BREAK_DIS Value \
- */
-#define MXC_S_UART_CTRL_BREAK_DIS \
- (MXC_V_UART_CTRL_BREAK_DIS \
- << MXC_F_UART_CTRL_BREAK_POS) /**< CTRL_BREAK_DIS Setting */
-#define MXC_V_UART_CTRL_BREAK_EN ((uint32_t)0x1UL) /**< CTRL_BREAK_EN Value */
-#define MXC_S_UART_CTRL_BREAK_EN \
- (MXC_V_UART_CTRL_BREAK_EN \
- << MXC_F_UART_CTRL_BREAK_POS) /**< CTRL_BREAK_EN Setting */
-
-#define MXC_F_UART_CTRL_CLKSEL_POS 15 /**< CTRL_CLKSEL Position */
-#define MXC_F_UART_CTRL_CLKSEL \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_CTRL_CLKSEL_POS)) /**< CTRL_CLKSEL Mask */
-#define MXC_V_UART_CTRL_CLKSEL_SYSTEM \
- ((uint32_t)0x0UL) /**< CTRL_CLKSEL_SYSTEM Value */
-#define MXC_S_UART_CTRL_CLKSEL_SYSTEM \
- (MXC_V_UART_CTRL_CLKSEL_SYSTEM \
- << MXC_F_UART_CTRL_CLKSEL_POS) /**< CTRL_CLKSEL_SYSTEM Setting */
-#define MXC_V_UART_CTRL_CLKSEL_ALTERNATE \
- ((uint32_t)0x1UL) /**< CTRL_CLKSEL_ALTERNATE Value */
-#define MXC_S_UART_CTRL_CLKSEL_ALTERNATE \
- (MXC_V_UART_CTRL_CLKSEL_ALTERNATE \
- << MXC_F_UART_CTRL_CLKSEL_POS) /**< CTRL_CLKSEL_ALTERNATE Setting */
-
-#define MXC_F_UART_CTRL_RX_TO_POS 16 /**< CTRL_RX_TO Position */
-#define MXC_F_UART_CTRL_RX_TO \
- ((uint32_t)( \
- 0xFFUL << MXC_F_UART_CTRL_RX_TO_POS)) /**< CTRL_RX_TO Mask */
-
-/**
- * Threshold Control register.
- */
-#define MXC_F_UART_THRESH_CTRL_RX_FIFO_THRESH_POS \
- 0 /**< THRESH_CTRL_RX_FIFO_THRESH Position */
-#define MXC_F_UART_THRESH_CTRL_RX_FIFO_THRESH \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_UART_THRESH_CTRL_RX_FIFO_THRESH_POS)) /**< \
- THRESH_CTRL_RX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_THRESH_CTRL_TX_FIFO_THRESH_POS \
- 8 /**< THRESH_CTRL_TX_FIFO_THRESH Position */
-#define MXC_F_UART_THRESH_CTRL_TX_FIFO_THRESH \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_UART_THRESH_CTRL_TX_FIFO_THRESH_POS)) /**< \
- THRESH_CTRL_TX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_THRESH_CTRL_RTS_FIFO_THRESH_POS \
- 16 /**< THRESH_CTRL_RTS_FIFO_THRESH Position */
-#define MXC_F_UART_THRESH_CTRL_RTS_FIFO_THRESH \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_UART_THRESH_CTRL_RTS_FIFO_THRESH_POS)) /**< \
- THRESH_CTRL_RTS_FIFO_THRESH \
- Mask */
-
-/**
- * Status Register.
- */
-#define MXC_F_UART_STATUS_TX_BUSY_POS 0 /**< STATUS_TX_BUSY Position */
-#define MXC_F_UART_STATUS_TX_BUSY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_STATUS_TX_BUSY_POS)) /**< STATUS_TX_BUSY Mask */
-
-#define MXC_F_UART_STATUS_RX_BUSY_POS 1 /**< STATUS_RX_BUSY Position */
-#define MXC_F_UART_STATUS_RX_BUSY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_STATUS_RX_BUSY_POS)) /**< STATUS_RX_BUSY Mask */
-
-#define MXC_F_UART_STATUS_PARITY_POS 2 /**< STATUS_PARITY Position */
-#define MXC_F_UART_STATUS_PARITY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_STATUS_PARITY_POS)) /**< STATUS_PARITY Mask */
-
-#define MXC_F_UART_STATUS_BREAK_POS 3 /**< STATUS_BREAK Position */
-#define MXC_F_UART_STATUS_BREAK \
- ((uint32_t)(0x1UL \
- << MXC_F_UART_STATUS_BREAK_POS)) /**< STATUS_BREAK Mask */
-
-#define MXC_F_UART_STATUS_RX_EMPTY_POS 4 /**< STATUS_RX_EMPTY Position */
-#define MXC_F_UART_STATUS_RX_EMPTY \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_STATUS_RX_EMPTY_POS)) /**< STATUS_RX_EMPTY \
- Mask */
-
-#define MXC_F_UART_STATUS_RX_FULL_POS 5 /**< STATUS_RX_FULL Position */
-#define MXC_F_UART_STATUS_RX_FULL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_STATUS_RX_FULL_POS)) /**< STATUS_RX_FULL Mask */
-
-#define MXC_F_UART_STATUS_TX_EMPTY_POS 6 /**< STATUS_TX_EMPTY Position */
-#define MXC_F_UART_STATUS_TX_EMPTY \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_STATUS_TX_EMPTY_POS)) /**< STATUS_TX_EMPTY \
- Mask */
-
-#define MXC_F_UART_STATUS_TX_FULL_POS 7 /**< STATUS_TX_FULL Position */
-#define MXC_F_UART_STATUS_TX_FULL \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_STATUS_TX_FULL_POS)) /**< STATUS_TX_FULL Mask */
-
-#define MXC_F_UART_STATUS_RX_FIFO_CNT_POS \
- 8 /**< STATUS_RX_FIFO_CNT Position \
- */
-#define MXC_F_UART_STATUS_RX_FIFO_CNT \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_UART_STATUS_RX_FIFO_CNT_POS)) /**< STATUS_RX_FIFO_CNT \
- Mask */
-
-#define MXC_F_UART_STATUS_TX_FIFO_CNT_POS \
- 16 /**< STATUS_TX_FIFO_CNT Position \
- */
-#define MXC_F_UART_STATUS_TX_FIFO_CNT \
- ((uint32_t)( \
- 0x3FUL \
- << MXC_F_UART_STATUS_TX_FIFO_CNT_POS)) /**< STATUS_TX_FIFO_CNT \
- Mask */
-
-#define MXC_F_UART_STATUS_RX_TO_POS 24 /**< STATUS_RX_TO Position */
-#define MXC_F_UART_STATUS_RX_TO \
- ((uint32_t)(0x1UL \
- << MXC_F_UART_STATUS_RX_TO_POS)) /**< STATUS_RX_TO Mask */
-
-/**
- * Interrupt Enable Register.
- */
-#define MXC_F_UART_INT_EN_RX_FRAME_ERROR_POS \
- 0 /**< INT_EN_RX_FRAME_ERROR Position */
-#define MXC_F_UART_INT_EN_RX_FRAME_ERROR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_RX_FRAME_ERROR_POS)) /**< \
- INT_EN_RX_FRAME_ERROR \
- Mask */
-
-#define MXC_F_UART_INT_EN_RX_PARITY_ERROR_POS \
- 1 /**< INT_EN_RX_PARITY_ERROR Position */
-#define MXC_F_UART_INT_EN_RX_PARITY_ERROR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_RX_PARITY_ERROR_POS)) /**< \
- INT_EN_RX_PARITY_ERROR \
- Mask */
-
-#define MXC_F_UART_INT_EN_CTS_CHANGE_POS 2 /**< INT_EN_CTS_CHANGE Position */
-#define MXC_F_UART_INT_EN_CTS_CHANGE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_CTS_CHANGE_POS)) /**< INT_EN_CTS_CHANGE \
- Mask */
-
-#define MXC_F_UART_INT_EN_RX_OVERRUN_POS 3 /**< INT_EN_RX_OVERRUN Position */
-#define MXC_F_UART_INT_EN_RX_OVERRUN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_RX_OVERRUN_POS)) /**< INT_EN_RX_OVERRUN \
- Mask */
-
-#define MXC_F_UART_INT_EN_RX_FIFO_THRESH_POS \
- 4 /**< INT_EN_RX_FIFO_THRESH Position */
-#define MXC_F_UART_INT_EN_RX_FIFO_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_RX_FIFO_THRESH_POS)) /**< \
- INT_EN_RX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_INT_EN_TX_FIFO_ALMOST_EMPTY_POS \
- 5 /**< INT_EN_TX_FIFO_ALMOST_EMPTY Position */
-#define MXC_F_UART_INT_EN_TX_FIFO_ALMOST_EMPTY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_TX_FIFO_ALMOST_EMPTY_POS)) /**< \
- INT_EN_TX_FIFO_ALMOST_EMPTY \
- Mask */
-
-#define MXC_F_UART_INT_EN_TX_FIFO_THRESH_POS \
- 6 /**< INT_EN_TX_FIFO_THRESH Position */
-#define MXC_F_UART_INT_EN_TX_FIFO_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_TX_FIFO_THRESH_POS)) /**< \
- INT_EN_TX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_INT_EN_BREAK_POS 7 /**< INT_EN_BREAK Position */
-#define MXC_F_UART_INT_EN_BREAK \
- ((uint32_t)(0x1UL \
- << MXC_F_UART_INT_EN_BREAK_POS)) /**< INT_EN_BREAK Mask */
-
-#define MXC_F_UART_INT_EN_RX_TIMEOUT_POS 8 /**< INT_EN_RX_TIMEOUT Position */
-#define MXC_F_UART_INT_EN_RX_TIMEOUT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_RX_TIMEOUT_POS)) /**< INT_EN_RX_TIMEOUT \
- Mask */
-
-#define MXC_F_UART_INT_EN_LAST_BREAK_POS 9 /**< INT_EN_LAST_BREAK Position */
-#define MXC_F_UART_INT_EN_LAST_BREAK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_EN_LAST_BREAK_POS)) /**< INT_EN_LAST_BREAK \
- Mask */
-
-/**
- * Interrupt Status Flags.
- */
-#define MXC_F_UART_INT_FL_RX_FRAME_ERROR_POS \
- 0 /**< INT_FL_RX_FRAME_ERROR Position */
-#define MXC_F_UART_INT_FL_RX_FRAME_ERROR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_RX_FRAME_ERROR_POS)) /**< \
- INT_FL_RX_FRAME_ERROR \
- Mask */
-
-#define MXC_F_UART_INT_FL_RX_PARITY_ERROR_POS \
- 1 /**< INT_FL_RX_PARITY_ERROR Position */
-#define MXC_F_UART_INT_FL_RX_PARITY_ERROR \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_RX_PARITY_ERROR_POS)) /**< \
- INT_FL_RX_PARITY_ERROR \
- Mask */
-
-#define MXC_F_UART_INT_FL_CTS_CHANGE_POS 2 /**< INT_FL_CTS_CHANGE Position */
-#define MXC_F_UART_INT_FL_CTS_CHANGE \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_CTS_CHANGE_POS)) /**< INT_FL_CTS_CHANGE \
- Mask */
-
-#define MXC_F_UART_INT_FL_RX_OVERRUN_POS 3 /**< INT_FL_RX_OVERRUN Position */
-#define MXC_F_UART_INT_FL_RX_OVERRUN \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_RX_OVERRUN_POS)) /**< INT_FL_RX_OVERRUN \
- Mask */
-
-#define MXC_F_UART_INT_FL_RX_FIFO_THRESH_POS \
- 4 /**< INT_FL_RX_FIFO_THRESH Position */
-#define MXC_F_UART_INT_FL_RX_FIFO_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_RX_FIFO_THRESH_POS)) /**< \
- INT_FL_RX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_INT_FL_TX_FIFO_ALMOST_EMPTY_POS \
- 5 /**< INT_FL_TX_FIFO_ALMOST_EMPTY Position */
-#define MXC_F_UART_INT_FL_TX_FIFO_ALMOST_EMPTY \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_TX_FIFO_ALMOST_EMPTY_POS)) /**< \
- INT_FL_TX_FIFO_ALMOST_EMPTY \
- Mask */
-
-#define MXC_F_UART_INT_FL_TX_FIFO_THRESH_POS \
- 6 /**< INT_FL_TX_FIFO_THRESH Position */
-#define MXC_F_UART_INT_FL_TX_FIFO_THRESH \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_TX_FIFO_THRESH_POS)) /**< \
- INT_FL_TX_FIFO_THRESH \
- Mask */
-
-#define MXC_F_UART_INT_FL_BREAK_POS 7 /**< INT_FL_BREAK Position */
-#define MXC_F_UART_INT_FL_BREAK \
- ((uint32_t)(0x1UL \
- << MXC_F_UART_INT_FL_BREAK_POS)) /**< INT_FL_BREAK Mask */
-
-#define MXC_F_UART_INT_FL_RX_TIMEOUT_POS 8 /**< INT_FL_RX_TIMEOUT Position */
-#define MXC_F_UART_INT_FL_RX_TIMEOUT \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_RX_TIMEOUT_POS)) /**< INT_FL_RX_TIMEOUT \
- Mask */
-
-#define MXC_F_UART_INT_FL_LAST_BREAK_POS 9 /**< INT_FL_LAST_BREAK Position */
-#define MXC_F_UART_INT_FL_LAST_BREAK \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_UART_INT_FL_LAST_BREAK_POS)) /**< INT_FL_LAST_BREAK \
- Mask */
-
-/**
- * Baud rate register. Integer portion.
- */
-#define MXC_F_UART_BAUD0_IBAUD_POS 0 /**< BAUD0_IBAUD Position */
-#define MXC_F_UART_BAUD0_IBAUD \
- ((uint32_t)(0xFFFUL \
- << MXC_F_UART_BAUD0_IBAUD_POS)) /**< BAUD0_IBAUD Mask */
-
-#define MXC_F_UART_BAUD0_FACTOR_POS 16 /**< BAUD0_FACTOR Position */
-#define MXC_F_UART_BAUD0_FACTOR \
- ((uint32_t)(0x3UL \
- << MXC_F_UART_BAUD0_FACTOR_POS)) /**< BAUD0_FACTOR Mask */
-#define MXC_V_UART_BAUD0_FACTOR_128 \
- ((uint32_t)0x0UL) /**< BAUD0_FACTOR_128 Value */
-#define MXC_S_UART_BAUD0_FACTOR_128 \
- (MXC_V_UART_BAUD0_FACTOR_128 \
- << MXC_F_UART_BAUD0_FACTOR_POS) /**< BAUD0_FACTOR_128 Setting */
-#define MXC_V_UART_BAUD0_FACTOR_64 \
- ((uint32_t)0x1UL) /**< BAUD0_FACTOR_64 Value */
-#define MXC_S_UART_BAUD0_FACTOR_64 \
- (MXC_V_UART_BAUD0_FACTOR_64 \
- << MXC_F_UART_BAUD0_FACTOR_POS) /**< BAUD0_FACTOR_64 Setting */
-#define MXC_V_UART_BAUD0_FACTOR_32 \
- ((uint32_t)0x2UL) /**< BAUD0_FACTOR_32 Value */
-#define MXC_S_UART_BAUD0_FACTOR_32 \
- (MXC_V_UART_BAUD0_FACTOR_32 \
- << MXC_F_UART_BAUD0_FACTOR_POS) /**< BAUD0_FACTOR_32 Setting */
-#define MXC_V_UART_BAUD0_FACTOR_16 \
- ((uint32_t)0x3UL) /**< BAUD0_FACTOR_16 Value */
-#define MXC_S_UART_BAUD0_FACTOR_16 \
- (MXC_V_UART_BAUD0_FACTOR_16 \
- << MXC_F_UART_BAUD0_FACTOR_POS) /**< BAUD0_FACTOR_16 Setting */
-
-/**
- * Baud rate register. Decimal Setting.
- */
-#define MXC_F_UART_BAUD1_DBAUD_POS 0 /**< BAUD1_DBAUD Position */
-#define MXC_F_UART_BAUD1_DBAUD \
- ((uint32_t)(0xFFFUL \
- << MXC_F_UART_BAUD1_DBAUD_POS)) /**< BAUD1_DBAUD Mask */
-
-/**
- * FIFO Data buffer.
- */
-#define MXC_F_UART_FIFO_FIFO_POS 0 /**< FIFO_FIFO Position */
-#define MXC_F_UART_FIFO_FIFO \
- ((uint32_t)(0xFFUL << MXC_F_UART_FIFO_FIFO_POS)) /**< FIFO_FIFO Mask \
- */
-
-
-/**
- * DMA Configuration.
- */
-#define MXC_F_UART_DMA_TDMA_EN_POS 0 /**< DMA_TDMA_EN Position */
-#define MXC_F_UART_DMA_TDMA_EN \
- ((uint32_t)( \
- 0x1UL << MXC_F_UART_DMA_TDMA_EN_POS)) /**< DMA_TDMA_EN Mask */
-#define MXC_V_UART_DMA_TDMA_EN_DIS \
- ((uint32_t)0x0UL) /**< DMA_TDMA_EN_DIS Value */
-#define MXC_S_UART_DMA_TDMA_EN_DIS \
- (MXC_V_UART_DMA_TDMA_EN_DIS \
- << MXC_F_UART_DMA_TDMA_EN_POS) /**< DMA_TDMA_EN_DIS Setting */
-#define MXC_V_UART_DMA_TDMA_EN_EN \
- ((uint32_t)0x1UL) /**< DMA_TDMA_EN_EN Value \
- */
-#define MXC_S_UART_DMA_TDMA_EN_EN \
- (MXC_V_UART_DMA_TDMA_EN_EN \
- << MXC_F_UART_DMA_TDMA_EN_POS) /**< DMA_TDMA_EN_EN Setting */
-
-#define MXC_F_UART_DMA_RXDMA_EN_POS 1 /**< DMA_RXDMA_EN Position */
-#define MXC_F_UART_DMA_RXDMA_EN \
- ((uint32_t)(0x1UL \
- << MXC_F_UART_DMA_RXDMA_EN_POS)) /**< DMA_RXDMA_EN Mask */
-#define MXC_V_UART_DMA_RXDMA_EN_DIS \
- ((uint32_t)0x0UL) /**< DMA_RXDMA_EN_DIS Value */
-#define MXC_S_UART_DMA_RXDMA_EN_DIS \
- (MXC_V_UART_DMA_RXDMA_EN_DIS \
- << MXC_F_UART_DMA_RXDMA_EN_POS) /**< DMA_RXDMA_EN_DIS Setting */
-#define MXC_V_UART_DMA_RXDMA_EN_EN \
- ((uint32_t)0x1UL) /**< DMA_RXDMA_EN_EN Value */
-#define MXC_S_UART_DMA_RXDMA_EN_EN \
- (MXC_V_UART_DMA_RXDMA_EN_EN \
- << MXC_F_UART_DMA_RXDMA_EN_POS) /**< DMA_RXDMA_EN_EN Setting */
-
-#define MXC_F_UART_DMA_TXDMA_LEVEL_POS 8 /**< DMA_TXDMA_LEVEL Position */
-#define MXC_F_UART_DMA_TXDMA_LEVEL \
- ((uint32_t)(0x3FUL \
- << MXC_F_UART_DMA_TXDMA_LEVEL_POS)) /**< DMA_TXDMA_LEVEL \
- Mask */
-
-#define MXC_F_UART_DMA_RXDMA_LEVEL_POS 16 /**< DMA_RXDMA_LEVEL Position */
-#define MXC_F_UART_DMA_RXDMA_LEVEL \
- ((uint32_t)(0x3FUL \
- << MXC_F_UART_DMA_RXDMA_LEVEL_POS)) /**< DMA_RXDMA_LEVEL \
- Mask */
-
-/**
- * Transmit FIFO Status register.
- */
-#define MXC_F_UART_TX_FIFO_DATA_POS 0 /**< TX_FIFO_DATA Position */
-#define MXC_F_UART_TX_FIFO_DATA \
- ((uint32_t)(0x7FUL \
- << MXC_F_UART_TX_FIFO_DATA_POS)) /**< TX_FIFO_DATA Mask */
-
-#endif /* _UART_REGS_H_ */
diff --git a/chip/max32660/wdt_chip.c b/chip/max32660/wdt_chip.c
deleted file mode 100644
index 1c99c798fc..0000000000
--- a/chip/max32660/wdt_chip.c
+++ /dev/null
@@ -1,67 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Watchdog Module */
-
-#include "clock.h"
-#include "common.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "task.h"
-#include "util.h"
-#include "watchdog.h"
-#include "console.h"
-#include "registers.h"
-#include "board.h"
-#include "wdt_regs.h"
-
-#define CPUTS(outstr) cputs(CC_COMMAND, outstr)
-#define CPRINTS(format, args...) cprints(CC_COMMAND, format, ##args)
-
-/* For a System clock of 96MHz,
- * Time in seconds = 96000000 / 2 * 2^power
- * Example for MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW29
- * Time in seconds = 96000000 / 2 * 2^29
- * = 11.1 Seconds
- */
-#define WATCHDOG_TIMER_PERIOD MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW29
-
-volatile int starve_dog = 0;
-
-void watchdog_reload(void)
-{
- if (!starve_dog) {
- /* Reset the watchdog */
- MXC_WDT0->rst = 0x00A5;
- MXC_WDT0->rst = 0x005A;
- }
-}
-DECLARE_HOOK(HOOK_TICK, watchdog_reload, HOOK_PRIO_DEFAULT);
-
-int watchdog_init(void)
-{
- /* Set the Watchdog period */
- MXC_SETFIELD(MXC_WDT0->ctrl, MXC_F_WDT_CTRL_RST_PERIOD,
- (WATCHDOG_TIMER_PERIOD << 4));
-
- /* We want the WD to reset us if it is not fed in time. */
- MXC_WDT0->ctrl |= MXC_F_WDT_CTRL_RST_EN;
- /* Enable the watchdog */
- MXC_WDT0->ctrl |= MXC_F_WDT_CTRL_WDT_EN;
- /* Reset the watchdog */
- MXC_WDT0->rst = 0x00A5;
- MXC_WDT0->rst = 0x005A;
- return EC_SUCCESS;
-}
-
-static int command_watchdog_test(int argc, char **argv)
-{
- starve_dog = 1;
-
- CPRINTS("done command_watchdog_test.");
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(wdttest, command_watchdog_test, "wdttest",
- "Force a WDT reset.");
diff --git a/chip/max32660/wdt_regs.h b/chip/max32660/wdt_regs.h
deleted file mode 100644
index 32d6fe0925..0000000000
--- a/chip/max32660/wdt_regs.h
+++ /dev/null
@@ -1,355 +0,0 @@
-/* Copyright 2019 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* MAX32660 Registers, Bit Masks and Bit Positions for the WDT Peripheral */
-
-#ifndef _WDT_REGS_H_
-#define _WDT_REGS_H_
-
-#include <stdint.h>
-
-/*
- If types are not defined elsewhere (CMSIS) define them here
-*/
-#ifndef __IO
-#define __IO volatile
-#endif
-#ifndef __I
-#define __I volatile const
-#endif
-#ifndef __O
-#define __O volatile
-#endif
-#ifndef __R
-#define __R volatile const
-#endif
-
-/**
- * Structure type to access the WDT Registers.
- */
-typedef struct {
- __IO uint32_t ctrl; /**< <tt>\b 0x00:<\tt> WDT CTRL Register */
- __O uint32_t rst; /**< <tt>\b 0x04:<\tt> WDT RST Register */
-} mxc_wdt_regs_t;
-
-/**
- * WDT Peripheral Register Offsets from the WDT Base Peripheral
- * Address.
- */
-#define MXC_R_WDT_CTRL \
- ((uint32_t)0x00000000UL) /**< Offset from WDT Base Address: <tt> \
- 0x0x000 */
-#define MXC_R_WDT_RST \
- ((uint32_t)0x00000004UL) /**< Offset from WDT Base Address: <tt> \
- 0x0x004 */
-
-/**
- * Watchdog Timer Control Register.
- */
-#define MXC_F_WDT_CTRL_INT_PERIOD_POS 0 /**< CTRL_INT_PERIOD Position */
-#define MXC_F_WDT_CTRL_INT_PERIOD \
- ((uint32_t)( \
- 0xFUL << MXC_F_WDT_CTRL_INT_PERIOD_POS)) /**< CTRL_INT_PERIOD \
- Mask */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW31 \
- ((uint32_t)0x0UL) /**< CTRL_INT_PERIOD_WDT2POW31 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW31 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW31 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW31 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW30 \
- ((uint32_t)0x1UL) /**< CTRL_INT_PERIOD_WDT2POW30 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW30 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW30 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW30 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW29 \
- ((uint32_t)0x2UL) /**< CTRL_INT_PERIOD_WDT2POW29 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW29 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW29 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW29 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW28 \
- ((uint32_t)0x3UL) /**< CTRL_INT_PERIOD_WDT2POW28 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW28 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW28 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW28 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW27 \
- ((uint32_t)0x4UL) /**< CTRL_INT_PERIOD_WDT2POW27 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW27 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW27 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW27 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW26 \
- ((uint32_t)0x5UL) /**< CTRL_INT_PERIOD_WDT2POW26 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW26 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW26 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW26 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW25 \
- ((uint32_t)0x6UL) /**< CTRL_INT_PERIOD_WDT2POW25 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW25 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW25 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW25 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW24 \
- ((uint32_t)0x7UL) /**< CTRL_INT_PERIOD_WDT2POW24 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW24 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW24 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW24 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW23 \
- ((uint32_t)0x8UL) /**< CTRL_INT_PERIOD_WDT2POW23 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW23 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW23 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW23 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW22 \
- ((uint32_t)0x9UL) /**< CTRL_INT_PERIOD_WDT2POW22 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW22 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW22 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW22 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW21 \
- ((uint32_t)0xAUL) /**< CTRL_INT_PERIOD_WDT2POW21 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW21 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW21 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW21 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW20 \
- ((uint32_t)0xBUL) /**< CTRL_INT_PERIOD_WDT2POW20 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW20 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW20 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW20 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW19 \
- ((uint32_t)0xCUL) /**< CTRL_INT_PERIOD_WDT2POW19 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW19 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW19 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW19 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW18 \
- ((uint32_t)0xDUL) /**< CTRL_INT_PERIOD_WDT2POW18 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW18 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW18 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW18 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW17 \
- ((uint32_t)0xEUL) /**< CTRL_INT_PERIOD_WDT2POW17 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW17 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW17 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW17 \
- Setting */
-#define MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW16 \
- ((uint32_t)0xFUL) /**< CTRL_INT_PERIOD_WDT2POW16 Value */
-#define MXC_S_WDT_CTRL_INT_PERIOD_WDT2POW16 \
- (MXC_V_WDT_CTRL_INT_PERIOD_WDT2POW16 \
- << MXC_F_WDT_CTRL_INT_PERIOD_POS) /**< CTRL_INT_PERIOD_WDT2POW16 \
- Setting */
-
-#define MXC_F_WDT_CTRL_RST_PERIOD_POS 4 /**< CTRL_RST_PERIOD Position */
-#define MXC_F_WDT_CTRL_RST_PERIOD \
- ((uint32_t)( \
- 0xFUL << MXC_F_WDT_CTRL_RST_PERIOD_POS)) /**< CTRL_RST_PERIOD \
- Mask */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW31 \
- ((uint32_t)0x0UL) /**< CTRL_RST_PERIOD_WDT2POW31 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW31 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW31 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW31 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW30 \
- ((uint32_t)0x1UL) /**< CTRL_RST_PERIOD_WDT2POW30 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW30 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW30 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW30 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW29 \
- ((uint32_t)0x2UL) /**< CTRL_RST_PERIOD_WDT2POW29 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW29 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW29 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW29 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW28 \
- ((uint32_t)0x3UL) /**< CTRL_RST_PERIOD_WDT2POW28 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW28 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW28 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW28 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW27 \
- ((uint32_t)0x4UL) /**< CTRL_RST_PERIOD_WDT2POW27 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW27 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW27 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW27 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW26 \
- ((uint32_t)0x5UL) /**< CTRL_RST_PERIOD_WDT2POW26 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW26 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW26 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW26 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW25 \
- ((uint32_t)0x6UL) /**< CTRL_RST_PERIOD_WDT2POW25 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW25 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW25 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW25 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW24 \
- ((uint32_t)0x7UL) /**< CTRL_RST_PERIOD_WDT2POW24 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW24 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW24 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW24 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW23 \
- ((uint32_t)0x8UL) /**< CTRL_RST_PERIOD_WDT2POW23 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW23 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW23 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW23 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW22 \
- ((uint32_t)0x9UL) /**< CTRL_RST_PERIOD_WDT2POW22 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW22 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW22 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW22 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW21 \
- ((uint32_t)0xAUL) /**< CTRL_RST_PERIOD_WDT2POW21 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW21 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW21 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW21 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW20 \
- ((uint32_t)0xBUL) /**< CTRL_RST_PERIOD_WDT2POW20 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW20 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW20 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW20 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW19 \
- ((uint32_t)0xCUL) /**< CTRL_RST_PERIOD_WDT2POW19 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW19 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW19 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW19 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW18 \
- ((uint32_t)0xDUL) /**< CTRL_RST_PERIOD_WDT2POW18 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW18 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW18 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW18 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW17 \
- ((uint32_t)0xEUL) /**< CTRL_RST_PERIOD_WDT2POW17 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW17 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW17 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW17 \
- Setting */
-#define MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW16 \
- ((uint32_t)0xFUL) /**< CTRL_RST_PERIOD_WDT2POW16 Value */
-#define MXC_S_WDT_CTRL_RST_PERIOD_WDT2POW16 \
- (MXC_V_WDT_CTRL_RST_PERIOD_WDT2POW16 \
- << MXC_F_WDT_CTRL_RST_PERIOD_POS) /**< CTRL_RST_PERIOD_WDT2POW16 \
- Setting */
-
-#define MXC_F_WDT_CTRL_WDT_EN_POS 8 /**< CTRL_WDT_EN Position */
-#define MXC_F_WDT_CTRL_WDT_EN \
- ((uint32_t)( \
- 0x1UL << MXC_F_WDT_CTRL_WDT_EN_POS)) /**< CTRL_WDT_EN Mask */
-#define MXC_V_WDT_CTRL_WDT_EN_DIS \
- ((uint32_t)0x0UL) /**< CTRL_WDT_EN_DIS Value */
-#define MXC_S_WDT_CTRL_WDT_EN_DIS \
- (MXC_V_WDT_CTRL_WDT_EN_DIS \
- << MXC_F_WDT_CTRL_WDT_EN_POS) /**< CTRL_WDT_EN_DIS Setting */
-#define MXC_V_WDT_CTRL_WDT_EN_EN \
- ((uint32_t)0x1UL) /**< CTRL_WDT_EN_EN Value \
- */
-#define MXC_S_WDT_CTRL_WDT_EN_EN \
- (MXC_V_WDT_CTRL_WDT_EN_EN \
- << MXC_F_WDT_CTRL_WDT_EN_POS) /**< CTRL_WDT_EN_EN Setting */
-
-#define MXC_F_WDT_CTRL_INT_FLAG_POS 9 /**< CTRL_INT_FLAG Position */
-#define MXC_F_WDT_CTRL_INT_FLAG \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_WDT_CTRL_INT_FLAG_POS)) /**< CTRL_INT_FLAG Mask */
-#define MXC_V_WDT_CTRL_INT_FLAG_INACTIVE \
- ((uint32_t)0x0UL) /**< CTRL_INT_FLAG_INACTIVE Value */
-#define MXC_S_WDT_CTRL_INT_FLAG_INACTIVE \
- (MXC_V_WDT_CTRL_INT_FLAG_INACTIVE \
- << MXC_F_WDT_CTRL_INT_FLAG_POS) /**< CTRL_INT_FLAG_INACTIVE Setting \
- */
-#define MXC_V_WDT_CTRL_INT_FLAG_PENDING \
- ((uint32_t)0x1UL) /**< CTRL_INT_FLAG_PENDING Value */
-#define MXC_S_WDT_CTRL_INT_FLAG_PENDING \
- (MXC_V_WDT_CTRL_INT_FLAG_PENDING \
- << MXC_F_WDT_CTRL_INT_FLAG_POS) /**< CTRL_INT_FLAG_PENDING Setting */
-
-#define MXC_F_WDT_CTRL_INT_EN_POS 10 /**< CTRL_INT_EN Position */
-#define MXC_F_WDT_CTRL_INT_EN \
- ((uint32_t)( \
- 0x1UL << MXC_F_WDT_CTRL_INT_EN_POS)) /**< CTRL_INT_EN Mask */
-#define MXC_V_WDT_CTRL_INT_EN_DIS \
- ((uint32_t)0x0UL) /**< CTRL_INT_EN_DIS Value */
-#define MXC_S_WDT_CTRL_INT_EN_DIS \
- (MXC_V_WDT_CTRL_INT_EN_DIS \
- << MXC_F_WDT_CTRL_INT_EN_POS) /**< CTRL_INT_EN_DIS Setting */
-#define MXC_V_WDT_CTRL_INT_EN_EN \
- ((uint32_t)0x1UL) /**< CTRL_INT_EN_EN Value \
- */
-#define MXC_S_WDT_CTRL_INT_EN_EN \
- (MXC_V_WDT_CTRL_INT_EN_EN \
- << MXC_F_WDT_CTRL_INT_EN_POS) /**< CTRL_INT_EN_EN Setting */
-
-#define MXC_F_WDT_CTRL_RST_EN_POS 11 /**< CTRL_RST_EN Position */
-#define MXC_F_WDT_CTRL_RST_EN \
- ((uint32_t)( \
- 0x1UL << MXC_F_WDT_CTRL_RST_EN_POS)) /**< CTRL_RST_EN Mask */
-#define MXC_V_WDT_CTRL_RST_EN_DIS \
- ((uint32_t)0x0UL) /**< CTRL_RST_EN_DIS Value */
-#define MXC_S_WDT_CTRL_RST_EN_DIS \
- (MXC_V_WDT_CTRL_RST_EN_DIS \
- << MXC_F_WDT_CTRL_RST_EN_POS) /**< CTRL_RST_EN_DIS Setting */
-#define MXC_V_WDT_CTRL_RST_EN_EN \
- ((uint32_t)0x1UL) /**< CTRL_RST_EN_EN Value \
- */
-#define MXC_S_WDT_CTRL_RST_EN_EN \
- (MXC_V_WDT_CTRL_RST_EN_EN \
- << MXC_F_WDT_CTRL_RST_EN_POS) /**< CTRL_RST_EN_EN Setting */
-
-#define MXC_F_WDT_CTRL_RST_FLAG_POS 31 /**< CTRL_RST_FLAG Position */
-#define MXC_F_WDT_CTRL_RST_FLAG \
- ((uint32_t)( \
- 0x1UL \
- << MXC_F_WDT_CTRL_RST_FLAG_POS)) /**< CTRL_RST_FLAG Mask */
-#define MXC_V_WDT_CTRL_RST_FLAG_NOEVENT \
- ((uint32_t)0x0UL) /**< CTRL_RST_FLAG_NOEVENT Value */
-#define MXC_S_WDT_CTRL_RST_FLAG_NOEVENT \
- (MXC_V_WDT_CTRL_RST_FLAG_NOEVENT \
- << MXC_F_WDT_CTRL_RST_FLAG_POS) /**< CTRL_RST_FLAG_NOEVENT Setting */
-#define MXC_V_WDT_CTRL_RST_FLAG_OCCURRED \
- ((uint32_t)0x1UL) /**< CTRL_RST_FLAG_OCCURRED Value */
-#define MXC_S_WDT_CTRL_RST_FLAG_OCCURRED \
- (MXC_V_WDT_CTRL_RST_FLAG_OCCURRED \
- << MXC_F_WDT_CTRL_RST_FLAG_POS) /**< CTRL_RST_FLAG_OCCURRED Setting \
- */
-
-/**
- * Watchdog Timer Reset Register.
- */
-#define MXC_F_WDT_RST_WDT_RST_POS 0 /**< RST_WDT_RST Position */
-#define MXC_F_WDT_RST_WDT_RST \
- ((uint32_t)( \
- 0xFFUL << MXC_F_WDT_RST_WDT_RST_POS)) /**< RST_WDT_RST Mask */
-#define MXC_V_WDT_RST_WDT_RST_SEQ0 \
- ((uint32_t)0xA5UL) /**< RST_WDT_RST_SEQ0 Value */
-#define MXC_S_WDT_RST_WDT_RST_SEQ0 \
- (MXC_V_WDT_RST_WDT_RST_SEQ0 \
- << MXC_F_WDT_RST_WDT_RST_POS) /**< RST_WDT_RST_SEQ0 Setting */
-#define MXC_V_WDT_RST_WDT_RST_SEQ1 \
- ((uint32_t)0x5AUL) /**< RST_WDT_RST_SEQ1 Value */
-#define MXC_S_WDT_RST_WDT_RST_SEQ1 \
- (MXC_V_WDT_RST_WDT_RST_SEQ1 \
- << MXC_F_WDT_RST_WDT_RST_POS) /**< RST_WDT_RST_SEQ1 Setting */
-
-#endif /* _WDT_REGS_H_ */