summaryrefslogtreecommitdiff
path: root/chip/lm4
diff options
context:
space:
mode:
authorJack Rosenthal <jrosenth@chromium.org>2021-11-04 12:11:58 -0600
committerCommit Bot <commit-bot@chromium.org>2021-11-05 04:22:34 +0000
commit252457d4b21f46889eebad61d4c0a65331919cec (patch)
tree01856c4d31d710b20e85a74c8d7b5836e35c3b98 /chip/lm4
parent08f5a1e6fc2c9467230444ac9b582dcf4d9f0068 (diff)
downloadchrome-ec-stabilize-14588.123.B-ish.tar.gz
In the interest of making long-term branch maintenance incur as little technical debt on us as possible, we should not maintain any files on the branch we are not actually using. This has the added effect of making it extremely clear when merging CLs from the main branch when changes have the possibility to affect us. The follow-on CL adds a convenience script to actually pull updates from the main branch and generate a CL for the update. BUG=b:204206272 BRANCH=ish TEST=make BOARD=arcada_ish && make BOARD=drallion_ish Signed-off-by: Jack Rosenthal <jrosenth@chromium.org> Change-Id: I17e4694c38219b5a0823e0a3e55a28d1348f4b18 Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/3262038 Reviewed-by: Jett Rink <jettrink@chromium.org> Reviewed-by: Tom Hughes <tomhughes@chromium.org>
Diffstat (limited to 'chip/lm4')
-rw-r--r--chip/lm4/adc.c273
-rw-r--r--chip/lm4/adc_chip.h44
-rw-r--r--chip/lm4/build.mk31
-rw-r--r--chip/lm4/chip_temp_sensor.c29
-rw-r--r--chip/lm4/clock.c754
-rw-r--r--chip/lm4/config_chip.h108
-rw-r--r--chip/lm4/eeprom.c268
-rw-r--r--chip/lm4/fan.c192
-rw-r--r--chip/lm4/flash.c293
-rw-r--r--chip/lm4/gpio.c385
-rw-r--r--chip/lm4/hwtimer.c108
-rw-r--r--chip/lm4/i2c.c413
-rw-r--r--chip/lm4/keyboard_raw.c119
-rw-r--r--chip/lm4/lpc.c835
-rw-r--r--chip/lm4/peci.c152
-rw-r--r--chip/lm4/pwm.c70
-rw-r--r--chip/lm4/pwm_chip.h21
-rw-r--r--chip/lm4/registers.h600
-rw-r--r--chip/lm4/spi.c179
-rw-r--r--chip/lm4/system.c776
-rw-r--r--chip/lm4/uart.c352
-rw-r--r--chip/lm4/watchdog.c120
22 files changed, 0 insertions, 6122 deletions
diff --git a/chip/lm4/adc.c b/chip/lm4/adc.c
deleted file mode 100644
index 13b5ebdebd..0000000000
--- a/chip/lm4/adc.c
+++ /dev/null
@@ -1,273 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* LM4-specific ADC module for Chrome EC */
-
-#include "adc.h"
-#include "atomic.h"
-#include "clock.h"
-#include "console.h"
-#include "common.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "registers.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-
-/* Maximum time we allow for an ADC conversion */
-#define ADC_TIMEOUT_US SECOND
-
-static volatile task_id_t task_waiting_on_ss[LM4_ADC_SEQ_COUNT];
-
-static void configure_gpio(void)
-{
- int i, port, mask;
-
- /* Use analog function for AIN */
- for (i = 0; i < ADC_CH_COUNT; ++i) {
- if (adc_channels[i].gpio_mask) {
- mask = adc_channels[i].gpio_mask;
- port = adc_channels[i].gpio_port;
- LM4_GPIO_DEN(port) &= ~mask;
- LM4_GPIO_AMSEL(port) |= mask;
- }
- }
-}
-
-/**
- * Flush an ADC sequencer and initiate a read.
- *
- * @param seq Sequencer to read
- * @return Raw ADC value.
- */
-static int flush_and_read(enum lm4_adc_sequencer seq)
-{
- /*
- * This is currently simple because we can dedicate a sequencer to each
- * ADC channel. If we have enough channels that's no longer possible,
- * this code will need to become more complex. For example, we could:
- *
- * 1) Read them all using a timer interrupt, and then return the most
- * recent value? This is lowest-latency for the caller, but won't
- * return accurate data if read frequently.
- *
- * 2) Reserve SS3 for reading a single value, and configure it on each
- * read? Needs mutex if we could have multiple callers; doesn't matter
- * if just used for debugging.
- *
- * 3) Both?
- */
- volatile uint32_t scratch __attribute__((unused));
- int event;
-
- /* Empty the FIFO of any previous results */
- while (!(LM4_ADC_SSFSTAT(seq) & 0x100))
- scratch = LM4_ADC_SSFIFO(seq);
-
- /*
- * This assumes we don't have multiple tasks accessing the same
- * sequencer. Add mutex lock if needed.
- */
- task_waiting_on_ss[seq] = task_get_current();
-
- /* Clear the interrupt status */
- LM4_ADC_ADCISC |= 0x01 << seq;
-
- /* Enable interrupt */
- LM4_ADC_ADCIM |= 0x01 << seq;
-
- /* Initiate sample sequence */
- LM4_ADC_ADCPSSI |= 0x01 << seq;
-
- /* Wait for interrupt */
- event = task_wait_event_mask(TASK_EVENT_ADC_DONE, ADC_TIMEOUT_US);
-
- /* Disable interrupt */
- LM4_ADC_ADCIM &= ~(0x01 << seq);
-
- task_waiting_on_ss[seq] = TASK_ID_INVALID;
-
- if (!(event & TASK_EVENT_ADC_DONE))
- return ADC_READ_ERROR;
-
- /* Read the FIFO and convert to temperature */
- return LM4_ADC_SSFIFO(seq);
-}
-
-/**
- * Configure an ADC sequencer to be dedicated for an ADC input.
- *
- * @param seq Sequencer to configure
- * @param ain_id ADC input to use
- * @param ssctl Value for sampler sequencer control register
- *
- */
-static void adc_configure(const struct adc_t *adc)
-{
- const enum lm4_adc_sequencer seq = adc->sequencer;
-
- /* Configure sample sequencer */
- LM4_ADC_ADCACTSS &= ~(0x01 << seq);
-
- /* Trigger sequencer by processor request */
- LM4_ADC_ADCEMUX = (LM4_ADC_ADCEMUX & ~(0xf << (seq * 4))) | 0x00;
-
- /* Sample internal temp sensor */
- if (adc->channel == LM4_AIN_NONE) {
- LM4_ADC_SSMUX(seq) = 0x00;
- LM4_ADC_SSEMUX(seq) = 0x00;
- } else {
- LM4_ADC_SSMUX(seq) = adc->channel & 0xf;
- LM4_ADC_SSEMUX(seq) = adc->channel >> 4;
- }
- LM4_ADC_SSCTL(seq) = adc->flag;
-
- /* Enable sample sequencer */
- LM4_ADC_ADCACTSS |= 0x01 << seq;
-}
-
-int adc_read_channel(enum adc_channel ch)
-{
- const struct adc_t *adc = adc_channels + ch;
- static uint32_t ch_busy_mask;
- static struct mutex adc_clock;
- int rv;
-
- /*
- * TODO(crbug.com/314121): Generalize ADC reads such that any task can
- * trigger a read of any channel.
- */
-
- /*
- * Enable ADC clock and set a bit in ch_busy_mask to signify that this
- * channel is busy. Note, this function may be called from multiple
- * tasks, but each channel may be read by only one task. If assert
- * fails, then it means multiple tasks are trying to read same channel.
- */
- mutex_lock(&adc_clock);
- ASSERT(!(ch_busy_mask & (1UL << ch)));
- clock_enable_peripheral(CGC_OFFSET_ADC, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
- ch_busy_mask |= (1UL << ch);
- mutex_unlock(&adc_clock);
-
- rv = flush_and_read(adc->sequencer);
-
- /*
- * If no ADC channels are busy, then disable ADC clock to conserve
- * power.
- */
- mutex_lock(&adc_clock);
- ch_busy_mask &= ~(1UL << ch);
- if (!ch_busy_mask)
- clock_disable_peripheral(CGC_OFFSET_ADC, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
- mutex_unlock(&adc_clock);
-
- if (rv == ADC_READ_ERROR)
- return ADC_READ_ERROR;
-
- return rv * adc->factor_mul / adc->factor_div + adc->shift;
-}
-
-/*****************************************************************************/
-/* Interrupt handlers */
-
-/**
- * Handle an interrupt on the specified sample sequencer.
- */
-static void handle_interrupt(int ss)
-{
- int id = task_waiting_on_ss[ss];
-
- /* Clear the interrupt status */
- LM4_ADC_ADCISC = (0x1 << ss);
-
- /* Wake up the task which was waiting on the interrupt, if any */
- if (id != TASK_ID_INVALID)
- task_set_event(id, TASK_EVENT_ADC_DONE);
-}
-
-void ss0_interrupt(void) { handle_interrupt(0); }
-void ss1_interrupt(void) { handle_interrupt(1); }
-void ss2_interrupt(void) { handle_interrupt(2); }
-void ss3_interrupt(void) { handle_interrupt(3); }
-
-DECLARE_IRQ(LM4_IRQ_ADC0_SS0, ss0_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_ADC0_SS1, ss1_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_ADC0_SS2, ss2_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_ADC0_SS3, ss3_interrupt, 2);
-
-/*****************************************************************************/
-/* Console commands */
-
-#ifdef CONFIG_CMD_ECTEMP
-static int command_ectemp(int argc, char **argv)
-{
- int t = adc_read_channel(ADC_CH_EC_TEMP);
- ccprintf("EC temperature is %d K = %d C\n", t, K_TO_C(t));
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(ectemp, command_ectemp,
- NULL,
- "Print EC temperature");
-#endif
-
-/*****************************************************************************/
-/* Initialization */
-
-static void adc_init(void)
-{
- int i;
-
- /* Configure GPIOs */
- configure_gpio();
-
- /*
- * Temporarily enable the PLL when turning on the clock to the ADC
- * module, to work around chip errata (10.4). No need to notify
- * other modules; the PLL isn't enabled long enough to matter.
- */
- clock_enable_pll(1, 0);
-
- /* Enable ADC0 module in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_ADC, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- /*
- * Use external voltage references (VREFA+, VREFA-) instead of
- * VDDA and GNDA.
- */
- LM4_ADC_ADCCTL = 0x01;
-
- /* Use internal oscillator */
- LM4_ADC_ADCCC = 0x1;
-
- /* Disable the PLL now that the ADC is using the internal oscillator */
- clock_enable_pll(0, 0);
-
- /* No tasks waiting yet */
- for (i = 0; i < LM4_ADC_SEQ_COUNT; i++)
- task_waiting_on_ss[i] = TASK_ID_INVALID;
-
- /* Enable IRQs */
- task_enable_irq(LM4_IRQ_ADC0_SS0);
- task_enable_irq(LM4_IRQ_ADC0_SS1);
- task_enable_irq(LM4_IRQ_ADC0_SS2);
- task_enable_irq(LM4_IRQ_ADC0_SS3);
-
- /* 2**6 = 64x oversampling */
- LM4_ADC_ADCSAC = 6;
-
- /* Initialize ADC sequencer */
- for (i = 0; i < ADC_CH_COUNT; ++i)
- adc_configure(adc_channels + i);
-
- /* Disable ADC0 module until it is needed to conserve power. */
- clock_disable_peripheral(CGC_OFFSET_ADC, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-}
-DECLARE_HOOK(HOOK_INIT, adc_init, HOOK_PRIO_INIT_ADC);
diff --git a/chip/lm4/adc_chip.h b/chip/lm4/adc_chip.h
deleted file mode 100644
index a402c845a1..0000000000
--- a/chip/lm4/adc_chip.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* LM4-specific ADC module for Chrome EC */
-
-#ifndef __CROS_EC_ADC_CHIP_H
-#define __CROS_EC_ADC_CHIP_H
-
-#include <stdint.h>
-
-enum lm4_adc_sequencer {
- LM4_ADC_SEQ0 = 0,
- LM4_ADC_SEQ1,
- LM4_ADC_SEQ2,
- LM4_ADC_SEQ3,
- LM4_ADC_SEQ_COUNT
-};
-
-/* Data structure to define ADC channels. */
-struct adc_t {
- const char *name;
- enum lm4_adc_sequencer sequencer;
- int factor_mul;
- int factor_div;
- int shift;
- int channel;
- int flag;
- uint32_t gpio_port;
- uint8_t gpio_mask;
-};
-
-/* Minimum and maximum values returned by raw ADC read. */
-#define ADC_READ_MIN 0
-#define ADC_READ_MAX 4095
-
-/* Just plain id mapping for code readability */
-#define LM4_AIN(x) (x)
-
-/* Mock value for "channel" in adc_t if we don't have an external channel. */
-#define LM4_AIN_NONE (-1)
-
-#endif /* __CROS_EC_ADC_CHIP_H */
diff --git a/chip/lm4/build.mk b/chip/lm4/build.mk
deleted file mode 100644
index 26419d3a04..0000000000
--- a/chip/lm4/build.mk
+++ /dev/null
@@ -1,31 +0,0 @@
-# -*- makefile -*-
-# Copyright 2013 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.
-#
-# LM4 chip specific files build
-#
-
-# LM4 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.o gpio.o hwtimer.o system.o uart.o
-
-# Optional chip modules
-chip-$(CONFIG_ADC)+=adc.o chip_temp_sensor.o
-chip-$(CONFIG_EEPROM)+=eeprom.o
-chip-$(CONFIG_FANS)+=fan.o
-chip-$(CONFIG_FLASH_PHYSICAL)+=flash.o
-chip-$(CONFIG_I2C)+=i2c.o
-chip-$(CONFIG_HOSTCMD_LPC)+=lpc.o
-chip-$(CONFIG_PECI)+=peci.o
-# pwm functions are implemented with the fan functions
-chip-$(CONFIG_PWM)+=pwm.o fan.o
-chip-$(CONFIG_SPI)+=spi.o
-chip-$(CONFIG_WATCHDOG)+=watchdog.o
-ifndef CONFIG_KEYBOARD_NOT_RAW
-chip-$(HAS_TASK_KEYSCAN)+=keyboard_raw.o
-endif
diff --git a/chip/lm4/chip_temp_sensor.c b/chip/lm4/chip_temp_sensor.c
deleted file mode 100644
index 93b66f5f3f..0000000000
--- a/chip/lm4/chip_temp_sensor.c
+++ /dev/null
@@ -1,29 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* Temperature sensor module for Chrome EC */
-
-#include "adc.h"
-#include "common.h"
-#include "hooks.h"
-
-/* Initialize temperature reading to a valid value (27 C) */
-static int last_val = C_TO_K(27);
-
-static void chip_temp_sensor_poll(void)
-{
- last_val = adc_read_channel(ADC_CH_EC_TEMP);
-}
-DECLARE_HOOK(HOOK_SECOND, chip_temp_sensor_poll, HOOK_PRIO_TEMP_SENSOR);
-
-int chip_temp_sensor_get_val(int idx, int *temp_ptr)
-{
- if (last_val == ADC_READ_ERROR)
- return EC_ERROR_UNKNOWN;
-
- *temp_ptr = last_val;
-
- return EC_SUCCESS;
-}
diff --git a/chip/lm4/clock.c b/chip/lm4/clock.c
deleted file mode 100644
index 39800c9034..0000000000
--- a/chip/lm4/clock.c
+++ /dev/null
@@ -1,754 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* Clocks and power management settings */
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "cpu.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "hwtimer.h"
-#include "registers.h"
-#include "system.h"
-#include "task.h"
-#include "timer.h"
-#include "uart.h"
-#include "util.h"
-#include "watchdog.h"
-
-/* Console output macros */
-#define CPUTS(outstr) cputs(CC_CLOCK, outstr)
-#define CPRINTS(format, args...) cprints(CC_CLOCK, format, ## args)
-
-#define PLL_CLOCK 66666667 /* System clock = 200MHz PLL/3 = 66.667MHz */
-
-#ifdef CONFIG_LOW_POWER_USE_LFIOSC
-/*
- * Length of time for the processor to wake up from deep sleep. Actual
- * measurement gives anywhere up to 780us, depending on the mode it is coming
- * out of. The datasheet gives a maximum of 846us, for coming out of deep
- * sleep in our worst case deep sleep mode.
- */
-#define DEEP_SLEEP_RECOVER_TIME_USEC 850
-#else
-/*
- * Length of time for the processor to wake up from deep sleep. Datasheet
- * maximum is 145us, but in practice have seen as much as 336us.
- */
-#define DEEP_SLEEP_RECOVER_TIME_USEC 400
-#endif
-
-/* Low power idle statistics */
-#ifdef CONFIG_LOW_POWER_IDLE
-static int idle_sleep_cnt;
-static int idle_dsleep_cnt;
-static uint64_t idle_dsleep_time_us;
-static int dsleep_recovery_margin_us = 1000000;
-
-/*
- * Fixed amount of time to keep the console in use flag true after boot in
- * order to give a permanent window in which the low speed clock is not used.
- */
-#define CONSOLE_IN_USE_ON_BOOT_TIME (15*SECOND)
-
-static int console_in_use_timeout_sec = 60;
-static timestamp_t console_expire_time;
-#endif
-
-static int freq;
-
-/**
- * Disable the PLL; run off internal oscillator.
- */
-static void disable_pll(void)
-{
- /* Switch to 16MHz internal oscillator and power down the PLL */
- LM4_SYSTEM_RCC = LM4_SYSTEM_RCC_SYSDIV(0) |
- LM4_SYSTEM_RCC_BYPASS |
- LM4_SYSTEM_RCC_PWRDN |
- LM4_SYSTEM_RCC_OSCSRC(1) |
- LM4_SYSTEM_RCC_MOSCDIS;
-
-#ifdef CONFIG_LOW_POWER_IDLE
- /*
- * If using the low power idle, then set the ACG bit, which specifies
- * that the sleep and deep sleep modes are using their own clock gating
- * registers SCGC and DCGS respectively instead of using the run mode
- * clock gating registers RCGC.
- */
- LM4_SYSTEM_RCC |= LM4_SYSTEM_RCC_ACG;
-#endif
-
- LM4_SYSTEM_RCC2 &= ~LM4_SYSTEM_RCC2_USERCC2;
-
- freq = INTERNAL_CLOCK;
-}
-
-/**
- * Enable the PLL to run at full clock speed.
- */
-static void enable_pll(void)
-{
- /* Disable the PLL so we can reconfigure it */
- disable_pll();
-
- /*
- * Enable the PLL (PWRDN is no longer set) and set divider. PLL is
- * still bypassed, since it hasn't locked yet.
- */
- LM4_SYSTEM_RCC = LM4_SYSTEM_RCC_SYSDIV(2) |
- LM4_SYSTEM_RCC_USESYSDIV |
- LM4_SYSTEM_RCC_BYPASS |
- LM4_SYSTEM_RCC_OSCSRC(1) |
- LM4_SYSTEM_RCC_MOSCDIS;
-
-#ifdef CONFIG_LOW_POWER_IDLE
- /*
- * If using the low power idle, then set the ACG bit, which specifies
- * that the sleep and deep sleep modes are using their own clock gating
- * registers SCGC and DCGS respectively instead of using the run mode
- * clock gating registers RCGC.
- */
- LM4_SYSTEM_RCC |= LM4_SYSTEM_RCC_ACG;
-#endif
-
- /* Wait for the PLL to lock */
- clock_wait_cycles(1024);
- while (!(LM4_SYSTEM_PLLSTAT & 1))
- ;
-
- /* Remove bypass on PLL */
- LM4_SYSTEM_RCC &= ~LM4_SYSTEM_RCC_BYPASS;
- freq = PLL_CLOCK;
-}
-
-void clock_enable_pll(int enable, int notify)
-{
- if (enable)
- enable_pll();
- else
- disable_pll();
-
- /* Notify modules of frequency change */
- if (notify)
- hook_notify(HOOK_FREQ_CHANGE);
-}
-
-void clock_wait_cycles(uint32_t cycles)
-{
- asm volatile("1: subs %0, #1\n"
- " bne 1b\n" : "+r"(cycles));
-}
-
-int clock_get_freq(void)
-{
- return freq;
-}
-
-void clock_init(void)
-{
-#ifdef BOARD_BDS
- /*
- * Perform an auto calibration of the internal oscillator using the
- * 32.768KHz hibernate clock, unless we've already done so. This is
- * only necessary on A2 silicon as on BDS; A3 silicon is all
- * factory-trimmed.
- */
- if ((LM4_SYSTEM_PIOSCSTAT & 0x300) != 0x100) {
- /* Start calibration */
- LM4_SYSTEM_PIOSCCAL = 0x80000000;
- LM4_SYSTEM_PIOSCCAL = 0x80000200;
- /* Wait for result */
- clock_wait_cycles(16);
- while (!(LM4_SYSTEM_PIOSCSTAT & 0x300))
- ;
- }
-#else
- /*
- * Only BDS has an external crystal; other boards don't have one, and
- * can disable main oscillator control to reduce power consumption.
- */
- LM4_SYSTEM_MOSCCTL = 0x04;
-#endif
-
- /* Make sure PLL is disabled */
- disable_pll();
-}
-
-void clock_enable_peripheral(uint32_t offset, uint32_t mask, uint32_t mode)
-{
- if (mode & CGC_MODE_RUN)
- *(LM4_SYSTEM_RCGC_BASE + offset) |= mask;
-
- if (mode & CGC_MODE_SLEEP)
- *(LM4_SYSTEM_SCGC_BASE + offset) |= mask;
-
- if (mode & CGC_MODE_DSLEEP)
- *(LM4_SYSTEM_DCGC_BASE + offset) |= mask;
-
- /* Wait for clock change to take affect. */
- clock_wait_cycles(3);
-}
-
-void clock_disable_peripheral(uint32_t offset, uint32_t mask, uint32_t mode)
-{
- if (mode & CGC_MODE_RUN)
- *(LM4_SYSTEM_RCGC_BASE + offset) &= ~mask;
-
- if (mode & CGC_MODE_SLEEP)
- *(LM4_SYSTEM_SCGC_BASE + offset) &= ~mask;
-
- if (mode & CGC_MODE_DSLEEP)
- *(LM4_SYSTEM_DCGC_BASE + offset) &= ~mask;
-}
-
-/*
- * The low power idle task does not support using the EEPROM,
- * because it is dangerous to go to deep sleep while EEPROM
- * transaction is in progress. To fix, LM4_EEPROM_EEDONE, should
- * be checked before going in to deep sleep.
- */
-#if defined(CONFIG_LOW_POWER_IDLE) && defined(CONFIG_EEPROM)
-#error "Low power idle mode does not support use of EEPROM"
-#endif
-
-#ifdef CONFIG_LOW_POWER_IDLE
-
-void clock_refresh_console_in_use(void)
-{
- disable_sleep(SLEEP_MASK_CONSOLE);
-
- /* Set console in use expire time. */
- console_expire_time = get_time();
- console_expire_time.val += console_in_use_timeout_sec * SECOND;
-
-}
-
-/* Low power idle task. Executed when no tasks are ready to be scheduled. */
-void __idle(void)
-{
- timestamp_t t0, t1, rtc_t0, rtc_t1;
- int next_delay = 0;
- int time_for_dsleep, margin_us;
- int use_low_speed_clock;
-
- /* Enable the hibernate IRQ used to wake up from deep sleep */
- system_enable_hib_interrupt();
-
- /* Set SRAM and flash power management to 'low power' in deep sleep. */
- LM4_SYSTEM_DSLPPWRCFG = 0x23;
-
- /* Enable JTAG interrupt which will notify us when JTAG is in use. */
- gpio_enable_interrupt(GPIO_JTAG_TCK);
-
- /*
- * Initialize console in use to true and specify the console expire
- * time in order to give a fixed window on boot in which the low speed
- * clock will not be used in idle.
- */
- disable_sleep(SLEEP_MASK_CONSOLE);
- console_expire_time.val = get_time().val + CONSOLE_IN_USE_ON_BOOT_TIME;
-
- /*
- * Print when the idle task starts. This is the lowest priority task,
- * so this only starts once all other tasks have gotten a chance to do
- * their task inits and have gone to sleep.
- */
- CPRINTS("low power idle task started");
-
- while (1) {
- /*
- * Disable interrupts before going to deep sleep in order to
- * calculate the appropriate time to wake up. Note: the wfi
- * instruction waits until an interrupt is pending, so it
- * will still wake up even with interrupts disabled.
- */
- interrupt_disable();
-
- t0 = get_time();
- next_delay = __hw_clock_event_get() - t0.le.lo;
-
- /* Do we have enough time before next event to deep sleep. */
- time_for_dsleep = next_delay > (DEEP_SLEEP_RECOVER_TIME_USEC +
- HIB_SET_RTC_MATCH_DELAY_USEC);
-
- if (DEEP_SLEEP_ALLOWED && time_for_dsleep) {
- /* Deep-sleep in STOP mode. */
- idle_dsleep_cnt++;
-
- /* Check if the console use has expired. */
- if ((sleep_mask & SLEEP_MASK_CONSOLE) &&
- t0.val > console_expire_time.val) {
- /* Enable low speed deep sleep. */
- enable_sleep(SLEEP_MASK_CONSOLE);
-
- /*
- * Wait one clock before checking if low speed
- * deep sleep is allowed to give time for
- * sleep mask to update.
- */
- clock_wait_cycles(1);
-
- if (LOW_SPEED_DEEP_SLEEP_ALLOWED)
- CPRINTS("Disabling console in "
- "deep sleep");
- }
-
- /*
- * Determine if we should use a lower clock speed or
- * keep the same (16MHz) clock in deep sleep. Use the
- * lower speed only if the sleep mask specifies that low
- * speed sleep is allowed, the console UART TX is not
- * busy, and the console UART buffer is empty.
- */
- use_low_speed_clock = LOW_SPEED_DEEP_SLEEP_ALLOWED &&
- !uart_tx_in_progress() && uart_buffer_empty();
-
-#ifdef CONFIG_LOW_POWER_USE_LFIOSC
- /* Set the deep sleep clock register. Use either the
- * normal PIOSC (16MHz) or the LFIOSC (32kHz). */
- LM4_SYSTEM_DSLPCLKCFG = use_low_speed_clock ?
- 0x32 : 0x10;
-#else
- /*
- * Set the deep sleep clock register. Use either the
- * PIOSC with no divider (16MHz) or the PIOSC with
- * a /64 divider (250kHz).
- */
- LM4_SYSTEM_DSLPCLKCFG = use_low_speed_clock ?
- 0x1f800010 : 0x10;
-#endif
-
- /*
- * If using low speed clock, disable console.
- * This will also convert the console RX pin to a GPIO
- * and set an edge interrupt to wake us from deep sleep
- * if any action occurs on console.
- */
- if (use_low_speed_clock)
- uart_enter_dsleep();
-
- /* Set deep sleep bit. */
- CPU_SCB_SYSCTRL |= 0x4;
-
- /* Record real time before sleeping. */
- rtc_t0 = system_get_rtc();
-
- /*
- * Set RTC interrupt in time to wake up before
- * next event.
- */
- system_set_rtc_alarm(0, next_delay -
- DEEP_SLEEP_RECOVER_TIME_USEC);
-
- /* Wait for interrupt: goes into deep sleep. */
- asm("wfi");
-
- /* Clear deep sleep bit. */
- CPU_SCB_SYSCTRL &= ~0x4;
-
- /* Disable and clear RTC interrupt. */
- system_reset_rtc_alarm();
-
- /* Fast forward timer according to RTC counter. */
- rtc_t1 = system_get_rtc();
- t1.val = t0.val + (rtc_t1.val - rtc_t0.val);
- force_time(t1);
-
- /* If using low speed clock, re-enable the console. */
- if (use_low_speed_clock)
- uart_exit_dsleep();
-
- /* Record time spent in deep sleep. */
- idle_dsleep_time_us += (rtc_t1.val - rtc_t0.val);
-
- /* Calculate how close we were to missing deadline */
- margin_us = next_delay - (int)(rtc_t1.val - rtc_t0.val);
- if (margin_us < 0)
- CPRINTS("overslept by %dus", -margin_us);
-
- /* Record the closest to missing a deadline. */
- if (margin_us < dsleep_recovery_margin_us)
- dsleep_recovery_margin_us = margin_us;
- } else {
- idle_sleep_cnt++;
-
- /* Normal idle : only CPU clock stopped. */
- asm("wfi");
- }
- interrupt_enable();
- }
-}
-#endif /* CONFIG_LOW_POWER_IDLE */
-
-/*****************************************************************************/
-/* Console commands */
-
-#ifdef CONFIG_CMD_SLEEP
-/**
- * Measure baseline for power consumption.
- *
- * Levels :
- * 0 : CPU running in tight loop
- * 1 : CPU running in tight loop but peripherals gated
- * 2 : CPU in sleep mode
- * 3 : CPU in sleep mode and peripherals gated
- * 4 : CPU in deep sleep mode
- * 5 : CPU in deep sleep mode and peripherals gated
- *
- * Clocks :
- * 0 : No change
- * 1 : 16MHz
- * 2 : 1 MHz
- * 3 : 30kHz
- *
- * SRAM Power Management:
- * 0 : Active
- * 1 : Standby
- * 3 : Low Power
- *
- * Flash Power Management:
- * 0 : Active
- * 2 : Low Power
- */
-static int command_sleep(int argc, char **argv)
-{
- int level = 0;
- int clock = 0;
- int sram_pm = 0;
- int flash_pm = 0;
- uint32_t uartibrd = 0;
- uint32_t uartfbrd = 0;
-
- if (argc >= 2)
- level = strtoi(argv[1], NULL, 10);
- if (argc >= 3)
- clock = strtoi(argv[2], NULL, 10);
- if (argc >= 4)
- sram_pm = strtoi(argv[3], NULL, 10);
- if (argc >= 5)
- flash_pm = strtoi(argv[4], NULL, 10);
-
-#ifdef BOARD_BDS
- /* Remove LED current sink. */
- gpio_set_level(GPIO_DEBUG_LED, 0);
-#endif
-
- ccprintf("Sleep : level %d, clock %d, sram pm %d, flash_pm %d...\n",
- level, clock, sram_pm, flash_pm);
- cflush();
-
- /* Set clock speed. */
- if (clock) {
- /* Use ROM code function to set the clock */
- void **func_table = (void **)*(uint32_t *)0x01000044;
- void (*rom_clock_set)(uint32_t rcc) = func_table[23];
-
- /* Disable interrupts. */
- asm volatile("cpsid i");
-
- switch (clock) {
- case 1: /* 16MHz IOSC */
- uartibrd = 17;
- uartfbrd = 23;
- rom_clock_set(0x00000d51);
- break;
- case 2: /* 1MHz IOSC */
- uartibrd = 1;
- uartfbrd = 5;
- rom_clock_set(0x07C00d51);
- break;
- case 3: /* 30 kHz */
- uartibrd = 0;
- uartfbrd = 0;
- rom_clock_set(0x00000d71);
- break;
- }
-
- /*
- * TODO(crosbug.com/p/23795): move this to the UART module;
- * ugly to have UARTisms here. Also note this only fixes
- * UART0, not UART1. Should just be able to trigger
- * HOOK_FREQ_CHANGE and have that take care of it.
- */
- if (uartfbrd) {
- /* Disable the port via UARTCTL and add HSE. */
- LM4_UART_CTL(0) = 0x0320;
- /* Set the baud rate divisor. */
- LM4_UART_IBRD(0) = uartibrd;
- LM4_UART_FBRD(0) = uartfbrd;
- /* Poke UARTLCRH to make the new divisor take effect. */
- LM4_UART_LCRH(0) = LM4_UART_LCRH(0);
- /* Enable the port. */
- LM4_UART_CTL(0) |= 0x0001;
- }
- asm volatile("cpsie i");
- }
-
- if (uartfbrd) {
- ccprintf("We are still alive. RCC=%08x\n", LM4_SYSTEM_RCC);
- cflush();
- }
-
- /* Enable interrupts. */
- asm volatile("cpsid i");
-
- /* gate peripheral clocks */
- if (level & 1) {
- clock_disable_peripheral(CGC_OFFSET_WD, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_TIMER, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_GPIO, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_DMA, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_HIB, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_UART, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_SSI, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_I2C, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_ADC, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_LPC, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_PECI, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_FAN, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_EEPROM, 0xffffffff,
- CGC_MODE_ALL);
- clock_disable_peripheral(CGC_OFFSET_WTIMER, 0xffffffff,
- CGC_MODE_ALL);
- }
-
- /* Set deep sleep bit. */
- if (level >= 4)
- CPU_SCB_SYSCTRL |= 0x4;
-
- /* Set SRAM and flash PM for sleep and deep sleep. */
- LM4_SYSTEM_SLPPWRCFG = (flash_pm << 4) | sram_pm;
- LM4_SYSTEM_DSLPPWRCFG = (flash_pm << 4) | sram_pm;
-
- /* Go to low power mode (forever ...) */
- if (level > 1)
- while (1) {
- asm("wfi");
- watchdog_reload();
- }
- else
- while (1)
- watchdog_reload();
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(sleep, command_sleep,
- "[level [clock] [sram pm] [flash pm]]",
- "Drop into sleep");
-#endif /* CONFIG_CMD_SLEEP */
-
-#ifdef CONFIG_CMD_PLL
-
-static int command_pll(int argc, char **argv)
-{
- int v;
-
- /* Toggle the PLL */
- if (argc > 1) {
- if (parse_bool(argv[1], &v)) {
- clock_enable_pll(v, 1);
- } else {
- /* Disable PLL and set extra divider */
- char *e;
- v = strtoi(argv[1], &e, 10);
- if (*e)
- return EC_ERROR_PARAM1;
-
- LM4_SYSTEM_RCC = LM4_SYSTEM_RCC_SYSDIV(v - 1) |
- LM4_SYSTEM_RCC_BYPASS |
- LM4_SYSTEM_RCC_PWRDN |
- LM4_SYSTEM_RCC_OSCSRC(1) |
- LM4_SYSTEM_RCC_MOSCDIS;
-
- freq = INTERNAL_CLOCK / v;
-
- /* Notify modules of frequency change */
- hook_notify(HOOK_FREQ_CHANGE);
- }
- }
-
- /* Print current PLL state */
- ccprintf("RCC: 0x%08x\n", LM4_SYSTEM_RCC);
- ccprintf("RCC2: 0x%08x\n", LM4_SYSTEM_RCC2);
- ccprintf("PLLSTAT: 0x%08x\n", LM4_SYSTEM_PLLSTAT);
- ccprintf("Clock: %d Hz\n", clock_get_freq());
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(pll, command_pll,
- "[ on | off | <div> ]",
- "Get/set PLL state");
-
-#endif /* CONFIG_CMD_PLL */
-
-#ifdef CONFIG_CMD_CLOCKGATES
-/**
- * Print all clock gating registers
- */
-static int command_clock_gating(int argc, char **argv)
-{
- ccprintf(" Run , Sleep , Deep Sleep\n");
-
- ccprintf("WD: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_WD));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_WD));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_WD));
-
- ccprintf("TIMER: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_TIMER));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_TIMER));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_TIMER));
-
- ccprintf("GPIO: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_GPIO));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_GPIO));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_GPIO));
-
- ccprintf("DMA: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_DMA));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_DMA));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_DMA));
-
- ccprintf("HIB: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_HIB));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_HIB));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_HIB));
-
- ccprintf("UART: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_UART));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_UART));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_UART));
-
- ccprintf("SSI: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_SSI));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_SSI));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_SSI));
-
- ccprintf("I2C: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_I2C));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_I2C));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_I2C));
-
- ccprintf("ADC: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_ADC));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_ADC));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_ADC));
-
- ccprintf("LPC: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_LPC));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_LPC));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_LPC));
-
- ccprintf("PECI: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_PECI));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_PECI));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_PECI));
-
- ccprintf("FAN: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_FAN));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_FAN));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_FAN));
-
- ccprintf("EEPROM: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_EEPROM));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_EEPROM));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_EEPROM));
-
- ccprintf("WTIMER: 0x%08x, ",
- *(LM4_SYSTEM_RCGC_BASE + CGC_OFFSET_WTIMER));
- ccprintf("0x%08x, ", *(LM4_SYSTEM_SCGC_BASE + CGC_OFFSET_WTIMER));
- ccprintf("0x%08x\n", *(LM4_SYSTEM_DCGC_BASE + CGC_OFFSET_WTIMER));
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(clockgates, command_clock_gating,
- "",
- "Get state of the clock gating controls regs");
-#endif /* CONFIG_CMD_CLOCKGATES */
-
-#ifdef CONFIG_LOW_POWER_IDLE
-/**
- * Print low power idle statistics
- */
-static int command_idle_stats(int argc, char **argv)
-{
- timestamp_t ts = get_time();
-
- ccprintf("Num idle calls that sleep: %d\n", idle_sleep_cnt);
- ccprintf("Num idle calls that deep-sleep: %d\n", idle_dsleep_cnt);
- ccprintf("Time spent in deep-sleep: %.6llds\n",
- idle_dsleep_time_us);
- ccprintf("Total time on: %.6llds\n", ts.val);
- ccprintf("Deep-sleep closest to wake deadline: %dus\n",
- dsleep_recovery_margin_us);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(idlestats, command_idle_stats,
- "",
- "Print last idle stats");
-
-/**
- * Configure deep sleep clock settings.
- */
-static int command_dsleep(int argc, char **argv)
-{
- int v;
-
- if (argc > 1) {
- if (parse_bool(argv[1], &v)) {
- /*
- * Force deep sleep not to use low speed clock or
- * allow it to use the low speed clock.
- */
- if (v)
- disable_sleep(SLEEP_MASK_FORCE_NO_LOW_SPEED);
- else
- enable_sleep(SLEEP_MASK_FORCE_NO_LOW_SPEED);
- } else {
- /* Set console in use timeout. */
- char *e;
- v = strtoi(argv[1], &e, 10);
- if (*e)
- return EC_ERROR_PARAM1;
-
- console_in_use_timeout_sec = v;
-
- /* Refresh console in use to use new timeout. */
- clock_refresh_console_in_use();
- }
- }
-
- ccprintf("Sleep mask: %08x\n", sleep_mask);
- ccprintf("Console in use timeout: %d sec\n",
- console_in_use_timeout_sec);
- ccprintf("DSLPCLKCFG register: 0x%08x\n", LM4_SYSTEM_DSLPCLKCFG);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(dsleep, command_dsleep,
- "[ on | off | <timeout> sec]",
- "Deep sleep clock settings:\nUse 'on' to force deep "
- "sleep not to use low speed clock.\nUse 'off' to "
- "allow deep sleep to auto-select using the low speed "
- "clock.\n"
- "Give a timeout value for the console in use timeout.\n"
- "See also 'sleepmask'.");
-#endif /* CONFIG_LOW_POWER_IDLE */
-
diff --git a/chip/lm4/config_chip.h b/chip/lm4/config_chip.h
deleted file mode 100644
index 4e442004c9..0000000000
--- a/chip/lm4/config_chip.h
+++ /dev/null
@@ -1,108 +0,0 @@
-/* Copyright 2013 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"
-
-/* 16.000 MHz internal oscillator frequency (PIOSC) */
-#define INTERNAL_CLOCK 16000000
-
-/* 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 6
-
-/*
- * 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 0x00008000
-
-/* 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 0x00000800 /* protect bank size */
-#define CONFIG_FLASH_ERASE_SIZE 0x00000400 /* 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
-
-/****************************************************************************/
-/* 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_ADC
-#define CONFIG_HOSTCMD_ALIGNED
-#define CONFIG_HOSTCMD_LPC
-#define CONFIG_PECI
-#define CONFIG_RTC
-#define CONFIG_SWITCH
-#define CONFIG_MPU
-
-/* Chip needs to do custom pre-init */
-#define CONFIG_CHIP_PRE_INIT
-
-#define GPIO_PIN(port, index) GPIO_##port, BIT(index)
-#define GPIO_PIN_MASK(p, m) .port = GPIO_##p, .mask = (m)
-
-#endif /* __CROS_EC_CONFIG_CHIP_H */
diff --git a/chip/lm4/eeprom.c b/chip/lm4/eeprom.c
deleted file mode 100644
index 97fd3bdc24..0000000000
--- a/chip/lm4/eeprom.c
+++ /dev/null
@@ -1,268 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* EEPROM module for Chrome EC */
-
-#include "clock.h"
-#include "console.h"
-#include "eeprom.h"
-#include "registers.h"
-#include "timer.h"
-#include "util.h"
-#include "watchdog.h"
-
-/* Size of EEPROM block in bytes */
-#define EEPROM_BLOCK_SIZE 64
-
-/* Count of EEPROM blocks */
-static int block_count;
-
-/*
- * Wait for the current EEPROM operation to finish; all operations but write
- * should normally finish in 4 system clocks, but worst case is up to
- * 1800ms if the EEPROM needs to do an internal page erase/copy. We must
- * spin-wait for this delay, because EEPROM operations will fail if the chip
- * drops to sleep mode.
- */
-static int wait_for_done(void)
-{
- int j;
-
- for (j = 0; j < 20; j++) { /* 20 * 100 ms = 2000 ms */
- uint64_t tstop = get_time().val + 100 * MSEC;
- while (get_time().val < tstop) {
- if (!(LM4_EEPROM_EEDONE & 0x01))
- return EC_SUCCESS;
- }
- watchdog_reload();
- }
-
- return EC_ERROR_UNKNOWN;
-}
-
-
-int eeprom_get_block_count(void)
-{
- return block_count;
-}
-
-
-int eeprom_get_block_size(void)
-{
- return EEPROM_BLOCK_SIZE;
-}
-
-
-int eeprom_read(int block, int offset, int size, char *data)
-{
- uint32_t *d = (uint32_t *)data;
- int rv;
-
- if (block < 0 || block >= block_count ||
- offset < 0 || offset > EEPROM_BLOCK_SIZE || offset & 3 ||
- size < 0 || offset + size > EEPROM_BLOCK_SIZE || size & 3)
- return EC_ERROR_UNKNOWN;
-
- rv = wait_for_done();
- if (rv)
- return rv;
-
- LM4_EEPROM_EEBLOCK = block;
- if (LM4_EEPROM_EEBLOCK != block)
- return EC_ERROR_UNKNOWN; /* Error setting block */
-
- LM4_EEPROM_EEOFFSET = offset >> 2;
-
- for (; size; size -= sizeof(uint32_t))
- *(d++) = LM4_EEPROM_EERDWRINC;
-
- return EC_SUCCESS;
-}
-
-
-int eeprom_write(int block, int offset, int size, const char *data)
-{
- uint32_t *d = (uint32_t *)data;
- int rv;
-
- if (block < 0 || block >= block_count ||
- offset < 0 || offset > EEPROM_BLOCK_SIZE || offset & 3 ||
- size < 0 || offset + size > EEPROM_BLOCK_SIZE || size & 3)
- return EC_ERROR_UNKNOWN;
-
- rv = wait_for_done();
- if (rv)
- return rv;
-
- LM4_EEPROM_EEBLOCK = block;
- if (LM4_EEPROM_EEBLOCK != block)
- return EC_ERROR_UNKNOWN; /* Error setting block */
-
- LM4_EEPROM_EEOFFSET = offset >> 2;
-
- /* Write 32 bits at a time; wait for each write to complete */
- for (; size; size -= sizeof(uint32_t)) {
- LM4_EEPROM_EERDWRINC = *(d++);
-
- rv = wait_for_done();
- if (rv)
- return rv;
-
- if (LM4_EEPROM_EEDONE & 0x10) {
- /* Failed due to write protect */
- return EC_ERROR_ACCESS_DENIED;
- } else if (LM4_EEPROM_EEDONE & 0x100) {
- /* Failed due to program voltage level */
- return EC_ERROR_UNKNOWN;
- }
- }
-
- return EC_SUCCESS;
-}
-
-
-int eeprom_hide(int block)
-{
- /* Block 0 can't be hidden */
- if (block <= 0 || block >= block_count)
- return EC_ERROR_UNKNOWN;
-
- LM4_EEPROM_EEHIDE |= 1 << block;
- return EC_SUCCESS;
-}
-
-
-/*****************************************************************************/
-/* Console commands */
-
-static int command_eeprom_info(int argc, char **argv)
-{
- ccprintf("%d blocks @ %d bytes, hide=0x%08x\n",
- eeprom_get_block_count(), eeprom_get_block_size(),
- LM4_EEPROM_EEHIDE);
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(eeinfo, command_eeprom_info,
- NULL,
- "Print EEPROM info");
-
-
-static int command_eeprom_read(int argc, char **argv)
-{
- int block = 0;
- int offset = 0;
- char *e;
- int rv;
- uint32_t d;
-
- if (argc < 2)
- return EC_ERROR_PARAM_COUNT;
-
- block = strtoi(argv[1], &e, 0);
- if (*e)
- return EC_ERROR_PARAM1;
-
- if (argc > 2) {
- offset = strtoi(argv[2], &e, 0);
- if (*e)
- return EC_ERROR_PARAM2;
- }
-
- rv = eeprom_read(block, offset, sizeof(d), (char *)&d);
- if (rv == EC_SUCCESS)
- ccprintf("%d:%d = 0x%08x\n", block, offset, d);
- return rv;
-}
-DECLARE_CONSOLE_COMMAND(eeread, command_eeprom_read,
- "block [offset]",
- "Read a word of EEPROM");
-
-
-static int command_eeprom_write(int argc, char **argv)
-{
- int block = 0;
- int offset = 0;
- char *e;
- uint32_t d;
-
- if (argc < 4)
- return EC_ERROR_PARAM_COUNT;
-
- block = strtoi(argv[1], &e, 0);
- if (*e)
- return EC_ERROR_PARAM1;
- offset = strtoi(argv[2], &e, 0);
- if (*e)
- return EC_ERROR_PARAM2;
- d = strtoi(argv[3], &e, 0);
- if (*e)
- return EC_ERROR_PARAM3;
-
- ccprintf("Writing 0x%08x to %d:%d...\n", d, block, offset);
- return eeprom_write(block, offset, sizeof(d), (char *)&d);
-}
-DECLARE_CONSOLE_COMMAND(eewrite, command_eeprom_write,
- "block offset value",
- "Write a word of EEPROM");
-
-
-#ifdef CONSOLE_COMMAND_EEHIDE
-static int command_eeprom_hide(int argc, char **argv)
-{
- int block = 0;
- char *e;
-
- if (argc < 2)
- return EC_ERROR_PARAM_COUNT;
-
- block = strtoi(argv[1], &e, 0);
- if (*e)
- return EC_ERROR_PARAM1;
-
- ccprintf("Hiding block %d\n", block);
- return eeprom_hide(block);
-}
-DECLARE_CONSOLE_COMMAND(eehide, command_eeprom_hide,
- "block",
- "Hide a block of EEPROM");
-#endif
-
-
-/*****************************************************************************/
-/* Initialization */
-
-
-int eeprom_init(void)
-{
- /* Enable the EEPROM module in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_EEPROM, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- /* Wait for internal EEPROM init to finish */
- wait_for_done();
-
- /* Store block count */
- block_count = LM4_EEPROM_EESIZE >> 16;
-
- /*
- * Handle resetting the EEPROM module to clear state from a previous
- * error condition.
- */
- if (LM4_EEPROM_EESUPP & 0xc0) {
- LM4_SYSTEM_SREEPROM = 1;
- clock_wait_cycles(200);
- LM4_SYSTEM_SREEPROM = 0;
-
- /* Wait again for internal init to finish */
- clock_wait_cycles(6);
- wait_for_done();
-
- /* Fail if error condition didn't clear */
- if (LM4_EEPROM_EESUPP & 0xc0)
- return EC_ERROR_UNKNOWN;
- }
-
- return EC_SUCCESS;
-}
diff --git a/chip/lm4/fan.c b/chip/lm4/fan.c
deleted file mode 100644
index b09323a37b..0000000000
--- a/chip/lm4/fan.c
+++ /dev/null
@@ -1,192 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* LM4 fan control module. */
-
-#include "clock.h"
-#include "fan.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "registers.h"
-#include "util.h"
-
-/* Maximum RPM for fan controller */
-#define MAX_RPM 0x1fff
-
-/* Maximum PWM for PWM controller */
-#define MAX_PWM 0x1ff
-
-/*
- * Scaling factor for requested/actual RPM for CPU fan. We need this because
- * the fan controller on Blizzard filters tach pulses that are less than 64
- * 15625Hz ticks apart, which works out to ~7000rpm on an unscaled fan. By
- * telling the controller we actually have twice as many edges per revolution,
- * the controller can handle fans that actually go twice as fast. See
- * crosbug.com/p/7718.
- */
-#define RPM_SCALE 2
-
-
-void fan_set_enabled(int ch, int enabled)
-{
- if (enabled)
- LM4_FAN_FANCTL |= BIT(ch);
- else
- LM4_FAN_FANCTL &= ~BIT(ch);
-}
-
-int fan_get_enabled(int ch)
-{
- return (LM4_FAN_FANCTL & BIT(ch)) ? 1 : 0;
-}
-
-void fan_set_duty(int ch, int percent)
-{
- int duty;
-
- if (percent < 0)
- percent = 0;
- else if (percent > 100)
- percent = 100;
-
- duty = (MAX_PWM * percent + 50) / 100;
-
- /* Always enable the channel */
- fan_set_enabled(ch, 1);
-
- /* Set the duty cycle */
- LM4_FAN_FANCMD(ch) = duty << 16;
-}
-
-int fan_get_duty(int ch)
-{
- return ((LM4_FAN_FANCMD(ch) >> 16) * 100 + MAX_PWM / 2) / MAX_PWM;
-}
-
-int fan_get_rpm_mode(int ch)
-{
- return (LM4_FAN_FANCH(ch) & 0x0001) ? 0 : 1;
-}
-
-void fan_set_rpm_mode(int ch, int rpm_mode)
-{
- int was_enabled = fan_get_enabled(ch);
- int was_rpm = fan_get_rpm_mode(ch);
-
- if (!was_rpm && rpm_mode) {
- /* Enable RPM control */
- fan_set_enabled(ch, 0);
- LM4_FAN_FANCH(ch) &= ~0x0001;
- fan_set_enabled(ch, was_enabled);
- } else if (was_rpm && !rpm_mode) {
- /* Disable RPM mode */
- fan_set_enabled(ch, 0);
- LM4_FAN_FANCH(ch) |= 0x0001;
- fan_set_enabled(ch, was_enabled);
- }
-}
-
-int fan_get_rpm_actual(int ch)
-{
- return (LM4_FAN_FANCST(ch) & MAX_RPM) * RPM_SCALE;
-}
-
-int fan_get_rpm_target(int ch)
-{
- return (LM4_FAN_FANCMD(ch) & MAX_RPM) * RPM_SCALE;
-}
-
-test_mockable void fan_set_rpm_target(int ch, int rpm)
-{
- /* Apply fan scaling */
- if (rpm > 0)
- rpm /= RPM_SCALE;
-
- /* Treat out-of-range requests as requests for maximum fan speed */
- if (rpm < 0 || rpm > MAX_RPM)
- rpm = MAX_RPM;
-
- LM4_FAN_FANCMD(ch) = rpm;
-}
-
-/* The LM4 status is the original definition of enum fan_status */
-enum fan_status fan_get_status(int ch)
-{
- return (LM4_FAN_FANSTS >> (2 * ch)) & 0x03;
-}
-
-/**
- * Return non-zero if fan is enabled but stalled.
- */
-int fan_is_stalled(int ch)
-{
- /* Must be enabled with non-zero target to stall */
- if (!fan_get_enabled(ch) || fan_get_rpm_target(ch) == 0)
- return 0;
-
- /* Check for stall condition */
- return fan_get_status(ch) == FAN_STATUS_STOPPED;
-}
-
-void fan_channel_setup(int ch, unsigned int flags)
-{
- uint32_t init;
-
- if (flags & FAN_USE_RPM_MODE)
- /*
- * Configure automatic/feedback mode:
- * 0x8000 = bit 15 = auto-restart
- * 0x0000 = bit 14 = slow acceleration
- * 0x0000 = bits 13:11 = no hysteresis
- * 0x0000 = bits 10:8 = start period (2<<0) edges
- * 0x0000 = bits 7:6 = no fast start
- * 0x0020 = bits 5:4 = average 4 edges when
- * calculating RPM
- * 0x000c = bits 3:2 = 8 pulses per revolution
- * (see note at top of file)
- * 0x0000 = bit 0 = automatic control
- */
- init = 0x802c;
- else
- /*
- * Configure drive-only mode:
- * 0x0000 = bit 15 = no auto-restart
- * 0x0000 = bit 14 = slow acceleration
- * 0x0000 = bits 13:11 = no hysteresis
- * 0x0000 = bits 10:8 = start period (2<<0) edges
- * 0x0000 = bits 7:6 = no fast start
- * 0x0000 = bits 5:4 = no RPM averaging
- * 0x0000 = bits 3:2 = 1 pulses per revolution
- * 0x0001 = bit 0 = manual control
- */
- init = 0x0001;
-
- if (flags & FAN_USE_FAST_START)
- /*
- * Configure fast-start mode
- * 0x0000 = bits 10:8 = start period (2<<0) edges
- * 0x0040 = bits 7:6 = fast start at 50% duty
- */
- init |= 0x0040;
-
- LM4_FAN_FANCH(ch) = init;
-}
-
-static void fan_init(void)
-{
-
-#ifdef CONFIG_FAN_DSLEEP
- /* Enable the fan module and delay a few clocks */
- clock_enable_peripheral(CGC_OFFSET_FAN, 0x1, CGC_MODE_ALL);
-#else
- /* Enable the fan module and delay a few clocks */
- clock_enable_peripheral(CGC_OFFSET_FAN, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-#endif
- /* Disable all fans */
- LM4_FAN_FANCTL = 0;
-}
-/* Init before PWM */
-DECLARE_HOOK(HOOK_INIT, fan_init, HOOK_PRIO_INIT_FAN);
diff --git a/chip/lm4/flash.c b/chip/lm4/flash.c
deleted file mode 100644
index 5b61874984..0000000000
--- a/chip/lm4/flash.c
+++ /dev/null
@@ -1,293 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* Flash memory module for Chrome EC */
-
-#include "flash.h"
-#include "registers.h"
-#include "switch.h"
-#include "system.h"
-#include "timer.h"
-#include "util.h"
-#include "watchdog.h"
-
-#define FLASH_FWB_WORDS 32
-#define FLASH_FWB_BYTES (FLASH_FWB_WORDS * 4)
-
-#define BANK_SHIFT 5 /* bank registers have 32bits each, 2^32 */
-#define BANK_MASK (BIT(BANK_SHIFT) - 1) /* 5 bits */
-#define F_BANK(b) ((b) >> BANK_SHIFT)
-#define F_BIT(b) (1 << ((b) & BANK_MASK))
-
-/* Flash timeouts. These are 2x the spec sheet max. */
-#define ERASE_TIMEOUT_MS 200
-#define WRITE_TIMEOUT_US 300
-
-int stuck_locked; /* Is physical flash stuck protected? */
-int all_protected; /* Has all-flash protection been requested? */
-
-/**
- * Protect flash banks until reboot.
- *
- * @param start_bank Start bank to protect
- * @param bank_count Number of banks to protect
- */
-static void protect_banks(int start_bank, int bank_count)
-{
- int bank;
- for (bank = start_bank; bank < start_bank + bank_count; bank++)
- LM4_FLASH_FMPPE[F_BANK(bank)] &= ~F_BIT(bank);
-}
-
-/**
- * Perform a write-buffer operation. Buffer (FWB) and address (FMA) must be
- * pre-loaded.
- *
- * @return EC_SUCCESS, or nonzero if error.
- */
-static int write_buffer(void)
-{
- int t;
-
- if (all_protected)
- return EC_ERROR_ACCESS_DENIED;
-
- if (!LM4_FLASH_FWBVAL)
- return EC_SUCCESS; /* Nothing to do */
-
- /* Clear previous error status */
- LM4_FLASH_FCMISC = LM4_FLASH_FCRIS;
-
- /* Start write operation at page boundary */
- LM4_FLASH_FMC2 = 0xa4420001;
-
- /*
- * Reload the watchdog timer, so that writing a large amount of flash
- * doesn't cause a watchdog reset.
- */
- watchdog_reload();
-
- /* Wait for write to complete */
- for (t = 0; LM4_FLASH_FMC2 & 0x01; t += 10) {
- if (t > WRITE_TIMEOUT_US)
- return EC_ERROR_TIMEOUT;
- udelay(10);
- }
-
- /* Check for error conditions - program failed, erase needed,
- * voltage error. */
- if (LM4_FLASH_FCRIS & 0x2e01)
- return EC_ERROR_UNKNOWN;
-
- return EC_SUCCESS;
-}
-
-/*****************************************************************************/
-/* Physical layer APIs */
-
-int crec_flash_physical_write(int offset, int size, const char *data)
-{
- const uint32_t *data32 = (const uint32_t *)data;
- int rv;
- int i;
-
- if (all_protected)
- return EC_ERROR_ACCESS_DENIED;
-
- /* Fail if offset, size, and data aren't at least word-aligned */
- if ((offset | size | (uint32_t)(uintptr_t)data) & 3)
- return EC_ERROR_INVAL;
-
- /* Get initial write buffer index and page */
- LM4_FLASH_FMA = offset & ~(FLASH_FWB_BYTES - 1);
- i = (offset >> 2) & (FLASH_FWB_WORDS - 1);
-
- /* Copy words into buffer */
- for (; size > 0; size -= 4) {
- LM4_FLASH_FWB[i++] = *data32++;
- if (i == FLASH_FWB_WORDS) {
- rv = write_buffer();
- if (rv != EC_SUCCESS)
- return rv;
-
- /* Advance to next page */
- i = 0;
- LM4_FLASH_FMA += FLASH_FWB_BYTES;
- }
- }
-
- /* Handle final partial page, if any */
- if (i > 0)
- return write_buffer();
-
- return EC_SUCCESS;
-}
-
-int crec_flash_physical_erase(int offset, int size)
-{
- if (all_protected)
- return EC_ERROR_ACCESS_DENIED;
-
- LM4_FLASH_FCMISC = LM4_FLASH_FCRIS; /* Clear previous error status */
-
- for (; size > 0; size -= CONFIG_FLASH_ERASE_SIZE,
- offset += CONFIG_FLASH_ERASE_SIZE) {
- int t;
-
- /* Do nothing if already erased */
- if (crec_flash_is_erased(offset, CONFIG_FLASH_ERASE_SIZE))
- continue;
-
- LM4_FLASH_FMA = offset;
-
- /*
- * Reload the watchdog timer, so that erasing many flash pages
- * doesn't cause a watchdog reset. May not need this now that
- * we're using msleep() below.
- */
- watchdog_reload();
-
- /* Start erase */
- LM4_FLASH_FMC = 0xa4420002;
-
- /* Wait for erase to complete */
- for (t = 0; LM4_FLASH_FMC & 0x02; t++) {
- if (t > ERASE_TIMEOUT_MS)
- return EC_ERROR_TIMEOUT;
- msleep(1);
- }
-
- /* Check for error conditions - erase failed, voltage error,
- * protection error */
- if (LM4_FLASH_FCRIS & 0x0a01)
- return EC_ERROR_UNKNOWN;
- }
-
- return EC_SUCCESS;
-}
-
-int crec_flash_physical_get_protect(int bank)
-{
- return (LM4_FLASH_FMPPE[F_BANK(bank)] & F_BIT(bank)) ? 0 : 1;
-}
-
-uint32_t crec_flash_physical_get_protect_flags(void)
-{
- uint32_t flags = 0;
-
- /* Read all-protected state from our shadow copy */
- if (all_protected)
- flags |= EC_FLASH_PROTECT_ALL_NOW;
-
- /* Check if blocks were stuck locked at pre-init */
- if (stuck_locked)
- flags |= EC_FLASH_PROTECT_ERROR_STUCK;
-
- return flags;
-}
-
-int crec_flash_physical_protect_now(int all)
-{
- if (all) {
- /* Protect the entire flash */
- all_protected = 1;
- protect_banks(0, CONFIG_FLASH_SIZE_BYTES /
- CONFIG_FLASH_BANK_SIZE);
- } else
- /* Protect the WP region (read-only section and pstate) */
- protect_banks(WP_BANK_OFFSET, WP_BANK_COUNT);
-
- return EC_SUCCESS;
-}
-
-uint32_t crec_flash_physical_get_valid_flags(void)
-{
- 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)
-{
- uint32_t ret = 0;
-
- /* If RO protection isn't enabled, its at-boot state can be changed. */
- if (!(cur_flags & EC_FLASH_PROTECT_RO_NOW))
- ret |= EC_FLASH_PROTECT_RO_AT_BOOT;
-
- /*
- * If entire flash isn't protected at this boot, it can be enabled if
- * the WP GPIO is asserted.
- */
- if (!(cur_flags & EC_FLASH_PROTECT_ALL_NOW) &&
- (cur_flags & EC_FLASH_PROTECT_GPIO_ASSERTED))
- ret |= EC_FLASH_PROTECT_ALL_NOW;
-
- return ret;
-}
-
-
-/*****************************************************************************/
-/* High-level APIs */
-
-int crec_flash_pre_init(void)
-{
- uint32_t reset_flags = system_get_reset_flags();
- uint32_t prot_flags = crec_flash_get_protect();
- uint32_t unwanted_prot_flags = EC_FLASH_PROTECT_ALL_NOW |
- EC_FLASH_PROTECT_ERROR_INCONSISTENT;
-
- /*
- * If we have already jumped between images, an earlier image could
- * have applied write protection. Nothing additional needs to be done.
- */
- if (reset_flags & EC_RESET_FLAG_SYSJUMP)
- return EC_SUCCESS;
-
- if (prot_flags & EC_FLASH_PROTECT_GPIO_ASSERTED) {
- /*
- * Write protect is asserted. If we want RO flash protected,
- * protect it now.
- */
- if ((prot_flags & EC_FLASH_PROTECT_RO_AT_BOOT) &&
- !(prot_flags & EC_FLASH_PROTECT_RO_NOW)) {
- int rv = crec_flash_set_protect(EC_FLASH_PROTECT_RO_NOW,
- EC_FLASH_PROTECT_RO_NOW);
- if (rv)
- return rv;
-
- /* Re-read flags */
- prot_flags = crec_flash_get_protect();
- }
-
- /* Update all-now flag if all flash is protected */
- if (prot_flags & EC_FLASH_PROTECT_ALL_NOW)
- all_protected = 1;
-
- } else {
- /* Don't want RO flash protected */
- unwanted_prot_flags |= EC_FLASH_PROTECT_RO_NOW;
- }
-
- /* If there are no unwanted flags, done */
- if (!(prot_flags & unwanted_prot_flags))
- return EC_SUCCESS;
-
- /*
- * If the last reboot was a power-on reset, it should have cleared
- * write-protect. If it didn't, then the flash write protect registers
- * have been permanently committed and we can't fix that.
- */
- if (reset_flags & EC_RESET_FLAG_POWER_ON) {
- stuck_locked = 1;
- return EC_ERROR_ACCESS_DENIED;
- }
-
- /* Otherwise, do a hard boot to clear the flash protection registers */
- system_reset(SYSTEM_RESET_HARD | SYSTEM_RESET_PRESERVE_FLAGS);
-
- /* That doesn't return, so if we're still here that's an error */
- return EC_ERROR_UNKNOWN;
-}
diff --git a/chip/lm4/gpio.c b/chip/lm4/gpio.c
deleted file mode 100644
index 841bfdb214..0000000000
--- a/chip/lm4/gpio.c
+++ /dev/null
@@ -1,385 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* GPIO module for Chrome EC */
-
-#include "clock.h"
-#include "common.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "registers.h"
-#include "switch.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-
-/* 0-terminated list of GPIO base addresses */
-static const uint32_t gpio_bases[] = {
- LM4_GPIO_A, LM4_GPIO_B, LM4_GPIO_C, LM4_GPIO_D,
- LM4_GPIO_E, LM4_GPIO_F, LM4_GPIO_G, LM4_GPIO_H,
- LM4_GPIO_J, LM4_GPIO_K, LM4_GPIO_L, LM4_GPIO_M,
- LM4_GPIO_N, LM4_GPIO_P, LM4_GPIO_Q, 0
-};
-
-/**
- * Find the index of a GPIO port base address
- *
- * This is used by the clock gating registers.
- *
- * @param port_base Base address to find (LM4_GPIO_[A-Q])
- *
- * @return The index, or -1 if no match.
- */
-static int find_gpio_port_index(uint32_t port_base)
-{
- int i;
- for (i = 0; gpio_bases[i]; i++) {
- if (gpio_bases[i] == port_base)
- return i;
- }
- return -1;
-}
-
-void gpio_set_alternate_function(uint32_t port, uint32_t mask,
- enum gpio_alternate_func func)
-{
- int port_index = find_gpio_port_index(port);
- int cgmask;
-
- /* Ignore (do nothing for) invalid port values */
- if (port_index < 0)
- return;
-
- /* Enable the GPIO port in run and sleep. */
- cgmask = 1 << port_index;
- clock_enable_peripheral(CGC_OFFSET_GPIO, cgmask,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- if (func != GPIO_ALT_FUNC_NONE) {
- int pctlmask = 0;
- int i;
- /* Expand mask from bits to nibbles */
- for (i = 0; i < 8; i++) {
- if (mask & BIT(i))
- pctlmask |= 1 << (4 * i);
- }
-
- LM4_GPIO_PCTL(port) =
- (LM4_GPIO_PCTL(port) & ~(pctlmask * 0xf)) |
- (pctlmask * func);
- LM4_GPIO_AFSEL(port) |= mask;
- } else {
- LM4_GPIO_AFSEL(port) &= ~mask;
- }
-}
-
-test_mockable int gpio_get_level(enum gpio_signal signal)
-{
- return LM4_GPIO_DATA(gpio_list[signal].port,
- gpio_list[signal].mask) ? 1 : 0;
-}
-
-void gpio_set_level(enum gpio_signal signal, int value)
-{
- /*
- * Ok to write 0xff because LM4_GPIO_DATA bit-masks only the bit
- * we care about.
- */
- LM4_GPIO_DATA(gpio_list[signal].port,
- gpio_list[signal].mask) = (value ? 0xff : 0);
-}
-
-void gpio_set_flags_by_mask(uint32_t port, uint32_t mask, uint32_t flags)
-{
- /*
- * Select open drain first, so that we don't glitch the signal
- * when changing the line to an output.
- */
- if (flags & GPIO_OPEN_DRAIN)
- LM4_GPIO_ODR(port) |= mask;
- else
- LM4_GPIO_ODR(port) &= ~mask;
-
- if (flags & GPIO_OUTPUT)
- LM4_GPIO_DIR(port) |= mask;
- else
- LM4_GPIO_DIR(port) &= ~mask;
-
- /* Handle pullup / pulldown */
- if (flags & GPIO_PULL_UP) {
- LM4_GPIO_PUR(port) |= mask;
- } else if (flags & GPIO_PULL_DOWN) {
- LM4_GPIO_PDR(port) |= mask;
- } else {
- /* No pull up/down */
- LM4_GPIO_PUR(port) &= ~mask;
- LM4_GPIO_PDR(port) &= ~mask;
- }
-
- /* Set up interrupt type */
- if (flags & (GPIO_INT_F_LOW | GPIO_INT_F_HIGH))
- LM4_GPIO_IS(port) |= mask;
- else
- LM4_GPIO_IS(port) &= ~mask;
-
- if (flags & (GPIO_INT_F_RISING | GPIO_INT_F_HIGH))
- LM4_GPIO_IEV(port) |= mask;
- else
- LM4_GPIO_IEV(port) &= ~mask;
-
- /* Handle interrupting on both edges */
- if ((flags & GPIO_INT_F_RISING) &&
- (flags & GPIO_INT_F_FALLING))
- LM4_GPIO_IBE(port) |= mask;
- else
- LM4_GPIO_IBE(port) &= ~mask;
-
- if (flags & GPIO_ANALOG)
- LM4_GPIO_DEN(port) &= ~mask;
- else
- LM4_GPIO_DEN(port) |= mask;
-
- /* Set level */
- if (flags & GPIO_HIGH)
- LM4_GPIO_DATA(port, mask) = 0xff;
- else if (flags & GPIO_LOW)
- LM4_GPIO_DATA(port, mask) = 0;
-}
-
-int gpio_enable_interrupt(enum gpio_signal signal)
-{
- const struct gpio_info *g = gpio_list + signal;
- /* Fail if no interrupt handler */
- if (signal >= GPIO_IH_COUNT)
- return EC_ERROR_UNKNOWN;
-
- LM4_GPIO_IM(g->port) |= g->mask;
- return EC_SUCCESS;
-}
-
-int gpio_disable_interrupt(enum gpio_signal signal)
-{
- const struct gpio_info *g = gpio_list + signal;
-
- /* Fail if no interrupt handler */
- if (signal >= GPIO_IH_COUNT)
- return EC_ERROR_UNKNOWN;
-
- LM4_GPIO_IM(g->port) &= ~g->mask;
- return EC_SUCCESS;
-}
-
-int gpio_clear_pending_interrupt(enum gpio_signal signal)
-{
- const struct gpio_info *g = gpio_list + signal;
-
- /* Fail if no interrupt handler */
- if (signal >= GPIO_IH_COUNT)
- return EC_ERROR_INVAL;
-
- LM4_GPIO_ICR(g->port) |= g->mask;
- return EC_SUCCESS;
-}
-
-#ifdef CONFIG_LOW_POWER_IDLE
-/**
- * Convert GPIO port to a mask that can be used to set the
- * clock gate control register for GPIOs.
- */
-static int gpio_port_to_clock_gate_mask(uint32_t gpio_port)
-{
- int index = find_gpio_port_index(gpio_port);
-
- return index >= 0 ? BIT(index) : 0;
-}
-#endif
-
-void gpio_pre_init(void)
-{
- const struct gpio_info *g = gpio_list;
- int is_warm = 0;
- int i;
-
- if (LM4_SYSTEM_RCGCGPIO == 0x7fff) {
- /* This is a warm reboot */
- is_warm = 1;
- } else {
- /*
- * Enable clocks to all the GPIO blocks since we use all of
- * them as GPIOs in run and sleep modes.
- */
- clock_enable_peripheral(CGC_OFFSET_GPIO, 0x7fff,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
- }
-
- /*
- * Disable GPIO commit control for PD7 and PF0, since we don't use the
- * NMI pin function.
- */
- LM4_GPIO_LOCK(LM4_GPIO_D) = LM4_GPIO_LOCK_UNLOCK;
- LM4_GPIO_CR(LM4_GPIO_D) |= 0x80;
- LM4_GPIO_LOCK(LM4_GPIO_D) = 0;
- LM4_GPIO_LOCK(LM4_GPIO_F) = LM4_GPIO_LOCK_UNLOCK;
- LM4_GPIO_CR(LM4_GPIO_F) |= 0x01;
- LM4_GPIO_LOCK(LM4_GPIO_F) = 0;
-
- /* Clear SSI0 alternate function on PA2:5 */
- LM4_GPIO_AFSEL(LM4_GPIO_A) &= ~0x3c;
-
- /* Mask all GPIO interrupts */
- for (i = 0; gpio_bases[i]; i++)
- LM4_GPIO_IM(gpio_bases[i]) = 0;
-
- /* Set all GPIOs to defaults */
- for (i = 0; i < GPIO_COUNT; i++, g++) {
- int flags = g->flags;
-
- if (flags & GPIO_DEFAULT)
- continue;
-
-#ifdef CONFIG_LOW_POWER_IDLE
- /*
- * Enable board specific GPIO ports to interrupt deep sleep by
- * providing a clock to that port in deep sleep mode.
- */
- if (flags & GPIO_INT_DSLEEP) {
- clock_enable_peripheral(CGC_OFFSET_GPIO,
- gpio_port_to_clock_gate_mask(g->port),
- CGC_MODE_ALL);
- }
-#endif
-
- /*
- * If this is a warm reboot, don't set the output levels or
- * we'll shut off the main chipset.
- */
- if (is_warm)
- flags &= ~(GPIO_LOW | GPIO_HIGH);
-
- /* Set up GPIO based on flags */
- gpio_set_flags_by_mask(g->port, g->mask, flags);
-
- /* Use as GPIO, not alternate function */
- gpio_set_alternate_function(g->port, g->mask,
- GPIO_ALT_FUNC_NONE);
- }
-
-#ifdef CONFIG_LOW_POWER_IDLE
- /*
- * Enable KB scan row to interrupt deep sleep by providing a clock
- * signal to that port in deep sleep mode.
- */
- clock_enable_peripheral(CGC_OFFSET_GPIO,
- gpio_port_to_clock_gate_mask(KB_SCAN_ROW_GPIO),
- CGC_MODE_ALL);
-#endif
-}
-
-/* List of GPIO IRQs to enable. Don't automatically enable interrupts for
- * the keyboard input GPIO bank - that's handled separately. Of course the
- * bank is different for different systems. */
-static const uint8_t gpio_irqs[] = {
- LM4_IRQ_GPIOA, LM4_IRQ_GPIOB, LM4_IRQ_GPIOC, LM4_IRQ_GPIOD,
- LM4_IRQ_GPIOE, LM4_IRQ_GPIOF, LM4_IRQ_GPIOG, LM4_IRQ_GPIOH,
- LM4_IRQ_GPIOJ,
-#if defined(KB_SCAN_ROW_IRQ) && (KB_SCAN_ROW_IRQ != LM4_IRQ_GPIOK)
- LM4_IRQ_GPIOK,
-#endif
- LM4_IRQ_GPIOL, LM4_IRQ_GPIOM,
-#if defined(KB_SCAN_ROW_IRQ) && (KB_SCAN_ROW_IRQ != LM4_IRQ_GPION)
- LM4_IRQ_GPION,
-#endif
- LM4_IRQ_GPIOP, LM4_IRQ_GPIOQ
-};
-
-static void gpio_init(void)
-{
- int i;
-
- /* Enable IRQs now that pins are set up */
- for (i = 0; i < ARRAY_SIZE(gpio_irqs); i++)
- task_enable_irq(gpio_irqs[i]);
-}
-DECLARE_HOOK(HOOK_INIT, gpio_init, HOOK_PRIO_DEFAULT);
-
-/*****************************************************************************/
-/* Interrupt handlers */
-
-/**
- * Handle a GPIO interrupt.
- *
- * @param port GPIO port (LM4_GPIO_*)
- * @param 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. These read and clear the interrupt bits for
- * the port, then call the main handler above.
- */
-#define GPIO_IRQ_FUNC(irqfunc, gpiobase) \
- void irqfunc(void) \
- { \
- uint32_t mis = LM4_GPIO_MIS(gpiobase); \
- LM4_GPIO_ICR(gpiobase) = mis; \
- gpio_interrupt(gpiobase, mis); \
- }
-
-GPIO_IRQ_FUNC(__gpio_a_interrupt, LM4_GPIO_A);
-GPIO_IRQ_FUNC(__gpio_b_interrupt, LM4_GPIO_B);
-GPIO_IRQ_FUNC(__gpio_c_interrupt, LM4_GPIO_C);
-GPIO_IRQ_FUNC(__gpio_d_interrupt, LM4_GPIO_D);
-GPIO_IRQ_FUNC(__gpio_e_interrupt, LM4_GPIO_E);
-GPIO_IRQ_FUNC(__gpio_f_interrupt, LM4_GPIO_F);
-GPIO_IRQ_FUNC(__gpio_g_interrupt, LM4_GPIO_G);
-GPIO_IRQ_FUNC(__gpio_h_interrupt, LM4_GPIO_H);
-GPIO_IRQ_FUNC(__gpio_j_interrupt, LM4_GPIO_J);
-#if defined(KB_SCAN_ROW_GPIO) && (KB_SCAN_ROW_GPIO != LM4_GPIO_K)
-GPIO_IRQ_FUNC(__gpio_k_interrupt, LM4_GPIO_K);
-#endif
-GPIO_IRQ_FUNC(__gpio_l_interrupt, LM4_GPIO_L);
-GPIO_IRQ_FUNC(__gpio_m_interrupt, LM4_GPIO_M);
-#if defined(KB_SCAN_ROW_GPIO) && (KB_SCAN_ROW_GPIO != LM4_GPIO_N)
-GPIO_IRQ_FUNC(__gpio_n_interrupt, LM4_GPIO_N);
-#endif
-GPIO_IRQ_FUNC(__gpio_p_interrupt, LM4_GPIO_P);
-GPIO_IRQ_FUNC(__gpio_q_interrupt, LM4_GPIO_Q);
-
-#undef GPIO_IRQ_FUNC
-
-/*
- * Declare IRQs. Nesting this macro inside the GPIO_IRQ_FUNC macro works
- * poorly because DECLARE_IRQ() stringizes its inputs.
- */
-DECLARE_IRQ(LM4_IRQ_GPIOA, __gpio_a_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOB, __gpio_b_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOC, __gpio_c_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOD, __gpio_d_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOE, __gpio_e_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOF, __gpio_f_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOG, __gpio_g_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOH, __gpio_h_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOJ, __gpio_j_interrupt, 1);
-#if defined(KB_SCAN_ROW_GPIO) && (KB_SCAN_ROW_GPIO != LM4_GPIO_K)
-DECLARE_IRQ(LM4_IRQ_GPIOK, __gpio_k_interrupt, 1);
-#endif
-DECLARE_IRQ(LM4_IRQ_GPIOL, __gpio_l_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOM, __gpio_m_interrupt, 1);
-#if defined(KB_SCAN_ROW_GPIO) && (KB_SCAN_ROW_GPIO != LM4_GPIO_N)
-DECLARE_IRQ(LM4_IRQ_GPION, __gpio_n_interrupt, 1);
-#endif
-DECLARE_IRQ(LM4_IRQ_GPIOP, __gpio_p_interrupt, 1);
-DECLARE_IRQ(LM4_IRQ_GPIOQ, __gpio_q_interrupt, 1);
diff --git a/chip/lm4/hwtimer.c b/chip/lm4/hwtimer.c
deleted file mode 100644
index 44e1c2fb27..0000000000
--- a/chip/lm4/hwtimer.c
+++ /dev/null
@@ -1,108 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* Hardware timers driver */
-
-#include "clock.h"
-#include "common.h"
-#include "hooks.h"
-#include "hwtimer.h"
-#include "registers.h"
-#include "task.h"
-#include "timer.h"
-
-void __hw_clock_event_set(uint32_t deadline)
-{
- /* set the match on the deadline */
- LM4_TIMER_TAMATCHR(6) = 0xffffffff - deadline;
- /* Set the match interrupt */
- LM4_TIMER_IMR(6) |= 0x10;
-}
-
-uint32_t __hw_clock_event_get(void)
-{
- return 0xffffffff - LM4_TIMER_TAMATCHR(6);
-}
-
-void __hw_clock_event_clear(void)
-{
- /* Disable the match interrupt */
- LM4_TIMER_IMR(6) &= ~0x10;
-}
-
-uint32_t __hw_clock_source_read(void)
-{
- return 0xffffffff - LM4_TIMER_TAV(6);
-}
-
-void __hw_clock_source_set(uint32_t ts)
-{
- LM4_TIMER_TAV(6) = 0xffffffff - ts;
-}
-
-void __hw_clock_source_irq(void)
-{
- uint32_t status = LM4_TIMER_RIS(6);
-
- /* Clear interrupt */
- LM4_TIMER_ICR(6) = status;
-
- /*
- * Find expired timers and set the new timer deadline; check the IRQ
- * status to determine if the free-running counter overflowed.
- */
- process_timers(status & 0x01);
-}
-DECLARE_IRQ(LM4_IRQ_TIMERW0A, __hw_clock_source_irq, 1);
-
-static void update_prescaler(void)
-{
- /*
- * Set the prescaler to increment every microsecond. This takes
- * effect immediately, because the TAILD bit in TAMR is clear.
- */
- LM4_TIMER_TAPR(6) = clock_get_freq() / SECOND;
-}
-DECLARE_HOOK(HOOK_FREQ_CHANGE, update_prescaler, HOOK_PRIO_DEFAULT);
-
-int __hw_clock_source_init(uint32_t start_t)
-{
- /*
- * Use WTIMER0 (timer 6) configured as a free running counter with 1 us
- * period.
- */
-
- /* Enable WTIMER0 clock in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_WTIMER, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- /* Ensure timer is disabled : TAEN = TBEN = 0 */
- LM4_TIMER_CTL(6) &= ~0x101;
- /* Set overflow interrupt */
- LM4_TIMER_IMR(6) = 0x1;
- /* 32-bit timer mode */
- LM4_TIMER_CFG(6) = 4;
-
- /* Set initial prescaler */
- update_prescaler();
-
- /* Periodic mode, counting down */
- LM4_TIMER_TAMR(6) = 0x22;
- /* Use the full 32-bits of the timer */
- LM4_TIMER_TAILR(6) = 0xffffffff;
- /* Starts counting in timer A */
- LM4_TIMER_CTL(6) |= 0x1;
-
- /*
- * Override the count with the start value now that counting has
- * started.
- */
- __hw_clock_source_set(start_t);
-
- /* Enable interrupt */
- task_enable_irq(LM4_IRQ_TIMERW0A);
-
- return LM4_IRQ_TIMERW0A;
-}
diff --git a/chip/lm4/i2c.c b/chip/lm4/i2c.c
deleted file mode 100644
index 56084c38e6..0000000000
--- a/chip/lm4/i2c.c
+++ /dev/null
@@ -1,413 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* I2C port module for Chrome EC */
-
-#include "atomic.h"
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "registers.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-
-#define CPUTS(outstr) cputs(CC_I2C, outstr)
-#define CPRINTS(format, args...) cprints(CC_I2C, format, ## args)
-
-/* Flags for writes to MCS */
-#define LM4_I2C_MCS_RUN BIT(0)
-#define LM4_I2C_MCS_START BIT(1)
-#define LM4_I2C_MCS_STOP BIT(2)
-#define LM4_I2C_MCS_ACK BIT(3)
-#define LM4_I2C_MCS_HS BIT(4)
-#define LM4_I2C_MCS_QCMD BIT(5)
-
-/* Flags for reads from MCS */
-#define LM4_I2C_MCS_BUSY BIT(0)
-#define LM4_I2C_MCS_ERROR BIT(1)
-#define LM4_I2C_MCS_ADRACK BIT(2)
-#define LM4_I2C_MCS_DATACK BIT(3)
-#define LM4_I2C_MCS_ARBLST BIT(4)
-#define LM4_I2C_MCS_IDLE BIT(5)
-#define LM4_I2C_MCS_BUSBSY BIT(6)
-#define LM4_I2C_MCS_CLKTO BIT(7)
-
-/*
- * Minimum delay between resetting the port or sending a stop condition,
- * and when the port can be expected to be back in an idle state (and
- * the peripheral has had long enough to see the start/stop condition
- * edges).
- *
- * 500 us = 50 clocks at 100 KHz bus speed. This has been experimentally
- * determined to be enough.
- */
-#define I2C_IDLE_US 500
-
-/* IRQ for each port */
-static const uint32_t i2c_irqs[] = {LM4_IRQ_I2C0, LM4_IRQ_I2C1, LM4_IRQ_I2C2,
- LM4_IRQ_I2C3, LM4_IRQ_I2C4, LM4_IRQ_I2C5};
-BUILD_ASSERT(ARRAY_SIZE(i2c_irqs) == I2C_PORT_COUNT);
-
-/* I2C port state data */
-struct i2c_port_data {
- const uint8_t *out; /* Output data pointer */
- int out_size; /* Output data to transfer, in bytes */
- uint8_t *in; /* Input data pointer */
- int in_size; /* Input data to transfer, in bytes */
- int flags; /* Flags (I2C_XFER_*) */
- int idx; /* Index into input/output data */
- int err; /* Error code, if any */
- uint32_t timeout_us; /* Transaction timeout, or 0 to use default */
-
- /* Task waiting on port, or TASK_ID_INVALID if none. */
- volatile int task_waiting;
-};
-static struct i2c_port_data pdata[I2C_PORT_COUNT];
-
-int i2c_is_busy(int port)
-{
- return LM4_I2C_MCS(port) & LM4_I2C_MCS_BUSBSY;
-}
-
-/**
- * I2C transfer engine.
- *
- * @return Zero when done with transfer (ready to wake task).
- *
- * MCS sequence on multi-byte write:
- * 0x3 0x1 0x1 ... 0x1 0x5
- * Single byte write:
- * 0x7
- *
- * MCS receive sequence on multi-byte read:
- * 0xb 0x9 0x9 ... 0x9 0x5
- * Single byte read:
- * 0x7
- */
-int i2c_do_work(int port)
-{
- struct i2c_port_data *pd = pdata + port;
- uint32_t reg_mcs = LM4_I2C_MCS_RUN;
-
- if (pd->flags & I2C_XFER_START) {
- /* Set start bit on first byte */
- reg_mcs |= LM4_I2C_MCS_START;
- pd->flags &= ~I2C_XFER_START;
- } else if (LM4_I2C_MCS(port) & (LM4_I2C_MCS_CLKTO | LM4_I2C_MCS_ARBLST |
- LM4_I2C_MCS_ERROR)) {
- /*
- * Error after starting; abort transfer. Ignore errors at
- * start because arbitration and timeout errors are taken care
- * of in chip_i2c_xfer(), and peripheral ack failures will
- * automatically clear once we send a start condition.
- */
- pd->err = EC_ERROR_UNKNOWN;
- return 0;
- }
-
- if (pd->out_size) {
- /* Send next byte of output */
- LM4_I2C_MDR(port) = *(pd->out++);
- pd->idx++;
-
- /* Handle starting to send last byte */
- if (pd->idx == pd->out_size) {
-
- /* Done with output after this */
- pd->out_size = 0;
- pd->idx = 0;
-
- /* Resend start bit when changing direction */
- pd->flags |= I2C_XFER_START;
-
- /*
- * Send stop bit after last byte if the stop flag is
- * on, and caller doesn't expect to receive data.
- */
- if ((pd->flags & I2C_XFER_STOP) && pd->in_size == 0)
- reg_mcs |= LM4_I2C_MCS_STOP;
- }
-
- LM4_I2C_MCS(port) = reg_mcs;
- return 1;
-
- } else if (pd->in_size) {
- if (pd->idx) {
- /* Copy the byte we just read */
- *(pd->in++) = LM4_I2C_MDR(port) & 0xff;
- } else {
- /* Starting receive; switch to receive address */
- LM4_I2C_MSA(port) |= 0x01;
- }
-
- if (pd->idx < pd->in_size) {
- /* More data to read */
- pd->idx++;
-
- /* ACK all bytes except the last one */
- if ((pd->flags & I2C_XFER_STOP) &&
- pd->idx == pd->in_size)
- reg_mcs |= LM4_I2C_MCS_STOP;
- else
- reg_mcs |= LM4_I2C_MCS_ACK;
-
- LM4_I2C_MCS(port) = reg_mcs;
- return 1;
- }
- }
-
- /* If we're still here, done with transfer */
- return 0;
-}
-
-int chip_i2c_xfer(const int port, const uint16_t addr_flags,
- const uint8_t *out, int out_size,
- uint8_t *in, int in_size, int flags)
-{
- struct i2c_port_data *pd = pdata + port;
- uint32_t reg_mcs = LM4_I2C_MCS(port);
- int events = 0;
-
- if (out_size == 0 && in_size == 0)
- return EC_SUCCESS;
-
- /* Copy data to port struct */
- pd->out = out;
- pd->out_size = out_size;
- pd->in = in;
- pd->in_size = in_size;
- pd->flags = flags;
- pd->idx = 0;
- pd->err = 0;
-
- /* Make sure we're in a good state to start */
- if ((flags & I2C_XFER_START) &&
- ((reg_mcs & (LM4_I2C_MCS_CLKTO | LM4_I2C_MCS_ARBLST)) ||
- (i2c_get_line_levels(port) != I2C_LINE_IDLE))) {
- uint32_t tpr = LM4_I2C_MTPR(port);
-
- CPRINTS("I2C%d Addr:%02X bad status 0x%02x, SCL=%d, SDA=%d",
- port,
- I2C_STRIP_FLAGS(addr_flags),
- reg_mcs,
- i2c_get_line_levels(port) & I2C_LINE_SCL_HIGH,
- i2c_get_line_levels(port) & I2C_LINE_SDA_HIGH);
-
- /* Attempt to unwedge the port. */
- i2c_unwedge(port);
-
- /* Clock timeout or arbitration lost. Reset port to clear. */
- atomic_or(LM4_SYSTEM_SRI2C_ADDR, BIT(port));
- clock_wait_cycles(3);
- atomic_clear_bits(LM4_SYSTEM_SRI2C_ADDR, BIT(port));
- clock_wait_cycles(3);
-
- /* Restore settings */
- LM4_I2C_MCR(port) = 0x10;
- LM4_I2C_MTPR(port) = tpr;
-
- /*
- * We don't know what edges the peripheral saw, so sleep
- * long enough that the peripheral will see the new
- * start condition below.
- */
- usleep(I2C_IDLE_US);
- }
-
- /* Set peripheral address for transmit */
- LM4_I2C_MSA(port) = (I2C_STRIP_FLAGS(addr_flags) << 1) & 0xff;
-
- /* Enable interrupts */
- pd->task_waiting = task_get_current();
- LM4_I2C_MICR(port) = 0x03;
- LM4_I2C_MIMR(port) = 0x03;
-
- /* Kick the port interrupt handler to start the transfer */
- task_trigger_irq(i2c_irqs[port]);
-
- /* Wait for transfer complete or timeout */
- events = task_wait_event_mask(TASK_EVENT_I2C_IDLE, pd->timeout_us);
-
- /* Disable interrupts */
- LM4_I2C_MIMR(port) = 0x00;
- pd->task_waiting = TASK_ID_INVALID;
-
- /* Handle timeout */
- if (events & TASK_EVENT_TIMER)
- pd->err = EC_ERROR_TIMEOUT;
-
- if (pd->err) {
- /* Force port back idle */
- LM4_I2C_MCS(port) = LM4_I2C_MCS_STOP;
- usleep(I2C_IDLE_US);
- }
-
- return pd->err;
-}
-
-int i2c_raw_get_scl(int port)
-{
- enum gpio_signal g;
- int ret;
-
- /* If no SCL pin defined for this port, then return 1 to appear idle. */
- if (get_scl_from_i2c_port(port, &g) != EC_SUCCESS)
- return 1;
-
- /* If we are driving the pin low, it must be low. */
- if (gpio_get_level(g) == 0)
- return 0;
-
- /*
- * Otherwise, we need to toggle it to an input to read the true pin
- * state.
- */
- gpio_set_flags(g, GPIO_INPUT);
- ret = gpio_get_level(g);
- gpio_set_flags(g, GPIO_ODR_HIGH);
-
- return ret;
-}
-
-int i2c_raw_get_sda(int port)
-{
- enum gpio_signal g;
- int ret;
-
- /* If no SDA pin defined for this port, then return 1 to appear idle. */
- if (get_sda_from_i2c_port(port, &g) != EC_SUCCESS)
- return 1;
-
- /* If we are driving the pin low, it must be low. */
- if (gpio_get_level(g) == 0)
- return 0;
-
- /*
- * Otherwise, we need to toggle it to an input to read the true pin
- * state.
- */
- gpio_set_flags(g, GPIO_INPUT);
- ret = gpio_get_level(g);
- gpio_set_flags(g, GPIO_ODR_HIGH);
-
- return ret;
-}
-
-int i2c_get_line_levels(int port)
-{
- /* Conveniently, MBMON bit BIT(1) is SDA and BIT(0) is SCL. */
- return LM4_I2C_MBMON(port) & 0x03;
-}
-
-void i2c_set_timeout(int port, uint32_t timeout)
-{
- pdata[port].timeout_us = timeout ? timeout : I2C_TIMEOUT_DEFAULT_US;
-}
-
-/*****************************************************************************/
-/* Hooks */
-
-static void i2c_freq_changed(void)
-{
- int freq = clock_get_freq();
- int i;
-
- for (i = 0; i < i2c_ports_used; i++) {
- /*
- * From datasheet:
- * SCL_PRD = 2 * (1 + TPR) * (SCL_LP + SCL_HP) * CLK_PRD
- *
- * so:
- * TPR = SCL_PRD / (2 * (SCL_LP + SCL_HP) * CLK_PRD) - 1
- *
- * converting from period to frequency:
- * TPR = CLK_FREQ / (SCL_FREQ * 2 * (SCL_LP + SCL_HP)) - 1
- */
- const int d = 2 * (6 + 4) * (i2c_ports[i].kbps * 1000);
-
- /* Round TPR up, so desired kbps is an upper bound */
- const int tpr = (freq + d - 1) / d - 1;
-
-#ifdef PRINT_I2C_SPEEDS
- const int f = freq / (2 * (1 + tpr) * (6 + 4));
- CPRINTS("I2C%d clk=%d tpr=%d freq=%d",
- i2c_ports[i].port, freq, tpr, f);
-#endif
-
- LM4_I2C_MTPR(i2c_ports[i].port) = tpr;
- }
-}
-DECLARE_HOOK(HOOK_FREQ_CHANGE, i2c_freq_changed, HOOK_PRIO_DEFAULT);
-
-void i2c_init(void)
-{
- uint32_t mask = 0;
- int i;
-
- /* Enable I2C modules in run and sleep modes. */
- for (i = 0; i < i2c_ports_used; i++)
- mask |= 1 << i2c_ports[i].port;
-
- clock_enable_peripheral(CGC_OFFSET_I2C, mask,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- /* Configure GPIOs */
- gpio_config_module(MODULE_I2C, 1);
-
- /* Initialize ports as controller, with interrupts enabled */
- for (i = 0; i < i2c_ports_used; i++)
- LM4_I2C_MCR(i2c_ports[i].port) = 0x10;
-
- /* Set initial clock frequency */
- i2c_freq_changed();
-
- /* Enable IRQs; no tasks are waiting on ports */
- for (i = 0; i < I2C_PORT_COUNT; i++) {
- pdata[i].task_waiting = TASK_ID_INVALID;
- task_enable_irq(i2c_irqs[i]);
-
- /* Use default timeout */
- i2c_set_timeout(i, 0);
- }
-}
-
-/**
- * Handle an interrupt on the specified port.
- *
- * @param port I2C port generating interrupt
- */
-static void handle_interrupt(int port)
-{
- int id = pdata[port].task_waiting;
-
- /* Clear the interrupt status */
- LM4_I2C_MICR(port) = LM4_I2C_MMIS(port);
-
- /* If no task is waiting, just return */
- if (id == TASK_ID_INVALID)
- return;
-
- /* If done doing work, wake up the task waiting for the transfer */
- if (!i2c_do_work(port))
- task_set_event(id, TASK_EVENT_I2C_IDLE);
-}
-
-void i2c0_interrupt(void) { handle_interrupt(0); }
-void i2c1_interrupt(void) { handle_interrupt(1); }
-void i2c2_interrupt(void) { handle_interrupt(2); }
-void i2c3_interrupt(void) { handle_interrupt(3); }
-void i2c4_interrupt(void) { handle_interrupt(4); }
-void i2c5_interrupt(void) { handle_interrupt(5); }
-
-DECLARE_IRQ(LM4_IRQ_I2C0, i2c0_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_I2C1, i2c1_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_I2C2, i2c2_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_I2C3, i2c3_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_I2C4, i2c4_interrupt, 2);
-DECLARE_IRQ(LM4_IRQ_I2C5, i2c5_interrupt, 2);
diff --git a/chip/lm4/keyboard_raw.c b/chip/lm4/keyboard_raw.c
deleted file mode 100644
index 81af0efdde..0000000000
--- a/chip/lm4/keyboard_raw.c
+++ /dev/null
@@ -1,119 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* Functions needed by keyboard scanner module for Chrome EC */
-
-#include "common.h"
-#include "keyboard_raw.h"
-#include "keyboard_scan.h"
-#include "registers.h"
-#include "task.h"
-
-void keyboard_raw_init(void)
-{
- /* Ensure top-level interrupt is disabled */
- keyboard_raw_enable_interrupt(0);
-
- /*
- * Set column outputs as open-drain; we either pull them low or let
- * them float high.
- */
- LM4_GPIO_AFSEL(LM4_GPIO_P) = 0; /* KSO[7:0] */
- LM4_GPIO_AFSEL(LM4_GPIO_Q) &= ~0x1f; /* KSO[12:8] */
- LM4_GPIO_DEN(LM4_GPIO_P) = 0xff;
- LM4_GPIO_DEN(LM4_GPIO_Q) |= 0x1f;
- LM4_GPIO_DIR(LM4_GPIO_P) = 0xff;
- LM4_GPIO_DIR(LM4_GPIO_Q) |= 0x1f;
- LM4_GPIO_ODR(LM4_GPIO_P) = 0xff;
- LM4_GPIO_ODR(LM4_GPIO_Q) |= 0x1f;
-
-#ifdef CONFIG_KEYBOARD_COL2_INVERTED
- /*
- * When column 2 is inverted, the Silego has a pulldown instead of a
- * pullup. So drive it push-pull instead of open-drain.
- */
- LM4_GPIO_ODR(LM4_GPIO_P) &= ~BIT(2);
-#endif
-
- /* Set row inputs with pull-up */
- LM4_GPIO_AFSEL(KB_SCAN_ROW_GPIO) &= 0xff;
- LM4_GPIO_DEN(KB_SCAN_ROW_GPIO) |= 0xff;
- LM4_GPIO_DIR(KB_SCAN_ROW_GPIO) = 0;
- LM4_GPIO_PUR(KB_SCAN_ROW_GPIO) = 0xff;
-
- /* Edge-sensitive on both edges. */
- LM4_GPIO_IS(KB_SCAN_ROW_GPIO) = 0;
- LM4_GPIO_IBE(KB_SCAN_ROW_GPIO) = 0xff;
-
- /*
- * Enable interrupts for the inputs. The top-level interrupt is still
- * masked off, so this won't trigger interrupts yet.
- */
- LM4_GPIO_IM(KB_SCAN_ROW_GPIO) = 0xff;
-}
-
-void keyboard_raw_task_start(void)
-{
- task_enable_irq(KB_SCAN_ROW_IRQ);
-}
-
-test_mockable void keyboard_raw_drive_column(int col)
-{
- int mask;
-
- if (col == KEYBOARD_COLUMN_NONE)
- mask = 0x1fff; /* Tri-state all outputs */
- else if (col == KEYBOARD_COLUMN_ALL)
- mask = 0; /* Assert all outputs */
- else
- mask = 0x1fff ^ BIT(col); /* Assert a single output */
-
-#ifdef CONFIG_KEYBOARD_COL2_INVERTED
- /* Invert column 2 output */
- mask ^= BIT(2);
-#endif
-
- LM4_GPIO_DATA(LM4_GPIO_P, 0xff) = mask & 0xff;
- LM4_GPIO_DATA(LM4_GPIO_Q, 0x1f) = (mask >> 8) & 0x1f;
-}
-
-test_mockable int keyboard_raw_read_rows(void)
-{
- /* Bits are active-low, so invert returned levels */
- return LM4_GPIO_DATA(KB_SCAN_ROW_GPIO, 0xff) ^ 0xff;
-}
-
-void keyboard_raw_enable_interrupt(int enable)
-{
- if (enable) {
- /*
- * Clear pending interrupts before enabling them, because the
- * raw interrupt status may have been tripped by keyboard
- * scanning or, if a key is already pressed, by driving all the
- * outputs.
- *
- * We won't lose keyboard events because the scanning task will
- * explicitly check the raw row state before waiting for an
- * interrupt. If a key is pressed, the task won't wait.
- */
- LM4_GPIO_ICR(KB_SCAN_ROW_GPIO) = 0xff;
- LM4_GPIO_IM(KB_SCAN_ROW_GPIO) = 0xff;
- } else {
- LM4_GPIO_IM(KB_SCAN_ROW_GPIO) = 0;
- }
-}
-
-/**
- * Interrupt handler for the entire GPIO bank of keyboard rows.
- */
-void keyboard_raw_interrupt(void)
-{
- /* Clear all pending keyboard interrupts */
- LM4_GPIO_ICR(KB_SCAN_ROW_GPIO) = 0xff;
-
- /* Wake the scan task */
- task_wake(TASK_ID_KEYSCAN);
-}
-DECLARE_IRQ(KB_SCAN_ROW_IRQ, keyboard_raw_interrupt, 3);
diff --git a/chip/lm4/lpc.c b/chip/lm4/lpc.c
deleted file mode 100644
index 6e3c39220d..0000000000
--- a/chip/lm4/lpc.c
+++ /dev/null
@@ -1,835 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* LPC module for Chrome EC */
-
-#include "acpi.h"
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "host_command.h"
-#include "keyboard_protocol.h"
-#include "lpc.h"
-#include "port80.h"
-#include "pwm.h"
-#include "registers.h"
-#include "system.h"
-#include "task.h"
-#include "timer.h"
-#include "uart.h"
-#include "util.h"
-
-/* LPC channels */
-#define LPC_CH_ACPI 0 /* ACPI commands */
-#define LPC_CH_PORT80 1 /* Port 80 debug output */
-#define LPC_CH_CMD_DATA 2 /* Data for host commands (args/params/response) */
-#define LPC_CH_KEYBOARD 3 /* 8042 keyboard emulation */
-#define LPC_CH_CMD 4 /* Host commands */
-#define LPC_CH_MEMMAP 5 /* Memory-mapped data */
-#define LPC_CH_COMX 7 /* UART emulation */
-/* LPC pool offsets */
-#define LPC_POOL_OFFS_ACPI 0 /* ACPI commands - 0=in, 1=out */
-#define LPC_POOL_OFFS_PORT80 4 /* Port 80 - 4=in, 5=out */
-#define LPC_POOL_OFFS_COMX 8 /* UART emulation range - 8-15 */
-#define LPC_POOL_OFFS_KEYBOARD 16 /* Keyboard - 16=in, 17=out */
-#define LPC_POOL_OFFS_CMD 20 /* Host commands - 20=in, 21=out */
-#define LPC_POOL_OFFS_CMD_DATA 512 /* Data range for host commands - 512-767 */
-#define LPC_POOL_OFFS_MEMMAP 768 /* Memory-mapped data - 768-1023 */
-/* LPC pool data pointers */
-#define LPC_POOL_ACPI (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_ACPI)
-#define LPC_POOL_PORT80 (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_PORT80)
-#define LPC_POOL_COMX (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_COMX)
-#define LPC_POOL_KEYBOARD (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_KEYBOARD)
-#define LPC_POOL_CMD (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_CMD)
-#define LPC_POOL_CMD_DATA (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_CMD_DATA)
-#define LPC_POOL_MEMMAP (LM4_LPC_LPCPOOL + LPC_POOL_OFFS_MEMMAP)
-/* LPC COMx I/O address (in x86 I/O address space) */
-#define LPC_COMX_ADDR 0x3f8 /* COM1 */
-
-/* Console output macros */
-#define CPUTS(outstr) cputs(CC_LPC, outstr)
-#define CPRINTS(format, args...) cprints(CC_LPC, format, ## args)
-
-static struct host_packet lpc_packet;
-static struct host_cmd_handler_args host_cmd_args;
-static uint8_t host_cmd_flags; /* Flags from host command */
-
-/* Params must be 32-bit aligned */
-static uint8_t params_copy[EC_LPC_HOST_PACKET_SIZE] __aligned(4);
-static int init_done;
-
-static uint8_t * const cmd_params = (uint8_t *)LPC_POOL_CMD_DATA +
- EC_LPC_ADDR_HOST_PARAM - EC_LPC_ADDR_HOST_ARGS;
-static struct ec_lpc_host_args * const lpc_host_args =
- (struct ec_lpc_host_args *)LPC_POOL_CMD_DATA;
-
-static void wait_irq_sent(void)
-{
- /*
- * A hard-coded delay here isn't very elegant, but it's the best we can
- * manage (and it's a short delay, so it's not that horrible). We need
- * this because SIRQRIS isn't cleared in continuous mode, and the EC
- * has trouble sending more than 1 frame in quiet mode. Waiting 4 us =
- * 2 SERIRQ frames ensures the IRQ has been sent out.
- */
- udelay(4);
-}
-
-#ifdef CONFIG_KEYBOARD_IRQ_GPIO
-static void keyboard_irq_assert(void)
-{
- /*
- * Enforce signal-high for long enough for the signal to be pulled high
- * by the external pullup resistor. This ensures the host will see the
- * following falling edge, regardless of the line state before this
- * function call.
- */
- uint64_t tstop = get_time().val + MSEC;
- gpio_set_level(CONFIG_KEYBOARD_IRQ_GPIO, 1);
- udelay(4);
- /* Generate a falling edge */
- gpio_set_level(CONFIG_KEYBOARD_IRQ_GPIO, 0);
- /* Wait for host senses the interrupt and gets the char. */
- do {
- if (get_time().val > tstop)
- break;
- } while (lpc_keyboard_has_char());
- /* Set signal high, now that we've generated the edge */
- gpio_set_level(CONFIG_KEYBOARD_IRQ_GPIO, 1);
-}
-#else
-static void wait_send_serirq(uint32_t lpcirqctl)
-{
- LM4_LPC_LPCIRQCTL = lpcirqctl;
- wait_irq_sent();
-}
-
-/**
- * Manually generate an IRQ to host (edge-trigger).
- *
- * @param irq_num IRQ number to generate. Pass 0 to set the AH
- * (active high) bit.
- *
- * For SERIRQ quite mode, we need to set LM4_LPC_LPCIRQCTL twice.
- * The first one is to assert IRQ (pull low), and then the second one is
- * to de-assert it. This generates a pulse (high-low-high) for an IRQ.
- */
-static void lpc_manual_irq(int irq_num)
-{
- uint32_t common_bits =
- 0x00000004 | /* PULSE */
- 0x00000002 | /* ONCHG - for quiet mode */
- 0x00000001; /* SND - send immediately */
-
- /* Send out the IRQ first. */
- wait_send_serirq((1 << (irq_num + 16)) | common_bits);
-
- /* Generate a all-high frame to simulate a rising edge. */
- wait_send_serirq(common_bits);
-}
-
-static inline void keyboard_irq_assert(void)
-{
- /* Use serirq method. */
- lpc_manual_irq(1); /* IRQ#1 */
-}
-#endif
-
-/**
- * Generate SMI pulse to the host chipset via GPIO.
- *
- * If the x86 is in S0, SMI# is sampled at 33MHz, so minimum pulse length is
- * 60ns. If the x86 is in S3, SMI# is sampled at 32.768KHz, so we need pulse
- * length >61us. Both are short enough and events are infrequent, so just
- * delay for 65us.
- */
-static void lpc_generate_smi(void)
-{
- host_event_t smi;
-
- /* Enforce signal-high for long enough to debounce high */
- gpio_set_level(GPIO_PCH_SMI_L, 1);
- udelay(65);
- /* Generate a falling edge */
- gpio_set_level(GPIO_PCH_SMI_L, 0);
- udelay(65);
- /* Set signal high, now that we've generated the edge */
- gpio_set_level(GPIO_PCH_SMI_L, 1);
-
- smi = lpc_get_host_events_by_type(LPC_HOST_EVENT_SMI);
- if (smi)
- HOST_EVENT_CPRINTS("smi", smi);
-}
-
-/**
- * Generate SCI pulse to the host chipset via LPC0SCI.
- */
-static void lpc_generate_sci(void)
-{
- host_event_t sci;
-
-#ifdef CONFIG_SCI_GPIO
- /* Enforce signal-high for long enough to debounce high */
- gpio_set_level(CONFIG_SCI_GPIO, 1);
- udelay(65);
- /* Generate a falling edge */
- gpio_set_level(CONFIG_SCI_GPIO, 0);
- udelay(65);
- /* Set signal high, now that we've generated the edge */
- gpio_set_level(CONFIG_SCI_GPIO, 1);
-#else
- LM4_LPC_LPCCTL |= LM4_LPC_SCI_START;
-#endif
-
- sci = lpc_get_host_events_by_type(LPC_HOST_EVENT_SCI);
- if (sci)
- HOST_EVENT_CPRINTS("sci", sci);
-}
-
-/**
- * Update the level-sensitive wake signal to the AP.
- *
- * @param wake_events Currently asserted wake events
- */
-static void lpc_update_wake(uint64_t wake_events)
-{
- /*
- * Mask off power button event, since the AP gets that through a
- * separate dedicated GPIO.
- */
- wake_events &= ~EC_HOST_EVENT_MASK(EC_HOST_EVENT_POWER_BUTTON);
-
- /* Signal is asserted low when wake events is non-zero */
- gpio_set_level(GPIO_PCH_WAKE_L, !wake_events);
-}
-
-uint8_t *lpc_get_memmap_range(void)
-{
- return (uint8_t *)LPC_POOL_MEMMAP;
-}
-
-static void lpc_send_response(struct host_cmd_handler_args *args)
-{
- uint8_t *out;
- int size = args->response_size;
- int csum;
- int i;
-
- /* Ignore in-progress on LPC since interface is synchronous anyway */
- if (args->result == EC_RES_IN_PROGRESS)
- return;
-
- /* Handle negative size */
- if (size < 0) {
- args->result = EC_RES_INVALID_RESPONSE;
- size = 0;
- }
-
- /* New-style response */
- lpc_host_args->flags =
- (host_cmd_flags & ~EC_HOST_ARGS_FLAG_FROM_HOST) |
- EC_HOST_ARGS_FLAG_TO_HOST;
-
- lpc_host_args->data_size = size;
-
- csum = args->command + lpc_host_args->flags +
- lpc_host_args->command_version +
- lpc_host_args->data_size;
-
- for (i = 0, out = (uint8_t *)args->response; i < size; i++, out++)
- csum += *out;
-
- lpc_host_args->checksum = (uint8_t)csum;
-
- /* Fail if response doesn't fit in the param buffer */
- if (size > EC_PROTO2_MAX_PARAM_SIZE)
- args->result = EC_RES_INVALID_RESPONSE;
-
- /* Write result to the data byte. This sets the TOH status bit. */
- LPC_POOL_CMD[1] = args->result;
-
- /* Clear the busy bit, so the host knows the EC is done. */
- task_disable_irq(LM4_IRQ_LPC);
- LM4_LPC_ST(LPC_CH_CMD) &= ~LM4_LPC_ST_BUSY;
- task_enable_irq(LM4_IRQ_LPC);
-}
-
-static void lpc_send_response_packet(struct host_packet *pkt)
-{
- /* Ignore in-progress on LPC since interface is synchronous anyway */
- if (pkt->driver_result == EC_RES_IN_PROGRESS)
- return;
-
- /* Write result to the data byte. This sets the TOH status bit. */
- LPC_POOL_CMD[1] = pkt->driver_result;
-
- /* Clear the busy bit, so the host knows the EC is done. */
- task_disable_irq(LM4_IRQ_LPC);
- LM4_LPC_ST(LPC_CH_CMD) &= ~LM4_LPC_ST_BUSY;
- task_enable_irq(LM4_IRQ_LPC);
-}
-
-int lpc_keyboard_has_char(void)
-{
- return (LM4_LPC_ST(LPC_CH_KEYBOARD) & LM4_LPC_ST_TOH) ? 1 : 0;
-}
-
-/* Return true if the FRMH is set */
-int lpc_keyboard_input_pending(void)
-{
- return (LM4_LPC_ST(LPC_CH_KEYBOARD) & LM4_LPC_ST_FRMH) ? 1 : 0;
-}
-
-/* Put a char to host buffer and send IRQ if specified. */
-void lpc_keyboard_put_char(uint8_t chr, int send_irq)
-{
- LPC_POOL_KEYBOARD[1] = chr;
- if (send_irq)
- keyboard_irq_assert();
-}
-
-void lpc_keyboard_clear_buffer(void)
-{
- /* Make sure the previous TOH and IRQ has been sent out. */
- wait_irq_sent();
-
- LM4_LPC_ST(LPC_CH_KEYBOARD) &= ~LM4_LPC_ST_TOH;
-
- /* Ensure there is no TOH set in this period. */
- wait_irq_sent();
-}
-
-void lpc_keyboard_resume_irq(void)
-{
- if (lpc_keyboard_has_char())
- keyboard_irq_assert();
-}
-
-#ifdef CONFIG_UART_HOST
-
-int lpc_comx_has_char(void)
-{
- return LM4_LPC_ST(LPC_CH_COMX) & LM4_LPC_ST_FRMH;
-}
-
-int lpc_comx_get_char(void)
-{
- return LPC_POOL_COMX[0];
-}
-
-void lpc_comx_put_char(int c)
-{
- LPC_POOL_COMX[1] = c;
-
- /*
- * We could in theory manually trigger an IRQ, like we do for the 8042
- * keyboard interface, but neither the kernel nor BIOS seems to require
- * this.
- */
-}
-
-#endif /* CONFIG_UART_HOST */
-
-/**
- * Update the host event status.
- *
- * Sends a pulse if masked event status becomes non-zero:
- * - SMI pulse via EC_SMI_L GPIO
- * - SCI pulse via LPC0SCI
- */
-void lpc_update_host_event_status(void)
-{
- int need_sci = 0;
- int need_smi = 0;
-
- if (!init_done)
- return;
-
- /* Disable LPC interrupt while updating status register */
- task_disable_irq(LM4_IRQ_LPC);
-
- if (lpc_get_host_events_by_type(LPC_HOST_EVENT_SMI)) {
- /* Only generate SMI for first event */
- if (!(LM4_LPC_ST(LPC_CH_ACPI) & LM4_LPC_ST_SMI))
- need_smi = 1;
- LM4_LPC_ST(LPC_CH_ACPI) |= LM4_LPC_ST_SMI;
- } else
- LM4_LPC_ST(LPC_CH_ACPI) &= ~LM4_LPC_ST_SMI;
-
- if (lpc_get_host_events_by_type(LPC_HOST_EVENT_SCI)) {
- /* Generate SCI for every event */
- need_sci = 1;
- LM4_LPC_ST(LPC_CH_ACPI) |= LM4_LPC_ST_SCI;
- } else
- LM4_LPC_ST(LPC_CH_ACPI) &= ~LM4_LPC_ST_SCI;
-
- /* Copy host events to mapped memory */
- *(host_event_t *)host_get_memmap(EC_MEMMAP_HOST_EVENTS) =
- lpc_get_host_events();
-
- task_enable_irq(LM4_IRQ_LPC);
-
- /* Process the wake events. */
- lpc_update_wake(lpc_get_host_events_by_type(LPC_HOST_EVENT_WAKE));
-
- /* Send pulse on SMI signal if needed */
- if (need_smi)
- lpc_generate_smi();
-
- /* ACPI 5.0-12.6.1: Generate SCI for SCI_EVT=1. */
- if (need_sci)
- lpc_generate_sci();
-}
-
-void lpc_set_acpi_status_mask(uint8_t mask)
-{
- uint32_t set_mask = 0;
- if (mask & EC_LPC_STATUS_BURST_MODE)
- set_mask |= LM4_LPC_ST_BURST;
-
- LM4_LPC_ST(LPC_CH_ACPI) |= set_mask;
-}
-
-void lpc_clear_acpi_status_mask(uint8_t mask)
-{
- uint32_t clear_mask = 0;
- if (mask & EC_LPC_STATUS_BURST_MODE)
- clear_mask |= LM4_LPC_ST_BURST;
-
- LM4_LPC_ST(LPC_CH_ACPI) &= ~clear_mask;
-}
-
-int lpc_get_pltrst_asserted(void)
-{
- return (LM4_LPC_LPCSTS & BIT(10)) ? 1 : 0;
-}
-
-/**
- * Handle write to ACPI I/O port
- *
- * @param is_cmd Is write command (is_cmd=1) or data (is_cmd=0)
- */
-static void handle_acpi_write(int is_cmd)
-{
- uint8_t value, result;
-
- /* Set the busy bit */
- LM4_LPC_ST(LPC_CH_ACPI) |= LM4_LPC_ST_BUSY;
-
- /* Read command/data; this clears the FRMH status bit. */
- value = LPC_POOL_ACPI[0];
-
- /* Handle whatever this was. */
- if (acpi_ap_to_ec(is_cmd, value, &result))
- LPC_POOL_ACPI[1] = result;
-
- /* Clear the busy bit */
- LM4_LPC_ST(LPC_CH_ACPI) &= ~LM4_LPC_ST_BUSY;
-
- /*
- * ACPI 5.0-12.6.1: Generate SCI for Input Buffer Empty / Output Buffer
- * Full condition on the kernel channel.
- */
- lpc_generate_sci();
-}
-
-/**
- * Handle write to host command I/O ports.
- *
- * @param is_cmd Is write command (1) or data (0)?
- */
-static void handle_host_write(int is_cmd)
-{
- /* Ignore data writes or overlapping commands from host */
- uint32_t is_overlapping = LM4_LPC_ST(LPC_CH_CMD) & LM4_LPC_ST_BUSY;
- if (!is_cmd || is_overlapping) {
- if (is_overlapping)
- CPRINTS("LPC Ignoring overlapping HC");
- LM4_LPC_ST(LPC_CH_CMD) &= ~LM4_LPC_ST_FRMH;
- return;
- }
-
- /* Set the busy bit */
- LM4_LPC_ST(LPC_CH_CMD) |= LM4_LPC_ST_BUSY;
-
- /*
- * Read the command byte. This clears the FRMH bit in
- * the status byte.
- */
- host_cmd_args.command = LPC_POOL_CMD[0];
-
- host_cmd_args.result = EC_RES_SUCCESS;
- host_cmd_args.send_response = lpc_send_response;
- host_cmd_flags = lpc_host_args->flags;
-
- /* See if we have an old or new style command */
- if (host_cmd_args.command == EC_COMMAND_PROTOCOL_3) {
- lpc_packet.send_response = lpc_send_response_packet;
-
- lpc_packet.request = (const void *)LPC_POOL_CMD_DATA;
- lpc_packet.request_temp = params_copy;
- lpc_packet.request_max = sizeof(params_copy);
- /* Don't know the request size so pass in the entire buffer */
- lpc_packet.request_size = EC_LPC_HOST_PACKET_SIZE;
-
- lpc_packet.response = (void *)LPC_POOL_CMD_DATA;
- lpc_packet.response_max = EC_LPC_HOST_PACKET_SIZE;
- lpc_packet.response_size = 0;
-
- lpc_packet.driver_result = EC_RES_SUCCESS;
- host_packet_receive(&lpc_packet);
- return;
-
- } else if (host_cmd_flags & EC_HOST_ARGS_FLAG_FROM_HOST) {
- /* Version 2 (link) style command */
- int size = lpc_host_args->data_size;
- int csum, i;
-
- host_cmd_args.version = lpc_host_args->command_version;
- host_cmd_args.params = params_copy;
- host_cmd_args.params_size = size;
- host_cmd_args.response = cmd_params;
- host_cmd_args.response_max = EC_PROTO2_MAX_PARAM_SIZE;
- host_cmd_args.response_size = 0;
-
- /* Verify params size */
- if (size > EC_PROTO2_MAX_PARAM_SIZE) {
- host_cmd_args.result = EC_RES_INVALID_PARAM;
- } else {
- const uint8_t *src = cmd_params;
- uint8_t *copy = params_copy;
-
- /*
- * Verify checksum and copy params out of LPC space.
- * This ensures the data acted on by the host command
- * handler can't be changed by host writes after the
- * checksum is verified.
- */
- csum = host_cmd_args.command +
- host_cmd_flags +
- host_cmd_args.version +
- host_cmd_args.params_size;
-
- for (i = 0; i < size; i++) {
- csum += *src;
- *(copy++) = *(src++);
- }
-
- if ((uint8_t)csum != lpc_host_args->checksum)
- host_cmd_args.result = EC_RES_INVALID_CHECKSUM;
- }
- } else {
- /* Old style command, now unsupported */
- host_cmd_args.result = EC_RES_INVALID_COMMAND;
- }
-
- /* Hand off to host command handler */
- host_command_received(&host_cmd_args);
-}
-
-#ifdef CONFIG_CHIPSET_RESET_HOOK
-static void lpc_chipset_reset(void)
-{
- hook_notify(HOOK_CHIPSET_RESET);
-}
-DECLARE_DEFERRED(lpc_chipset_reset);
-#endif
-
-/**
- * LPC interrupt handler
- */
-void lpc_interrupt(void)
-{
- uint32_t mis = LM4_LPC_LPCMIS;
- uint32_t st;
-
- /* Clear the interrupt bits we're handling */
- LM4_LPC_LPCIC = mis;
-
-#ifdef HAS_TASK_HOSTCMD
- /* Handle ACPI command and data writes */
- st = LM4_LPC_ST(LPC_CH_ACPI);
- if (st & LM4_LPC_ST_FRMH)
- handle_acpi_write(st & LM4_LPC_ST_CMD);
-
- /* Handle user command writes */
- st = LM4_LPC_ST(LPC_CH_CMD);
- if (st & LM4_LPC_ST_FRMH)
- handle_host_write(st & LM4_LPC_ST_CMD);
-#endif
-
- /*
- * Handle port 80 writes (CH0MIS1). Due to crosbug.com/p/12349 the
- * interrupt status (mis & LM4_LPC_INT_MASK(LPC_CH_PORT80, 2))
- * apparently gets lost on back-to-back writes to port 80, so check the
- * FRMH bit in the channel status register to see if a write is
- * pending. Loop to handle bursts of back-to-back writes.
- */
- while (LM4_LPC_ST(LPC_CH_PORT80) & LM4_LPC_ST_FRMH)
- port_80_write(LPC_POOL_PORT80[0]);
-
-#ifdef HAS_TASK_KEYPROTO
- /* Handle keyboard interface writes */
- st = LM4_LPC_ST(LPC_CH_KEYBOARD);
- if (st & LM4_LPC_ST_FRMH)
- keyboard_host_write(LPC_POOL_KEYBOARD[0], st & LM4_LPC_ST_CMD);
-
- if (mis & LM4_LPC_INT_MASK(LPC_CH_KEYBOARD, 1)) {
- /* Host read data; wake up task to send remaining bytes */
- task_wake(TASK_ID_KEYPROTO);
- }
-#endif
-
-#ifdef CONFIG_UART_HOST
- /* Handle COMx */
- if (lpc_comx_has_char()) {
- /* Copy a character to the UART if there's space */
- if (uart_comx_putc_ok())
- uart_comx_putc(lpc_comx_get_char());
- }
-#endif
-
- /* Debugging: print changes to LPC0RESET */
- if (mis & BIT(31)) {
- if (LM4_LPC_LPCSTS & BIT(10)) {
- int i;
-
- /* Store port 80 reset event */
- port_80_write(PORT_80_EVENT_RESET);
-
- /*
- * Workaround for crosbug.com/p/12349; clear all FRMH
- * bits so host writes will trigger interrupts.
- */
- for (i = 0; i < 8; i++)
- LM4_LPC_ST(i) &= ~LM4_LPC_ST_FRMH;
-
-#ifdef CONFIG_CHIPSET_RESET_HOOK
- /* Notify HOOK_CHIPSET_RESET */
- hook_call_deferred(&lpc_chipset_reset_data, MSEC);
-#endif
- }
-
- CPRINTS("LPC RESET# %sasserted",
- lpc_get_pltrst_asserted() ? "" : "de");
- }
-}
-DECLARE_IRQ(LM4_IRQ_LPC, lpc_interrupt, 2);
-
-/* Enable LPC ACPI-EC interrupts */
-void lpc_enable_acpi_interrupts(void)
-{
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_ACPI, 6);
-}
-
-/* Disable LPC ACPI-EC interrupts */
-void lpc_disable_acpi_interrupts(void)
-{
- LM4_LPC_LPCIM &= ~(LM4_LPC_INT_MASK(LPC_CH_ACPI, 6));
-}
-
-static void lpc_init(void)
-{
- /* Enable LPC clock in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_LPC, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- LM4_LPC_LPCIM = 0;
- LM4_LPC_LPCCTL = 0;
- LM4_LPC_LPCIRQCTL = 0;
-
- /* Configure GPIOs */
- gpio_config_module(MODULE_LPC, 1);
-
- /*
- * Set LPC channel 0 to I/O address 0x62 (data) / 0x66 (command),
- * single endpoint, offset 0 for host command/writes and 1 for EC
- * data writes, pool bytes 0(data)/1(cmd)
- */
- LM4_LPC_ADR(LPC_CH_ACPI) = EC_LPC_ADDR_ACPI_DATA;
- LM4_LPC_CTL(LPC_CH_ACPI) = (LPC_POOL_OFFS_ACPI << (5 - 1));
- LM4_LPC_ST(LPC_CH_ACPI) = 0;
- /* Unmask interrupt for host command and data writes */
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_ACPI, 6);
-
- /*
- * Set LPC channel 1 to I/O address 0x80 (data), single endpoint,
- * pool bytes 4(data)/5(cmd).
- */
- LM4_LPC_ADR(LPC_CH_PORT80) = 0x80;
- LM4_LPC_CTL(LPC_CH_PORT80) = (LPC_POOL_OFFS_PORT80 << (5 - 1));
- /* Unmask interrupt for host data writes */
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_PORT80, 2);
-
- /*
- * Set LPC channel 2 to I/O address 0x880, range endpoint,
- * arbitration disabled, pool bytes 512-639. To access this from
- * x86, use the following command to set GEN_LPC2:
- *
- * pci_write32 0 0x1f 0 0x88 0x007c0801
- */
- LM4_LPC_ADR(LPC_CH_CMD_DATA) = EC_LPC_ADDR_HOST_ARGS;
- LM4_LPC_CTL(LPC_CH_CMD_DATA) = 0x8019 |
- (LPC_POOL_OFFS_CMD_DATA << (5 - 1));
-
- /*
- * Set LPC channel 3 to I/O address 0x60 (data) / 0x64 (command),
- * single endpoint, offset 0 for host command/writes and 1 for EC
- * data writes, pool bytes 0(data)/1(cmd)
- */
- LM4_LPC_ADR(LPC_CH_KEYBOARD) = 0x60;
- LM4_LPC_CTL(LPC_CH_KEYBOARD) = (BIT(24)/* IRQSEL1 */) |
- (0 << 18/* IRQEN1 */) | (LPC_POOL_OFFS_KEYBOARD << (5 - 1));
- LM4_LPC_ST(LPC_CH_KEYBOARD) = 0;
- /* Unmask interrupt for host command/data writes and data reads */
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_KEYBOARD, 7);
-
- /*
- * Set LPC channel 4 to I/O address 0x200 (data) / 0x204 (command),
- * single endpoint, offset 0 for host command/writes and 1 for EC
- * data writes, pool bytes 0(data)/1(cmd)
- */
- LM4_LPC_ADR(LPC_CH_CMD) = EC_LPC_ADDR_HOST_DATA;
- LM4_LPC_CTL(LPC_CH_CMD) = (LPC_POOL_OFFS_CMD << (5 - 1));
- /*
- * Initialize status bits to 0. We never set the ACPI burst status bit,
- * so this guarantees that at least one status bit will always be 0.
- * This is used by comm_lpc.c to detect that the EC is present on the
- * LPC bus. See crosbug.com/p/10963.
- */
- LM4_LPC_ST(LPC_CH_CMD) = 0;
- /* Unmask interrupt for host command writes */
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_CMD, 4);
-
- /*
- * Set LPC channel 5 to I/O address 0x900, range endpoint,
- * arbitration enabled, pool bytes 768-1023. To access this from
- * x86, use the following command to set GEN_LPC3:
- *
- * pci_write32 0 0x1f 0 0x8c 0x007c0901
- */
- LM4_LPC_ADR(LPC_CH_MEMMAP) = EC_LPC_ADDR_MEMMAP;
- LM4_LPC_CTL(LPC_CH_MEMMAP) = 0x0019 | (LPC_POOL_OFFS_MEMMAP << (5 - 1));
-
-#ifdef CONFIG_UART_HOST
- /*
- * Set LPC channel 7 to COM port I/O address. Note that channel 7
- * ignores the TYPE bit and is always an 8-byte range.
- */
- LM4_LPC_ADR(LPC_CH_COMX) = LPC_COMX_ADDR;
- /*
- * In theory we could configure IRQSELs and set IRQEN2/CX, and then the
- * host could enable IRQs on its own. So far that hasn't been
- * necessary, and due to the issues with IRQs (see wait_irq_sent()
- * above) it might not work anyway.
- */
- LM4_LPC_CTL(LPC_CH_COMX) = 0x0004 | (LPC_POOL_OFFS_COMX << (5 - 1));
- /* Enable COMx emulation for reads and writes. */
- LM4_LPC_LPCDMACX = 0x00310000;
- /*
- * Unmask interrupt for host data writes. We don't need interrupts for
- * reads, because there's no flow control in that direction; LPC is
- * much faster than the UART, and the UART doesn't have anywhere
- * sensible to buffer input anyway.
- */
- LM4_LPC_LPCIM |= LM4_LPC_INT_MASK(LPC_CH_COMX, 2);
-#endif /* CONFIG_UART_HOST */
-
- /*
- * Unmask LPC bus reset interrupt. This lets us monitor the PCH
- * PLTRST# signal for debugging.
- */
- LM4_LPC_LPCIM |= BIT(31);
-
- /* Enable LPC channels */
- LM4_LPC_LPCCTL = LM4_LPC_SCI_CLK_1 |
- BIT(LPC_CH_ACPI) |
- BIT(LPC_CH_PORT80) |
- BIT(LPC_CH_CMD_DATA) |
- BIT(LPC_CH_KEYBOARD) |
- BIT(LPC_CH_CMD) |
- BIT(LPC_CH_MEMMAP);
-
-#ifdef CONFIG_UART_HOST
- LM4_LPC_LPCCTL |= 1 << LPC_CH_COMX;
-#endif
-
- /*
- * Ensure the EC (peripheral) has control of the memory-mapped
- * I/O space. Once the EC has won arbitration for the
- * memory-mapped space, it will keep control of it until it
- * writes the last byte in the space. (That never happens; we
- * can't use the last byte in the space because ACPI can't see
- * it anyway.)
- */
- while (!(LM4_LPC_ST(LPC_CH_MEMMAP) & 0x10)) {
- /* Clear HW1ST */
- LM4_LPC_ST(LPC_CH_MEMMAP) &= ~0x40;
- /* Do a peripheral write; this should cause SW1ST to be set */
- *LPC_POOL_MEMMAP = *LPC_POOL_MEMMAP;
- }
-
- /* Initialize host args and memory map to all zero */
- memset(lpc_host_args, 0, sizeof(*lpc_host_args));
- memset(lpc_get_memmap_range(), 0, EC_MEMMAP_SIZE);
-
- /* We support LPC args and version 3 protocol */
- *(lpc_get_memmap_range() + EC_MEMMAP_HOST_CMD_FLAGS) =
- EC_HOST_CMD_FLAG_LPC_ARGS_SUPPORTED |
- EC_HOST_CMD_FLAG_VERSION_3;
-
- /* Enable LPC interrupt */
- task_enable_irq(LM4_IRQ_LPC);
-
-#ifdef CONFIG_UART_HOST
- /* Enable COMx UART */
- uart_comx_enable();
-#endif
-
- /* Sufficiently initialized */
- init_done = 1;
-
- /* Update host events now that we can copy them to memmap */
- lpc_update_host_event_status();
-}
-/*
- * Set prio to higher than default; this way LPC memory mapped data is ready
- * before other inits try to initialize their memmap data.
- */
-DECLARE_HOOK(HOOK_INIT, lpc_init, HOOK_PRIO_INIT_LPC);
-
-static void lpc_tick(void)
-{
- /*
- * Make sure pending LPC interrupts have been processed.
- * This works around a LM4 bug where host writes sometimes
- * don't trigger interrupts. See crosbug.com/p/13965.
- */
- task_trigger_irq(LM4_IRQ_LPC);
-}
-DECLARE_HOOK(HOOK_TICK, lpc_tick, HOOK_PRIO_DEFAULT);
-
-/**
- * Get protocol information
- */
-static enum ec_status lpc_get_protocol_info(struct host_cmd_handler_args *args)
-{
- struct ec_response_get_protocol_info *r = args->response;
-
- memset(r, 0, sizeof(*r));
- r->protocol_versions = BIT(2) | BIT(3);
- r->max_request_packet_size = EC_LPC_HOST_PACKET_SIZE;
- r->max_response_packet_size = EC_LPC_HOST_PACKET_SIZE;
- r->flags = 0;
-
- args->response_size = sizeof(*r);
-
- return EC_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_GET_PROTOCOL_INFO,
- lpc_get_protocol_info,
- EC_VER_MASK(0));
diff --git a/chip/lm4/peci.c b/chip/lm4/peci.c
deleted file mode 100644
index b3b54a64bc..0000000000
--- a/chip/lm4/peci.c
+++ /dev/null
@@ -1,152 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* PECI interface for Chrome EC */
-
-#include "chipset.h"
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "peci.h"
-#include "registers.h"
-#include "temp_sensor.h"
-#include "util.h"
-
-/* Initial PECI baud rate */
-#define PECI_BAUD_RATE 100000
-
-/* Polling interval for PECI, in ms */
-#define PECI_POLL_INTERVAL_MS 250
-
-/*
- * Internal and external path delays, in ns. The external delay is a
- * best-guess measurement, but we're fairly tolerant of a bad guess because
- * PECI_BAUD_RATE is slow compared to PECI's actual maximum baud rate.
- */
-#define PECI_TD_FET_NS 60
-#define PECI_TD_INT_NS 80
-
-/* Number of controller retries. Should be between 0 and 7. */
-#define PECI_RETRY_COUNT 4
-
-/* Timing negotiation error bypass. 1 = on. 0 = off. */
-#define PECI_ERROR_BYPASS 1
-
-#define TEMP_AVG_LENGTH 4 /* Should be power of 2 */
-static int temp_vals[TEMP_AVG_LENGTH];
-static int temp_idx;
-
-int peci_get_cpu_temp(void)
-{
- int v = LM4_PECI_M0D0 & 0xffff;
-
- if (v >= 0x8000 && v <= 0x8fff)
- return -1;
-
- return v >> 6;
-}
-
-int peci_temp_sensor_get_val(int idx, int *temp_ptr)
-{
- int sum = 0;
- int success_cnt = 0;
- int i;
-
- if (!chipset_in_state(CHIPSET_STATE_ON))
- return EC_ERROR_NOT_POWERED;
-
- for (i = 0; i < TEMP_AVG_LENGTH; ++i) {
- if (temp_vals[i] >= 0) {
- success_cnt++;
- sum += temp_vals[i];
- }
- }
-
- /*
- * Require at least two valid samples. When the AP transitions into S0,
- * it is possible, depending on the timing of the PECI sample, to read
- * an invalid temperature. This is very rare, but when it does happen
- * the temperature returned is CONFIG_PECI_TJMAX. Requiring two valid
- * samples here assures us that one bad maximum temperature reading
- * when entering S0 won't cause us to trigger an over temperature.
- */
- if (success_cnt < 2)
- return EC_ERROR_UNKNOWN;
-
- *temp_ptr = sum / success_cnt;
- return EC_SUCCESS;
-}
-
-static void peci_temp_sensor_poll(void)
-{
- temp_vals[temp_idx] = peci_get_cpu_temp();
- temp_idx = (temp_idx + 1) & (TEMP_AVG_LENGTH - 1);
-}
-DECLARE_HOOK(HOOK_TICK, peci_temp_sensor_poll, HOOK_PRIO_TEMP_SENSOR);
-
-static void peci_freq_changed(void)
-{
- int freq = clock_get_freq();
- int baud;
-
- /* Disable polling while reconfiguring */
- LM4_PECI_CTL = 0;
-
- /*
- * Calculate baud setting from desired rate, compensating for internal
- * and external delays.
- */
- baud = freq / (4 * PECI_BAUD_RATE) - 2;
- baud -= (freq / 1000000) * (PECI_TD_FET_NS + PECI_TD_INT_NS) / 1000;
-
- /* Set baud rate and polling rate */
- LM4_PECI_DIV = (baud << 16) |
- (PECI_POLL_INTERVAL_MS * (freq / 1000 / 4096));
-
- /* Set up temperature monitoring to report in degrees K */
- LM4_PECI_CTL = ((CONFIG_PECI_TJMAX + 273) << 22) | 0x0001 |
- (PECI_RETRY_COUNT << 12) |
- (PECI_ERROR_BYPASS << 11);
-}
-DECLARE_HOOK(HOOK_FREQ_CHANGE, peci_freq_changed, HOOK_PRIO_DEFAULT);
-
-static void peci_init(void)
-{
- int i;
-
- /* Enable the PECI module in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_PECI, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- /* Configure GPIOs */
- gpio_config_module(MODULE_PECI, 1);
-
- /* Set initial clock frequency */
- peci_freq_changed();
-
- /* Initialize temperature reading buffer to a valid value. */
- for (i = 0; i < TEMP_AVG_LENGTH; ++i)
- temp_vals[i] = 300; /* 27 C */
-}
-DECLARE_HOOK(HOOK_INIT, peci_init, HOOK_PRIO_DEFAULT);
-
-/*****************************************************************************/
-/* Console commands */
-
-static int command_peci_temp(int argc, char **argv)
-{
- int t = peci_get_cpu_temp();
- if (t == -1) {
- ccprintf("PECI error 0x%04x\n", LM4_PECI_M0D0 & 0xffff);
- return EC_ERROR_UNKNOWN;
- }
- ccprintf("CPU temp = %d K = %d C\n", t, K_TO_C(t));
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(pecitemp, command_peci_temp,
- NULL,
- "Print CPU temperature");
diff --git a/chip/lm4/pwm.c b/chip/lm4/pwm.c
deleted file mode 100644
index 38ce61714d..0000000000
--- a/chip/lm4/pwm.c
+++ /dev/null
@@ -1,70 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* PWM control module for LM4.
- *
- * On this chip, the PWM logic is implemented by the hardware FAN modules.
- */
-
-#include "clock.h"
-#include "fan.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "pwm.h"
-#include "pwm_chip.h"
-#include "registers.h"
-#include "util.h"
-
-void pwm_enable(enum pwm_channel ch, int enabled)
-{
- fan_set_enabled(pwm_channels[ch].channel, enabled);
-}
-
-int pwm_get_enabled(enum pwm_channel ch)
-{
- return fan_get_enabled(pwm_channels[ch].channel);
-}
-
-void pwm_set_duty(enum pwm_channel ch, int percent)
-{
- if (percent < 0)
- percent = 0;
- else if (percent > 100)
- percent = 100;
-
- /* Assume the fan control is active high and invert it ourselves */
- if (pwm_channels[ch].flags & PWM_CONFIG_ACTIVE_LOW)
- percent = 100 - percent;
-
- /* Always enable the channel */
- pwm_enable(ch, 1);
-
- /* Set the duty cycle */
- fan_set_duty(pwm_channels[ch].channel, percent);
-}
-
-int pwm_get_duty(enum pwm_channel ch)
-{
- int percent = fan_get_duty(pwm_channels[ch].channel);
-
- if (pwm_channels[ch].flags & PWM_CONFIG_ACTIVE_LOW)
- percent = 100 - percent;
-
- return percent;
-}
-
-static void pwm_init(void)
-{
- int i;
-
- for (i = 0; i < PWM_CH_COUNT; ++i)
- fan_channel_setup(pwm_channels[i].channel,
- (pwm_channels[i].flags &
- PWM_CONFIG_HAS_RPM_MODE)
- ? FAN_USE_RPM_MODE : 0);
-}
-
-/* The chip-specific fan module initializes before this. */
-DECLARE_HOOK(HOOK_INIT, pwm_init, HOOK_PRIO_INIT_PWM);
diff --git a/chip/lm4/pwm_chip.h b/chip/lm4/pwm_chip.h
deleted file mode 100644
index ada5785495..0000000000
--- a/chip/lm4/pwm_chip.h
+++ /dev/null
@@ -1,21 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* LM4-specific PWM module for Chrome EC */
-
-#ifndef __CROS_EC_PWM_CHIP_H
-#define __CROS_EC_PWM_CHIP_H
-
-/* Data structure to define PWM channels. */
-struct pwm_t {
- /* PWM channel ID */
- int channel;
- /* PWM channel flags. See include/pwm.h */
- uint32_t flags;
-};
-
-extern const struct pwm_t pwm_channels[];
-
-#endif /* __CROS_EC_PWM_CHIP_H */
diff --git a/chip/lm4/registers.h b/chip/lm4/registers.h
deleted file mode 100644
index 0c59da19f6..0000000000
--- a/chip/lm4/registers.h
+++ /dev/null
@@ -1,600 +0,0 @@
-/* Copyright 2013 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.
- *
- * Register map for LM4x processor
- */
-
-#ifndef __CROS_EC_REGISTERS_H
-#define __CROS_EC_REGISTERS_H
-
-#include "common.h"
-
-#define LM4_UART_CH0_BASE 0x4000c000
-#define LM4_UART_CH1_BASE 0x4000d000
-#define LM4_UART_CH_SEP 0x00001000
-static inline int lm4_uart_addr(int ch, int offset)
-{
- return offset + LM4_UART_CH0_BASE + LM4_UART_CH_SEP * ch;
-}
-#define LM4UARTREG(ch, offset) REG32(lm4_uart_addr(ch, offset))
-#define LM4_UART_DR(ch) LM4UARTREG(ch, 0x000)
-#define LM4_UART_FR(ch) LM4UARTREG(ch, 0x018)
-#define LM4_UART_IBRD(ch) LM4UARTREG(ch, 0x024)
-#define LM4_UART_FBRD(ch) LM4UARTREG(ch, 0x028)
-#define LM4_UART_LCRH(ch) LM4UARTREG(ch, 0x02c)
-#define LM4_UART_CTL(ch) LM4UARTREG(ch, 0x030)
-#define LM4_UART_IFLS(ch) LM4UARTREG(ch, 0x034)
-#define LM4_UART_IM(ch) LM4UARTREG(ch, 0x038)
-#define LM4_UART_ICR(ch) LM4UARTREG(ch, 0x044)
-#define LM4_UART_DMACTL(ch) LM4UARTREG(ch, 0x048)
-#define LM4_UART_CC(ch) LM4UARTREG(ch, 0xfc8)
-
-#define LM4_SSI_BASE 0x40008000
-#define LM4_SSI_CH_SEP 0x40001000
-static inline int lm4_spi_addr(int ch, int offset)
-{
- return offset + LM4_SSI_BASE + LM4_SSI_CH_SEP * ch;
-}
-#define LM4SSIREG(ch, offset) REG32(lm4_spi_addr(ch, offset))
-#define LM4_SSI_CR0(ch) LM4SSIREG(ch, 0x000)
-#define LM4_SSI_CR1(ch) LM4SSIREG(ch, 0x004)
-#define LM4_SSI_DR(ch) LM4SSIREG(ch, 0x008)
-#define LM4_SSI_SR(ch) LM4SSIREG(ch, 0x00c)
-#define LM4_SSI_SR_TFE BIT(0) /* Transmit FIFO empty */
-#define LM4_SSI_SR_TNF BIT(1) /* Transmit FIFO not full */
-#define LM4_SSI_SR_RNE BIT(2) /* Receive FIFO not empty */
-#define LM4_SSI_SR_RFF BIT(3) /* Receive FIFO full */
-#define LM4_SSI_SR_BSY BIT(4) /* Busy */
-#define LM4_SSI_CPSR(ch) LM4SSIREG(ch, 0x010)
-#define LM4_SSI_IM(ch) LM4SSIREG(ch, 0x014)
-#define LM4_SSI_RIS(ch) LM4SSIREG(ch, 0x018)
-#define LM4_SSI_MIS(ch) LM4SSIREG(ch, 0x01c)
-#define LM4_SSI_ICR(ch) LM4SSIREG(ch, 0x020)
-#define LM4_SSI_DMACTL(ch) LM4SSIREG(ch, 0x024)
-#define LM4_SSI_CC(ch) LM4SSIREG(ch, 0xfc8)
-
-#define LM4_ADC_ADCACTSS REG32(0x40038000)
-#define LM4_ADC_ADCRIS REG32(0x40038004)
-#define LM4_ADC_ADCIM REG32(0x40038008)
-#define LM4_ADC_ADCISC REG32(0x4003800c)
-#define LM4_ADC_ADCOSTAT REG32(0x40038010)
-#define LM4_ADC_ADCEMUX REG32(0x40038014)
-#define LM4_ADC_ADCUSTAT REG32(0x40038018)
-#define LM4_ADC_ADCSSPRI REG32(0x40038020)
-#define LM4_ADC_ADCSPC REG32(0x40038024)
-#define LM4_ADC_ADCPSSI REG32(0x40038028)
-#define LM4_ADC_ADCSAC REG32(0x40038030)
-#define LM4_ADC_ADCCTL REG32(0x40038038)
-#define LM4_ADC_ADCCC REG32(0x40038fc8)
-#define LM4_ADC_SS0_BASE 0x40038040
-#define LM4_ADC_SS1_BASE 0x40038060
-#define LM4_ADC_SS2_BASE 0x40038080
-#define LM4_ADC_SS3_BASE 0x400380a0
-#define LM4_ADC_SS_SEP 0x00000020
-static inline int lm4_adc_addr(int ss, int offset)
-{
- return offset + LM4_ADC_SS0_BASE + LM4_ADC_SS_SEP * ss;
-}
-#define LM4ADCREG(ss, offset) REG32(lm4_adc_addr(ss, offset))
-#define LM4_ADC_SSMUX(ss) LM4ADCREG(ss, 0x000)
-#define LM4_ADC_SSCTL(ss) LM4ADCREG(ss, 0x004)
-#define LM4_ADC_SSFIFO(ss) LM4ADCREG(ss, 0x008)
-#define LM4_ADC_SSFSTAT(ss) LM4ADCREG(ss, 0x00c)
-#define LM4_ADC_SSOP(ss) LM4ADCREG(ss, 0x010)
-#define LM4_ADC_SSEMUX(ss) LM4ADCREG(ss, 0x018)
-
-#define LM4_LPC_LPCCTL REG32(0x40080000)
-#define LM4_LPC_SCI_START BIT(9) /* Start a pulse on LPC0SCI signal */
-#define LM4_LPC_SCI_CLK_1 (0 << 10) /* SCI asserted for 1 clock period */
-#define LM4_LPC_SCI_CLK_2 (1 << 10) /* SCI asserted for 2 clock periods */
-#define LM4_LPC_SCI_CLK_4 (2 << 10) /* SCI asserted for 4 clock periods */
-#define LM4_LPC_SCI_CLK_8 (3 << 10) /* SCI asserted for 8 clock periods */
-#define LM4_LPC_LPCSTS REG32(0x40080004)
-#define LM4_LPC_LPCIRQCTL REG32(0x40080008)
-#define LM4_LPC_LPCIRQST REG32(0x4008000c)
-#define LM4_LPC_LPCIM REG32(0x40080100)
-#define LM4_LPC_LPCRIS REG32(0x40080104)
-#define LM4_LPC_LPCMIS REG32(0x40080108)
-#define LM4_LPC_LPCIC REG32(0x4008010c)
-#define LM4_LPC_INT_MASK(ch, bits) ((bits) << (4 * (ch)))
-#define LM4_LPC_LPCDMACX REG32(0x40080120)
-#define LM4_LPC_CH0_BASE 0x40080010
-#define LM4_LPC_CH1_BASE 0x40080020
-#define LM4_LPC_CH2_BASE 0x40080030
-#define LM4_LPC_CH3_BASE 0x40080040
-#define LM4_LPC_CH4_BASE 0x40080050
-#define LM4_LPC_CH5_BASE 0x40080060
-#define LM4_LPC_CH6_BASE 0x40080070
-#define LM4_LPC_CH7_BASE 0x40080080
-#define LM4_LPC_CH_SEP 0x00000010
-static inline int lm4_lpc_addr(int ch, int offset)
-{
- return offset + LM4_LPC_CH0_BASE + LM4_LPC_CH_SEP * ch;
-}
-#define LM4LPCREG(ch, offset) REG32(lm4_lpc_addr(ch, offset))
-#define LM4_LPC_CTL(ch) LM4LPCREG(ch, 0x000)
-#define LM4_LPC_ST(ch) LM4LPCREG(ch, 0x004)
-#define LM4_LPC_ST_TOH BIT(0) /* TO Host bit */
-#define LM4_LPC_ST_FRMH BIT(1) /* FRoM Host bit */
-#define LM4_LPC_ST_CMD BIT(3) /* Last from-host byte was command */
-#define LM4_LPC_ST_BURST BIT(8)
-#define LM4_LPC_ST_SCI BIT(9)
-#define LM4_LPC_ST_SMI BIT(10)
-#define LM4_LPC_ST_BUSY BIT(12)
-#define LM4_LPC_ADR(ch) LM4LPCREG(ch, 0x008)
-#define LM4_LPC_POOL_BYTES 1024 /* Size of LPCPOOL in bytes */
-#define LM4_LPC_LPCPOOL ((volatile unsigned char *)0x40080400)
-
-#define LM4_FAN_FANSTS REG32(0x40084000)
-#define LM4_FAN_FANCTL REG32(0x40084004)
-#define LM4_FAN_CH0_BASE 0x40084010
-#define LM4_FAN_CH1_BASE 0x40084020
-#define LM4_FAN_CH2_BASE 0x40084030
-#define LM4_FAN_CH3_BASE 0x40084040
-#define LM4_FAN_CH4_BASE 0x40084050
-#define LM4_FAN_CH5_BASE 0x40084060
-#define LM4_FAN_CH_SEP 0x00000010
-static inline int lm4_fan_addr(int ch, int offset)
-{
- return offset + LM4_FAN_CH0_BASE + LM4_FAN_CH_SEP * ch;
-}
-#define LM4FANREG(ch, offset) REG32(lm4_fan_addr(ch, offset))
-#define LM4_FAN_FANCH(ch) LM4FANREG(ch, 0x000)
-#define LM4_FAN_FANCMD(ch) LM4FANREG(ch, 0x004)
-#define LM4_FAN_FANCST(ch) LM4FANREG(ch, 0x008)
-
-#define LM4_EEPROM_EESIZE REG32(0x400af000)
-#define LM4_EEPROM_EEBLOCK REG32(0x400af004)
-#define LM4_EEPROM_EEOFFSET REG32(0x400af008)
-#define LM4_EEPROM_EERDWR REG32(0x400af010)
-#define LM4_EEPROM_EERDWRINC REG32(0x400af014)
-#define LM4_EEPROM_EEDONE REG32(0x400af018)
-#define LM4_EEPROM_EESUPP REG32(0x400af01c)
-#define LM4_EEPROM_EEUNLOCK REG32(0x400af020)
-#define LM4_EEPROM_EEPROT REG32(0x400af030)
-#define LM4_EEPROM_EEPASS0 REG32(0x400af034)
-#define LM4_EEPROM_EEPASS1 REG32(0x400af038)
-#define LM4_EEPROM_EEPASS2 REG32(0x400af03c)
-#define LM4_EEPROM_EEINT REG32(0x400af040)
-#define LM4_EEPROM_EEHIDE REG32(0x400af050)
-
-#define LM4_PECI_CTL REG32(0x400b0000)
-#define LM4_PECI_DIV REG32(0x400b0004)
-#define LM4_PECI_CMP REG32(0x400b0008)
-#define LM4_PECI_M0D0C REG32(0x400b0010)
-#define LM4_PECI_M0D1C REG32(0x400b0014)
-#define LM4_PECI_M1D0C REG32(0x400b0018)
-#define LM4_PECI_M1D1C REG32(0x400b001c)
-#define LM4_PECI_M0D0 REG32(0x400b0040)
-#define LM4_PECI_M0D1 REG32(0x400b0044)
-#define LM4_PECI_M1D0 REG32(0x400b0048)
-#define LM4_PECI_M1D1 REG32(0x400b004c)
-#define LM4_PECI_IM REG32(0x400b0080)
-#define LM4_PECI_RIS REG32(0x400b0084)
-#define LM4_PECI_MIS REG32(0x400b0088)
-#define LM4_PECI_IC REG32(0x400b008c)
-#define LM4_PECI_ACADDR REG32(0x400b0100)
-#define LM4_PECI_ACARG REG32(0x400b0104)
-#define LM4_PECI_ACRDWR0 REG32(0x400b0108)
-#define LM4_PECI_ACRDWR1 REG32(0x400b010c)
-#define LM4_PECI_ACCMD REG32(0x400b0110)
-#define LM4_PECI_ACCODE REG32(0x400b0114)
-
-
-#define LM4_HIBERNATE_HIBRTCC REG32(0x400fc000)
-#define LM4_HIBERNATE_HIBRTCM0 REG32(0x400fc004)
-#define LM4_HIBERNATE_HIBRTCLD REG32(0x400fc00c)
-#define LM4_HIBERNATE_HIBCTL REG32(0x400fc010)
-#define LM4_HIBCTL_WRC BIT(31)
-#define LM4_HIBCTL_CLK32EN BIT(6)
-#define LM4_HIBCTL_PINWEN BIT(4)
-#define LM4_HIBCTL_RTCWEN BIT(3)
-#define LM4_HIBCTL_HIBREQ BIT(1)
-#define LM4_HIBCTL_RTCEN BIT(0)
-#define LM4_HIBERNATE_HIBIM REG32(0x400fc014)
-#define LM4_HIBERNATE_HIBRIS REG32(0x400fc018)
-#define LM4_HIBERNATE_HIBMIS REG32(0x400fc01c)
-#define LM4_HIBERNATE_HIBIC REG32(0x400fc020)
-#define LM4_HIBERNATE_HIBRTCT REG32(0x400fc024)
-#define LM4_HIBERNATE_HIBRTCSS REG32(0x400fc028)
-#define LM4_HIBERNATE_HIBDATA_ENTRIES 16 /* Number of entries in HIBDATA[] */
-#define LM4_HIBERNATE_HIBDATA ((volatile uint32_t *)0x400fc030)
-
-#define LM4_FLASH_FMA REG32(0x400fd000)
-#define LM4_FLASH_FMD REG32(0x400fd004)
-#define LM4_FLASH_FMC REG32(0x400fd008)
-#define LM4_FLASH_FCRIS REG32(0x400fd00c)
-#define LM4_FLASH_FCMISC REG32(0x400fd014)
-#define LM4_FLASH_FMC2 REG32(0x400fd020)
-#define LM4_FLASH_FWBVAL REG32(0x400fd030)
-/* FWB size is 32 words = 128 bytes */
-#define LM4_FLASH_FWB ((volatile uint32_t*)0x400fd100)
-#define LM4_FLASH_FSIZE REG32(0x400fdfc0)
-#define LM4_FLASH_FMPRE0 REG32(0x400fe200)
-#define LM4_FLASH_FMPRE1 REG32(0x400fe204)
-#define LM4_FLASH_FMPRE2 REG32(0x400fe208)
-#define LM4_FLASH_FMPRE3 REG32(0x400fe20c)
-#define LM4_FLASH_FMPPE ((volatile uint32_t*)0x400fe400)
-#define LM4_FLASH_FMPPE0 REG32(0x400fe400)
-#define LM4_FLASH_FMPPE1 REG32(0x400fe404)
-#define LM4_FLASH_FMPPE2 REG32(0x400fe408)
-#define LM4_FLASH_FMPPE3 REG32(0x400fe40c)
-
-#define LM4_SYSTEM_DID0 REG32(0x400fe000)
-#define LM4_SYSTEM_DID1 REG32(0x400fe004)
-#define LM4_SYSTEM_PBORCTL REG32(0x400fe030)
-#define LM4_SYSTEM_RIS REG32(0x400fe050)
-#define LM4_SYSTEM_MISC REG32(0x400fe058)
-#define LM4_SYSTEM_RESC REG32(0x400fe05c)
-#define LM4_SYSTEM_RCC REG32(0x400fe060)
-#define LM4_SYSTEM_RCC_ACG BIT(27)
-#define LM4_SYSTEM_RCC_SYSDIV(x) (((x) & 0xf) << 23)
-#define LM4_SYSTEM_RCC_USESYSDIV BIT(22)
-#define LM4_SYSTEM_RCC_PWRDN BIT(13)
-#define LM4_SYSTEM_RCC_BYPASS BIT(11)
-#define LM4_SYSTEM_RCC_XTAL(x) (((x) & 0x1f) << 6)
-#define LM4_SYSTEM_RCC_OSCSRC(x) (((x) & 0x3) << 4)
-#define LM4_SYSTEM_RCC_IOSCDIS BIT(1)
-#define LM4_SYSTEM_RCC_MOSCDIS BIT(0)
-#define LM4_SYSTEM_RCC2 REG32(0x400fe070)
-#define LM4_SYSTEM_RCC2_USERCC2 BIT(31)
-#define LM4_SYSTEM_RCC2_DIV400 BIT(30)
-#define LM4_SYSTEM_RCC2_SYSDIV2(x) (((x) & 0x3f) << 23)
-#define LM4_SYSTEM_RCC2_SYSDIV2LSB BIT(22)
-#define LM4_SYSTEM_RCC2_PWRDN2 BIT(13)
-#define LM4_SYSTEM_RCC2_BYPASS2 BIT(11)
-#define LM4_SYSTEM_RCC2_OSCSRC2(x) (((x) & 0x7) << 4)
-#define LM4_SYSTEM_MOSCCTL REG32(0x400fe07c)
-#define LM4_SYSTEM_DSLPCLKCFG REG32(0x400fe144)
-#define LM4_SYSTEM_PIOSCCAL REG32(0x400fe150)
-#define LM4_SYSTEM_PIOSCSTAT REG32(0x400fe154)
-#define LM4_SYSTEM_PLLSTAT REG32(0x400fe168)
-#define LM4_SYSTEM_SLPPWRCFG REG32(0x400fe188)
-#define LM4_SYSTEM_DSLPPWRCFG REG32(0x400fe18c)
-#define LM4_SYSTEM_LDOSPCTL REG32(0x400fe1b4)
-#define LM4_SYSTEM_LDOSPCAL REG32(0x400fe1b8)
-#define LM4_SYSTEM_LDODPCTL REG32(0x400fe1bc)
-#define LM4_SYSTEM_LDODPCAL REG32(0x400fe1c0)
-#define LM4_SYSTEM_SPDMST REG32(0x400fe1cc)
-#define LM4_SYSTEM_BOOTCFG REG32(0x400fe1d0)
-#define LM4_SYSTEM_BOOTCFG_MASK 0x7fff00ec /* Reserved bits of BOOTCFG reg */
-/* Note: USER_REG3 is used to hold pre-programming process data and should not
- * be modified by EC code. See crosbug.com/p/8889. */
-#define LM4_SYSTEM_USER_REG3 REG32(0x400fe1ec)
-#define LM4_SYSTEM_SRI2C REG32(0x400fe520)
-#define LM4_SYSTEM_SREEPROM REG32(0x400fe558)
-
-#define LM4_SYSTEM_SRI2C_ADDR ((uint32_t *)0x400fe520)
-
-#define LM4_SYSTEM_RCGC_BASE ((volatile uint32_t *)0x400fe600)
-#define LM4_SYSTEM_RCGCGPIO REG32(0x400fe608)
-#define LM4_SYSTEM_SCGC_BASE ((volatile uint32_t *)0x400fe700)
-#define LM4_SYSTEM_DCGC_BASE ((volatile uint32_t *)0x400fe800)
-
-/*
- * Offsets from CGC_BASE registers for each peripheral.
- * Note: these are in units of 32-bit words offset from
- * the base address.
- */
-enum clock_gate_offsets {
- CGC_OFFSET_WD = 0,
- CGC_OFFSET_TIMER = 1,
- CGC_OFFSET_GPIO = 2,
- CGC_OFFSET_DMA = 3,
- CGC_OFFSET_HIB = 5,
- CGC_OFFSET_UART = 6,
- CGC_OFFSET_SSI = 7,
- CGC_OFFSET_I2C = 8,
- CGC_OFFSET_ADC = 14,
- CGC_OFFSET_LPC = 18,
- CGC_OFFSET_PECI = 20,
- CGC_OFFSET_FAN = 21,
- CGC_OFFSET_EEPROM = 22,
- CGC_OFFSET_WTIMER = 23,
-};
-
-#define LM4_SYSTEM_PREEPROM REG32(0x400fea58)
-
-#define LM4_DMA_DMACFG REG32(0x400ff004)
-#define LM4_DMA_DMACTLBASE REG32(0x400ff008)
-#define LM4_DMA_DMACHMAP0 REG32(0x400ff510)
-#define LM4_DMA_DMACHMAP1 REG32(0x400ff514)
-#define LM4_DMA_DMACHMAP2 REG32(0x400ff518)
-#define LM4_DMA_DMACHMAP3 REG32(0x400ff51c)
-
-/* IRQ numbers */
-#define LM4_IRQ_GPIOA 0
-#define LM4_IRQ_GPIOB 1
-#define LM4_IRQ_GPIOC 2
-#define LM4_IRQ_GPIOD 3
-#define LM4_IRQ_GPIOE 4
-#define LM4_IRQ_UART0 5
-#define LM4_IRQ_UART1 6
-#define LM4_IRQ_SSI0 7
-#define LM4_IRQ_I2C0 8
-/* 9 - 13 reserved */
-#define LM4_IRQ_ADC0_SS0 14
-#define LM4_IRQ_ADC0_SS1 15
-#define LM4_IRQ_ADC0_SS2 16
-#define LM4_IRQ_ADC0_SS3 17
-#define LM4_IRQ_WATCHDOG 18
-#define LM4_IRQ_TIMER0A 19
-#define LM4_IRQ_TIMER0B 20
-#define LM4_IRQ_TIMER1A 21
-#define LM4_IRQ_TIMER1B 22
-#define LM4_IRQ_TIMER2A 23
-#define LM4_IRQ_TIMER2B 24
-#define LM4_IRQ_ACMP0 25
-#define LM4_IRQ_ACMP1 26
-#define LM4_IRQ_ACMP2 27
-#define LM4_IRQ_SYSCTRL 28
-#define LM4_IRQ_EEPROM 29
-#define LM4_IRQ_GPIOF 30
-#define LM4_IRQ_GPIOG 31
-#define LM4_IRQ_GPIOH 32
-#define LM4_IRQ_UART2 33
-#define LM4_IRQ_SSI1 34
-#define LM4_IRQ_TIMER3A 35
-#define LM4_IRQ_TIMER3B 36
-#define LM4_IRQ_I2C1 37
-/* 38 - 42 reserved */
-#define LM4_IRQ_HIBERNATE 43
-/* 44 - 45 reserved */
-#define LM4_IRQ_UDMA_SOFTWARE 46
-#define LM4_IRQ_UDMA_ERROR 47
-#define LM4_IRQ_ADC1_SS0 48
-#define LM4_IRQ_ADC1_SS1 49
-#define LM4_IRQ_ADC1_SS2 50
-#define LM4_IRQ_ADC1_SS3 51
-/* 52 - 53 reserved */
-#define LM4_IRQ_GPIOJ 54
-#define LM4_IRQ_GPIOK 55
-#define LM4_IRQ_GPIOL 56
-#define LM4_IRQ_SSI2 57
-#define LM4_IRQ_SSI3 58
-#define LM4_IRQ_UART3 59
-#define LM4_IRQ_UART4 60
-#define LM4_IRQ_UART5 61
-#define LM4_IRQ_UART6 62
-#define LM4_IRQ_UART7 63
-/* 64 - 67 reserved */
-#define LM4_IRQ_I2C2 68
-#define LM4_IRQ_I2C3 69
-#define LM4_IRQ_TIMER4A 70
-#define LM4_IRQ_TIMER4B 71
-/* 72 - 91 reserved */
-#define LM4_IRQ_TIMER5A 92
-#define LM4_IRQ_TIMER5B 93
-#define LM4_IRQ_TIMERW0A 94
-#define LM4_IRQ_TIMERW0B 95
-#define LM4_IRQ_TIMERW1A 96
-#define LM4_IRQ_TIMERW1B 97
-#define LM4_IRQ_TIMERW2A 98
-#define LM4_IRQ_TIMERW2B 99
-#define LM4_IRQ_TIMERW3A 100
-#define LM4_IRQ_TIMERW3B 101
-#define LM4_IRQ_TIMERW4A 102
-#define LM4_IRQ_TIMERW4B 103
-#define LM4_IRQ_TIMERW5A 104
-#define LM4_IRQ_TIMERW5B 105
-#define LM4_IRQ_SYS_EXCEPTION 106
-#define LM4_IRQ_SYS_PECI 107
-#define LM4_IRQ_LPC 108
-#define LM4_IRQ_I2C4 109
-#define LM4_IRQ_I2C5 110
-#define LM4_IRQ_GPIOM 111
-#define LM4_IRQ_GPION 112
-/* 113 reserved */
-#define LM4_IRQ_FAN 114
-/* 115 reserved */
-#define LM4_IRQ_GPIOP 116
-#define LM4_IRQ_GPIOP1 117
-#define LM4_IRQ_GPIOP2 118
-#define LM4_IRQ_GPIOP3 119
-#define LM4_IRQ_GPIOP4 120
-#define LM4_IRQ_GPIOP5 121
-#define LM4_IRQ_GPIOP6 122
-#define LM4_IRQ_GPIOP7 123
-#define LM4_IRQ_GPIOQ 124
-#define LM4_IRQ_GPIOQ1 125
-#define LM4_IRQ_GPIOQ2 126
-#define LM4_IRQ_GPIOQ3 127
-#define LM4_IRQ_GPIOQ4 128
-#define LM4_IRQ_GPIOQ5 129
-#define LM4_IRQ_GPIOQ6 130
-#define LM4_IRQ_GPIOQ7 131
-/* 132 - 138 reserved */
-
-/* GPIO */
-#define LM4_GPIO_PORTA_BASE 0x40004000
-#define LM4_GPIO_PORTB_BASE 0x40005000
-#define LM4_GPIO_PORTC_BASE 0x40006000
-#define LM4_GPIO_PORTD_BASE 0x40007000
-#define LM4_GPIO_PORTE_BASE 0x40024000
-#define LM4_GPIO_PORTF_BASE 0x40025000
-#define LM4_GPIO_PORTG_BASE 0x40026000
-#define LM4_GPIO_PORTH_BASE 0x40027000
-#define LM4_GPIO_PORTJ_BASE 0x4003d000
-#define LM4_GPIO_PORTK_BASE 0x40061000
-#define LM4_GPIO_PORTL_BASE 0x40062000
-#define LM4_GPIO_PORTM_BASE 0x40063000
-#define LM4_GPIO_PORTN_BASE 0x40064000
-#define LM4_GPIO_PORTP_BASE 0x40065000
-#define LM4_GPIO_PORTQ_BASE 0x40066000
-#define LM4_GPIO_PORTA_AHB_BASE 0x40058000
-#define LM4_GPIO_PORTB_AHB_BASE 0x40059000
-#define LM4_GPIO_PORTC_AHB_BASE 0x4005a000
-#define LM4_GPIO_PORTD_AHB_BASE 0x4005b000
-#define LM4_GPIO_PORTE_AHB_BASE 0x4005c000
-#define LM4_GPIO_PORTF_AHB_BASE 0x4005d000
-#define LM4_GPIO_PORTG_AHB_BASE 0x4005e000
-#define LM4_GPIO_PORTH_AHB_BASE 0x4005f000
-#define LM4_GPIO_PORTJ_AHB_BASE 0x40060000
-/* Ports for passing to LM4GPIOREG(); abstracted from base addresses above so
- * that we can switch to/from AHB. */
-#define LM4_GPIO_A LM4_GPIO_PORTA_BASE
-#define LM4_GPIO_B LM4_GPIO_PORTB_BASE
-#define LM4_GPIO_C LM4_GPIO_PORTC_BASE
-#define LM4_GPIO_D LM4_GPIO_PORTD_BASE
-#define LM4_GPIO_E LM4_GPIO_PORTE_BASE
-#define LM4_GPIO_F LM4_GPIO_PORTF_BASE
-#define LM4_GPIO_G LM4_GPIO_PORTG_BASE
-#define LM4_GPIO_H LM4_GPIO_PORTH_BASE
-#define LM4_GPIO_J LM4_GPIO_PORTJ_BASE
-#define LM4_GPIO_K LM4_GPIO_PORTK_BASE
-#define LM4_GPIO_L LM4_GPIO_PORTL_BASE
-#define LM4_GPIO_M LM4_GPIO_PORTM_BASE
-#define LM4_GPIO_N LM4_GPIO_PORTN_BASE
-#define LM4_GPIO_P LM4_GPIO_PORTP_BASE
-#define LM4_GPIO_Q LM4_GPIO_PORTQ_BASE
-#define LM4GPIOREG(port, offset) REG32((port) + (offset))
-#define LM4_GPIO_DATA(port, mask) LM4GPIOREG(port, ((mask) << 2))
-#define LM4_GPIO_DIR(port) LM4GPIOREG(port, 0x400)
-#define LM4_GPIO_IS(port) LM4GPIOREG(port, 0x404)
-#define LM4_GPIO_IBE(port) LM4GPIOREG(port, 0x408)
-#define LM4_GPIO_IEV(port) LM4GPIOREG(port, 0x40c)
-#define LM4_GPIO_IM(port) LM4GPIOREG(port, 0x410)
-#define LM4_GPIO_RIS(port) LM4GPIOREG(port, 0x414)
-#define LM4_GPIO_MIS(port) LM4GPIOREG(port, 0x418)
-#define LM4_GPIO_ICR(port) LM4GPIOREG(port, 0x41c)
-#define LM4_GPIO_AFSEL(port) LM4GPIOREG(port, 0x420)
-#define LM4_GPIO_DR2R(port) LM4GPIOREG(port, 0x500)
-#define LM4_GPIO_DR4R(port) LM4GPIOREG(port, 0x504)
-#define LM4_GPIO_DR8R(port) LM4GPIOREG(port, 0x508)
-#define LM4_GPIO_ODR(port) LM4GPIOREG(port, 0x50c)
-#define LM4_GPIO_PUR(port) LM4GPIOREG(port, 0x510)
-#define LM4_GPIO_PDR(port) LM4GPIOREG(port, 0x514)
-#define LM4_GPIO_SLR(port) LM4GPIOREG(port, 0x518)
-#define LM4_GPIO_DEN(port) LM4GPIOREG(port, 0x51c)
-#define LM4_GPIO_LOCK(port) LM4GPIOREG(port, 0x520)
-#define LM4_GPIO_CR(port) LM4GPIOREG(port, 0x524)
-#define LM4_GPIO_AMSEL(port) LM4GPIOREG(port, 0x528)
-#define LM4_GPIO_PCTL(port) LM4GPIOREG(port, 0x52c)
-
-/* Chip-independent aliases for port base addresses */
-#define GPIO_A LM4_GPIO_A
-#define GPIO_B LM4_GPIO_B
-#define GPIO_C LM4_GPIO_C
-#define GPIO_D LM4_GPIO_D
-#define GPIO_E LM4_GPIO_E
-#define GPIO_F LM4_GPIO_F
-#define GPIO_G LM4_GPIO_G
-#define GPIO_H LM4_GPIO_H
-#define GPIO_J LM4_GPIO_J
-#define GPIO_K LM4_GPIO_K
-#define GPIO_L LM4_GPIO_L
-#define GPIO_M LM4_GPIO_M
-#define GPIO_N LM4_GPIO_N
-#define GPIO_P LM4_GPIO_P
-#define GPIO_Q LM4_GPIO_Q
-
-#define UNIMPLEMENTED_GPIO_BANK GPIO_A
-
-/* Value to write to LM4_GPIO_LOCK to unlock writes */
-#define LM4_GPIO_LOCK_UNLOCK 0x4c4f434b
-
-/* I2C */
-#define LM4_I2C0_BASE 0x40020000
-#define LM4_I2C1_BASE 0x40021000
-#define LM4_I2C2_BASE 0x40022000
-#define LM4_I2C3_BASE 0x40023000
-#define LM4_I2C4_BASE 0x400c0000
-#define LM4_I2C5_BASE 0x400c1000
-#define LM4_I2C_BASESEP 0x00001000
-/* I2C base address by port. Compiles to a constant in gcc if port
- and offset are constant. */
-static inline int lm4_i2c_addr(int port, int offset)
-{
- return offset + (port < 4 ?
- LM4_I2C0_BASE + LM4_I2C_BASESEP * port :
- LM4_I2C4_BASE + LM4_I2C_BASESEP * (port - 4));
-}
-#define LM4I2CREG(port, offset) REG32(lm4_i2c_addr(port, offset))
-#define LM4_I2C_MSA(port) LM4I2CREG(port, 0x000)
-#define LM4_I2C_MCS(port) LM4I2CREG(port, 0x004)
-#define LM4_I2C_MDR(port) LM4I2CREG(port, 0x008)
-#define LM4_I2C_MTPR(port) LM4I2CREG(port, 0x00c)
-#define LM4_I2C_MIMR(port) LM4I2CREG(port, 0x010)
-#define LM4_I2C_MRIS(port) LM4I2CREG(port, 0x014)
-#define LM4_I2C_MMIS(port) LM4I2CREG(port, 0x018)
-#define LM4_I2C_MICR(port) LM4I2CREG(port, 0x01c)
-#define LM4_I2C_MCR(port) LM4I2CREG(port, 0x020)
-#define LM4_I2C_MCLKOCNT(port) LM4I2CREG(port, 0x024)
-#define LM4_I2C_MBMON(port) LM4I2CREG(port, 0x02c)
-
-
-/* Timers */
-/* Timers 0-5 are 16/32 bit */
-#define LM4_TIMER0_BASE 0x40030000
-#define LM4_TIMER1_BASE 0x40031000
-#define LM4_TIMER2_BASE 0x40032000
-#define LM4_TIMER3_BASE 0x40033000
-#define LM4_TIMER4_BASE 0x40034000
-#define LM4_TIMER5_BASE 0x40035000
-/* Timers 6-11 are 32/64 bit */
-#define LM4_TIMERW0_BASE 0x40036000
-#define LM4_TIMERW1_BASE 0x40037000
-#define LM4_TIMERW2_BASE 0x4004c000
-#define LM4_TIMERW3_BASE 0x4004d000
-#define LM4_TIMERW4_BASE 0x4004e000
-#define LM4_TIMERW5_BASE 0x4004f000
-#define LM4_TIMER_SEP 0x00001000
-static inline int lm4_timer_addr(int timer, int offset)
-{
- if (timer < 8)
- return offset + LM4_TIMER0_BASE + LM4_TIMER_SEP * timer;
- else
- return offset + LM4_TIMERW2_BASE + LM4_TIMER_SEP * (timer - 8);
-}
-#define LM4TIMERREG(timer, offset) REG32(lm4_timer_addr(timer, offset))
-#define LM4_TIMER_CFG(tmr) LM4TIMERREG(tmr, 0x00)
-#define LM4_TIMER_TAMR(tmr) LM4TIMERREG(tmr, 0x04)
-#define LM4_TIMER_TBMR(tmr) LM4TIMERREG(tmr, 0x08)
-#define LM4_TIMER_CTL(tmr) LM4TIMERREG(tmr, 0x0c)
-#define LM4_TIMER_SYNC(tmr) LM4TIMERREG(tmr, 0x10)
-#define LM4_TIMER_IMR(tmr) LM4TIMERREG(tmr, 0x18)
-#define LM4_TIMER_RIS(tmr) LM4TIMERREG(tmr, 0x1c)
-#define LM4_TIMER_MIS(tmr) LM4TIMERREG(tmr, 0x20)
-#define LM4_TIMER_ICR(tmr) LM4TIMERREG(tmr, 0x24)
-#define LM4_TIMER_TAILR(tmr) LM4TIMERREG(tmr, 0x28)
-#define LM4_TIMER_TBILR(tmr) LM4TIMERREG(tmr, 0x2c)
-#define LM4_TIMER_TAMATCHR(tmr) LM4TIMERREG(tmr, 0x30)
-#define LM4_TIMER_TBMATCHR(tmr) LM4TIMERREG(tmr, 0x34)
-#define LM4_TIMER_TAPR(tmr) LM4TIMERREG(tmr, 0x38)
-#define LM4_TIMER_TBPR(tmr) LM4TIMERREG(tmr, 0x3c)
-#define LM4_TIMER_TAPMR(tmr) LM4TIMERREG(tmr, 0x40)
-#define LM4_TIMER_TBPMR(tmr) LM4TIMERREG(tmr, 0x44)
-#define LM4_TIMER_TAR(tmr) LM4TIMERREG(tmr, 0x48)
-#define LM4_TIMER_TBR(tmr) LM4TIMERREG(tmr, 0x4c)
-#define LM4_TIMER_TAV(tmr) LM4TIMERREG(tmr, 0x50)
-#define LM4_TIMER_TBV(tmr) LM4TIMERREG(tmr, 0x54)
-#define LM4_TIMER_RTCPD(tmr) LM4TIMERREG(tmr, 0x58)
-#define LM4_TIMER_TAPS(tmr) LM4TIMERREG(tmr, 0x5c)
-#define LM4_TIMER_TBPS(tmr) LM4TIMERREG(tmr, 0x60)
-#define LM4_TIMER_TAPV(tmr) LM4TIMERREG(tmr, 0x64)
-#define LM4_TIMER_TBPV(tmr) LM4TIMERREG(tmr, 0x68)
-
-#define LM4_SYSTICK_CTRL REG32(0xe000e010)
-#define LM4_SYSTICK_RELOAD REG32(0xe000e014)
-#define LM4_SYSTICK_CURRENT REG32(0xe000e018)
-
-/* Watchdogs */
-#define LM4_WATCHDOG0_BASE 0x40000000
-#define LM4_WATCHDOG1_BASE 0x40001000
-static inline int lm4_watchdog_addr(int num, int offset)
-{
- return offset + (num ? LM4_WATCHDOG1_BASE : LM4_WATCHDOG0_BASE);
-}
-#define LM4WDTREG(num, offset) REG32(lm4_watchdog_addr(num, offset))
-#define LM4_WATCHDOG_LOAD(n) LM4WDTREG(n, 0x000)
-#define LM4_WATCHDOG_VALUE(n) LM4WDTREG(n, 0x004)
-#define LM4_WATCHDOG_CTL(n) LM4WDTREG(n, 0x008)
-#define LM4_WATCHDOG_ICR(n) LM4WDTREG(n, 0x00c)
-#define LM4_WATCHDOG_RIS(n) LM4WDTREG(n, 0x010)
-#define LM4_WATCHDOG_TEST(n) LM4WDTREG(n, 0x418)
-#define LM4_WATCHDOG_LOCK(n) LM4WDTREG(n, 0xc00)
-
-#define LM4_TEST_MODE_ENABLED REG32(0x400fdff0)
-
-#endif /* __CROS_EC_REGISTERS_H */
diff --git a/chip/lm4/spi.c b/chip/lm4/spi.c
deleted file mode 100644
index 629e306af7..0000000000
--- a/chip/lm4/spi.c
+++ /dev/null
@@ -1,179 +0,0 @@
-/* Copyright 2013 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.
- */
-
-/* SPI module for Chrome EC */
-
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "registers.h"
-#include "spi.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-
-/* Console output macros */
-#define CPUTS(outstr) cputs(CC_SPI, outstr)
-#define CPRINTS(format, args...) cprints(CC_SPI, format, ## args)
-
-int spi_enable(const struct spi_device_t *spi_device, int enable)
-{
- if (enable) {
- gpio_config_module(MODULE_SPI, 1);
- /*
- * Don't use the SSI0 frame output.
- * CS# is a GPIO so we can keep it low during an entire
- * transaction.
- */
- gpio_set_flags(spi_device->gpio_cs, GPIO_OUTPUT);
- gpio_set_level(spi_device->gpio_cs, 1);
-
- /* Enable SSI port */
- LM4_SSI_CR1(0) |= 0x02;
- } else {
- /* Disable SSI port */
- LM4_SSI_CR1(0) &= ~0x02;
-
- /* Make sure CS# is deselected */
- gpio_set_level(spi_device->gpio_cs, 1);
- gpio_set_flags(spi_device->gpio_cs[i], GPIO_ODR_HIGH);
-
- gpio_config_module(MODULE_SPI, 0);
- }
-
- return EC_SUCCESS;
-}
-
-
-int spi_transaction(const struct spi_device_t *spi_device,
- const uint8_t *txdata, int txlen,
- uint8_t *rxdata, int rxlen)
-{
- int totallen = txlen + rxlen;
- int txcount = 0, rxcount = 0;
- static struct mutex spi_mutex;
- volatile uint32_t unused __attribute__((unused));
-
- mutex_lock(&spi_mutex);
- /* Empty the receive FIFO */
- while (LM4_SSI_SR(0) & LM4_SSI_SR_RNE)
- unused = LM4_SSI_DR(0);
-
- /* Start transaction. Need to do this explicitly because the LM4
- * SSI controller pulses its frame select every byte, and the EEPROM
- * wants the chip select held low during the entire transaction. */
- gpio_set_level(spi_device->gpio_cs, 0);
-
- while (rxcount < totallen) {
- /* Handle received bytes if any. We just checked rxcount <
- * totallen, so we don't need to worry about overflowing the
- * receive buffer. */
- if (LM4_SSI_SR(0) & LM4_SSI_SR_RNE) {
- if (rxcount < txlen) {
- /* Throw away bytes received while we were
- transmitting */
- unused = LM4_SSI_DR(0);
- } else
- *(rxdata++) = LM4_SSI_DR(0);
- rxcount++;
- }
-
- /* Transmit another byte if needed */
- if ((LM4_SSI_SR(0) & LM4_SSI_SR_TNF) && txcount < totallen) {
- if (txcount < txlen)
- LM4_SSI_DR(0) = *(txdata++);
- else {
- /* Clock out unused byte so we can clock in the
- * response byte */
- LM4_SSI_DR(0) = 0;
- }
- txcount++;
- }
- }
-
- /* End transaction */
- gpio_set_level(spi_device->gpio_cs, 1);
- mutex_unlock(&spi_mutex);
-
- return EC_SUCCESS;
-}
-
-/*****************************************************************************/
-/* Hooks */
-
-static int spi_init(void)
-{
- /* Enable the SPI module in run and sleep modes */
- clock_enable_peripheral(CGC_OFFSET_SSI, 0x1,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- LM4_SSI_CR1(0) = 0; /* Disable SSI */
- LM4_SSI_CR0(0) = 0x0007; /* SCR=0, SPH=0, SPO=0, FRF=SPI, 8-bit */
-
- /* Use PIOSC for clock. This limits us to 8MHz (PIOSC/2), but is
- * simpler to configure and we don't need to worry about clock
- * frequency changing when the PLL is disabled. If we really start
- * using this, might be worth using the system clock and handling
- * frequency change (like we do with PECI) so we can go faster. */
- LM4_SSI_CC(0) = 1;
- /* SSICLK = PIOSC / (CPSDVSR * (1 + SCR)
- * = 16 MHz / (2 * (1 + 0))
- * = 8 MHz */
- LM4_SSI_CPSR(0) = 2;
-
- /* Ensure the SPI port is disabled. This keeps us from interfering
- * with the main chipset when we're not explicitly using the SPI
- * bus. */
- spi_enable(SPI_FLASH_DEVICE, 0);
-
- return EC_SUCCESS;
-}
-DECLARE_HOOK(HOOK_INIT, spi_init, HOOK_PRIO_INIT_SPI);
-
-/*****************************************************************************/
-/* Console commands */
-
-static int printrx(const char *desc, const uint8_t *txdata, int txlen,
- int rxlen)
-{
- uint8_t rxdata[32];
- int rv;
- int i;
-
- rv = spi_transaction(SPI_FLASH_DEVICE, txdata, txlen, rxdata, rxlen);
- if (rv)
- return rv;
-
- ccprintf("%-12s:", desc);
- for (i = 0; i < rxlen; i++)
- ccprintf(" 0x%02x", rxdata[i]);
- ccputs("\n");
- return EC_SUCCESS;
-}
-
-
-static int command_spirom(int argc, char **argv)
-{
- uint8_t txmandev[] = {0x90, 0x00, 0x00, 0x00};
- uint8_t txjedec[] = {0x9f};
- uint8_t txunique[] = {0x4b, 0x00, 0x00, 0x00, 0x00};
- uint8_t txsr1[] = {0x05};
- uint8_t txsr2[] = {0x35};
-
- spi_enable(SPI_FLASH_DEVICE, 1);
-
- printrx("Man/Dev ID", txmandev, sizeof(txmandev), 2);
- printrx("JEDEC ID", txjedec, sizeof(txjedec), 3);
- printrx("Unique ID", txunique, sizeof(txunique), 8);
- printrx("Status reg 1", txsr1, sizeof(txsr1), 1);
- printrx("Status reg 2", txsr2, sizeof(txsr2), 1);
-
- spi_enable(SPI_FLASH_DEVICE, 0);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(spirom, command_spirom,
- NULL,
- "Test reading SPI EEPROM");
diff --git a/chip/lm4/system.c b/chip/lm4/system.c
deleted file mode 100644
index 56bd1a82fd..0000000000
--- a/chip/lm4/system.c
+++ /dev/null
@@ -1,776 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* System module for Chrome EC : LM4 hardware specific implementation */
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "cpu.h"
-#include "host_command.h"
-#include "panic.h"
-#include "registers.h"
-#include "system.h"
-#include "task.h"
-#include "timer.h"
-#include "util.h"
-
-/* Indices for hibernate data registers */
-enum hibdata_index {
- HIBDATA_INDEX_SCRATCHPAD, /* General-purpose scratchpad */
- HIBDATA_INDEX_WAKE, /* Wake reasons for hibernate */
- HIBDATA_INDEX_SAVED_RESET_FLAGS, /* Saved reset flags */
-#ifdef CONFIG_SOFTWARE_PANIC
- HIBDATA_INDEX_SAVED_PANIC_REASON, /* Saved panic reason */
- HIBDATA_INDEX_SAVED_PANIC_INFO, /* Saved panic data */
- HIBDATA_INDEX_SAVED_PANIC_EXCEPTION,/* Saved panic exception code */
- HIBDATA_INDEX_SAVED_PANIC_FLAGS, /* Saved panic flags */
-#endif
-};
-
-/* Flags for HIBDATA_INDEX_WAKE */
-#define HIBDATA_WAKE_RTC BIT(0) /* RTC alarm */
-#define HIBDATA_WAKE_HARD_RESET BIT(1) /* Hard reset via short RTC alarm */
-#define HIBDATA_WAKE_PIN BIT(2) /* Wake pin */
-
-/*
- * Time to hibernate to trigger a power-on reset. 50 ms is sufficient for the
- * EC itself, but we need a longer delay to ensure the rest of the components
- * on the same power rail are reset and 5VALW has dropped.
- */
-#define HIB_RESET_USEC 1000000
-
-/*
- * Convert between microseconds and the hibernation module RTC subsecond
- * register which has 15-bit resolution. Divide down both numerator and
- * denominator to avoid integer overflow while keeping the math accurate.
- */
-#define HIB_RTC_USEC_TO_SUBSEC(us) ((us) * (32768/64) / (1000000/64))
-#define HIB_RTC_SUBSEC_TO_USEC(ss) ((ss) * (1000000/64) / (32768/64))
-
-/**
- * Wait for a write to commit to a hibernate register.
- *
- * @return EC_SUCCESS if successful, non-zero if error.
- */
-static int wait_for_hibctl_wc(void)
-{
- int i;
-
- /* Wait for write-capable */
- for (i = 0; i < 1000000; i++) {
- if (LM4_HIBERNATE_HIBCTL & LM4_HIBCTL_WRC)
- return EC_SUCCESS;
- }
- return EC_ERROR_TIMEOUT;
-}
-
-/**
- * Read hibernate register at specified index.
- *
- * @return The value of the register or 0 if invalid index.
- */
-static uint32_t hibdata_read(enum hibdata_index index)
-{
- if (index < 0 || index >= LM4_HIBERNATE_HIBDATA_ENTRIES)
- return 0;
-
- return LM4_HIBERNATE_HIBDATA[index];
-}
-
-/**
- * Write hibernate register at specified index.
- *
- * @return nonzero if error.
- */
-static int hibdata_write(enum hibdata_index index, uint32_t value)
-{
- int rv;
-
- if (index < 0 || index >= LM4_HIBERNATE_HIBDATA_ENTRIES)
- return EC_ERROR_INVAL;
-
- /* Wait for ok-to-write */
- rv = wait_for_hibctl_wc();
- if (rv != EC_SUCCESS)
- return rv;
-
- /* Write register */
- LM4_HIBERNATE_HIBDATA[index] = value;
-
- /* Wait for write-complete */
- return wait_for_hibctl_wc();
-}
-
-uint32_t chip_read_reset_flags(void)
-{
- return hibdata_read(HIBDATA_INDEX_SAVED_RESET_FLAGS);
-}
-
-void chip_save_reset_flags(uint32_t flags)
-{
- hibdata_write(HIBDATA_INDEX_SAVED_RESET_FLAGS, flags);
-}
-
-static void check_reset_cause(void)
-{
- uint32_t hib_status = LM4_HIBERNATE_HIBRIS;
- uint32_t raw_reset_cause = LM4_SYSTEM_RESC;
- uint32_t hib_wake_flags = hibdata_read(HIBDATA_INDEX_WAKE);
- uint32_t flags = 0;
-
- /* Clear the reset causes now that we've read them */
- LM4_SYSTEM_RESC = 0;
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIC = hib_status;
- hibdata_write(HIBDATA_INDEX_WAKE, 0);
-
- if (raw_reset_cause & 0x02) {
- /*
- * Full power-on reset of chip. This resets the flash
- * protection registers to their permanently-stored values.
- * Note that this is also triggered by hibernation, because
- * that de-powers the chip.
- */
- flags |= EC_RESET_FLAG_POWER_ON;
- } else if (!flags && (raw_reset_cause & 0x01)) {
- /*
- * LM4 signals the reset pin in RESC for all power-on resets,
- * even though the external pin wasn't asserted. Make setting
- * this flag mutually-exclusive with power on flag, so we can
- * use it to indicate a keyboard-triggered reset.
- */
- flags |= EC_RESET_FLAG_RESET_PIN;
- }
-
- if (raw_reset_cause & 0x04)
- flags |= EC_RESET_FLAG_BROWNOUT;
-
- if (raw_reset_cause & 0x10)
- flags |= EC_RESET_FLAG_SOFT;
-
- if (raw_reset_cause & 0x28) {
- /* Watchdog timer 0 or 1 */
- flags |= EC_RESET_FLAG_WATCHDOG;
- }
-
- /* Handle other raw reset causes */
- if (raw_reset_cause && !flags)
- flags |= EC_RESET_FLAG_OTHER;
-
-
- if ((hib_status & 0x09) &&
- (hib_wake_flags & HIBDATA_WAKE_HARD_RESET)) {
- /* Hibernation caused by software-triggered hard reset */
- flags |= EC_RESET_FLAG_HARD;
-
- /* Consume the hibernate reasons so we don't see them below */
- hib_status &= ~0x09;
- }
-
- if ((hib_status & 0x01) && (hib_wake_flags & HIBDATA_WAKE_RTC))
- flags |= EC_RESET_FLAG_RTC_ALARM;
-
- if ((hib_status & 0x08) && (hib_wake_flags & HIBDATA_WAKE_PIN))
- flags |= EC_RESET_FLAG_WAKE_PIN;
-
- if (hib_status & 0x04)
- flags |= EC_RESET_FLAG_LOW_BATTERY;
-
- /* Restore then clear saved reset flags */
- flags |= chip_read_reset_flags();
- chip_save_reset_flags(0);
-
- system_set_reset_flags(flags);
-}
-
-/*
- * A3 and earlier chip stepping has a problem accessing flash during shutdown.
- * To work around that, we jump to RAM before hibernating. This function must
- * live in RAM. It must be called with interrupts disabled, cannot call other
- * functions, and can't be declared static (or else the compiler optimizes it
- * into the main hibernate function.
- */
-void __attribute__((noinline)) __attribute__((section(".iram.text")))
-__enter_hibernate(int hibctl)
-{
- LM4_HIBERNATE_HIBCTL = hibctl;
- while (1)
- ;
-}
-
-/**
- * Read the real-time clock.
- *
- * @param ss_ptr Destination for sub-seconds value, if not null.
- *
- * @return the real-time clock seconds value.
- */
-uint32_t system_get_rtc_sec_subsec(uint32_t *ss_ptr)
-{
- uint32_t rtc, rtc2;
- uint32_t rtcss, rtcss2;
-
- /*
- * The hibernate module isn't synchronized, so need to read repeatedly
- * to guarantee a valid read.
- */
- do {
- rtc = LM4_HIBERNATE_HIBRTCC;
- rtcss = LM4_HIBERNATE_HIBRTCSS & 0x7fff;
- rtcss2 = LM4_HIBERNATE_HIBRTCSS & 0x7fff;
- rtc2 = LM4_HIBERNATE_HIBRTCC;
- } while (rtc != rtc2 || rtcss != rtcss2);
-
- if (ss_ptr)
- *ss_ptr = rtcss;
-
- return rtc;
-}
-
-timestamp_t system_get_rtc(void)
-{
- uint32_t rtc, rtc_ss;
- timestamp_t time;
-
- rtc = system_get_rtc_sec_subsec(&rtc_ss);
-
- time.val = ((uint64_t)rtc) * SECOND + HIB_RTC_SUBSEC_TO_USEC(rtc_ss);
- return time;
-}
-
-/**
- * Set the real-time clock.
- *
- * @param seconds New clock value.
- */
-void system_set_rtc(uint32_t seconds)
-{
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBRTCLD = seconds;
- wait_for_hibctl_wc();
-}
-
-/**
- * Set the hibernate RTC match time at a given time from now
- *
- * @param seconds Number of seconds from now for RTC match
- * @param microseconds Number of microseconds from now for RTC match
- */
-static void set_hibernate_rtc_match_time(uint32_t seconds,
- uint32_t microseconds)
-{
- uint32_t rtc, rtcss;
-
- /*
- * Make sure that the requested delay is not less then the
- * amount of time it takes to set the RTC match registers,
- * otherwise, the match event could be missed.
- */
- if (seconds == 0 && microseconds < HIB_SET_RTC_MATCH_DELAY_USEC)
- microseconds = HIB_SET_RTC_MATCH_DELAY_USEC;
-
- /* Calculate the wake match */
- rtc = system_get_rtc_sec_subsec(&rtcss) + seconds;
- rtcss += HIB_RTC_USEC_TO_SUBSEC(microseconds);
- if (rtcss > 0x7fff) {
- rtc += rtcss >> 15;
- rtcss &= 0x7fff;
- }
-
- /* Set RTC alarm match */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBRTCM0 = rtc;
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBRTCSS = rtcss << 16;
- wait_for_hibctl_wc();
-}
-
-/**
- * Use hibernate module to set up an RTC interrupt at a given
- * time from now
- *
- * @param seconds Number of seconds before RTC interrupt
- * @param microseconds Number of microseconds before RTC interrupt
- */
-void system_set_rtc_alarm(uint32_t seconds, uint32_t microseconds)
-{
- /* Clear pending interrupt */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIC = LM4_HIBERNATE_HIBRIS;
-
- /* Set match time */
- set_hibernate_rtc_match_time(seconds, microseconds);
-
- /* Enable RTC interrupt on match */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIM = 1;
-
- /*
- * Wait for the write to commit. This ensures that the RTC interrupt
- * actually gets enabled. This is important if we're about to switch
- * the system to the 30 kHz oscillator, which might prevent the write
- * from committing.
- */
- wait_for_hibctl_wc();
-}
-
-/**
- * Disable and clear the RTC interrupt.
- */
-void system_reset_rtc_alarm(void)
-{
- /* Disable hibernate interrupts */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIM = 0;
-
- /* Clear interrupts */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIC = LM4_HIBERNATE_HIBRIS;
-}
-
-/**
- * Hibernate module interrupt
- */
-void __hibernate_irq(void)
-{
- system_reset_rtc_alarm();
-}
-DECLARE_IRQ(LM4_IRQ_HIBERNATE, __hibernate_irq, 1);
-
-/**
- * Enable hibernate interrupt
- */
-void system_enable_hib_interrupt(void)
-{
- task_enable_irq(LM4_IRQ_HIBERNATE);
-}
-
-/**
- * Internal hibernate function.
- *
- * @param seconds Number of seconds to sleep before RTC alarm
- * @param microseconds Number of microseconds to sleep before RTC alarm
- * @param flags Additional hibernate wake flags
- */
-static void hibernate(uint32_t seconds, uint32_t microseconds, uint32_t flags)
-{
- uint32_t hibctl;
-
- /* Set up wake reasons and hibernate flags */
- hibctl = LM4_HIBERNATE_HIBCTL | LM4_HIBCTL_PINWEN;
-
- if (flags & HIBDATA_WAKE_PIN)
- hibctl |= LM4_HIBCTL_PINWEN;
- else
- hibctl &= ~LM4_HIBCTL_PINWEN;
-
- if (seconds || microseconds) {
- hibctl |= LM4_HIBCTL_RTCWEN;
- flags |= HIBDATA_WAKE_RTC;
-
- set_hibernate_rtc_match_time(seconds, microseconds);
-
- /* Enable RTC interrupt on match */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIM = 1;
- } else {
- hibctl &= ~LM4_HIBCTL_RTCWEN;
- }
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBCTL = hibctl;
-
- /* Clear pending interrupt */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIC = LM4_HIBERNATE_HIBRIS;
-
- /* Store hibernate flags */
- hibdata_write(HIBDATA_INDEX_WAKE, flags);
-
- __enter_hibernate(hibctl | LM4_HIBCTL_HIBREQ);
-}
-
-void system_hibernate(uint32_t seconds, uint32_t microseconds)
-{
- /* Flush console before hibernating */
- cflush();
- hibernate(seconds, microseconds, HIBDATA_WAKE_PIN);
-}
-
-void chip_pre_init(void)
-{
- /* Enable clocks to GPIO block C in run and sleep modes. */
- clock_enable_peripheral(CGC_OFFSET_GPIO, 0x0004, CGC_MODE_ALL);
-
- /*
- * Ensure PC0:3 are set to JTAG function. They should be set this way
- * on a cold boot, but on a warm reboot a previous misbehaving image
- * could have set them differently.
- */
- if (((LM4_GPIO_PCTL(LM4_GPIO_C) & 0x0000ffff) == 0x00001111) &&
- ((LM4_GPIO_AFSEL(LM4_GPIO_C) & 0x0f) == 0x0f) &&
- ((LM4_GPIO_DEN(LM4_GPIO_C) & 0x0f) == 0x0f) &&
- ((LM4_GPIO_PUR(LM4_GPIO_C) & 0x0f) == 0x0f))
- return; /* Already properly configured */
-
- /* Unlock commit register for JTAG pins */
- LM4_GPIO_LOCK(LM4_GPIO_C) = LM4_GPIO_LOCK_UNLOCK;
- LM4_GPIO_CR(LM4_GPIO_C) |= 0x0f;
-
- /* Reset JTAG pins */
- LM4_GPIO_PCTL(LM4_GPIO_C) =
- (LM4_GPIO_PCTL(LM4_GPIO_C) & 0xffff0000) | 0x00001111;
- LM4_GPIO_AFSEL(LM4_GPIO_C) |= 0x0f;
- LM4_GPIO_DEN(LM4_GPIO_C) |= 0x0f;
- LM4_GPIO_PUR(LM4_GPIO_C) |= 0x0f;
-
- /* Set interrupt on either edge of the JTAG signals */
- LM4_GPIO_IS(LM4_GPIO_C) &= ~0x0f;
- LM4_GPIO_IBE(LM4_GPIO_C) |= 0x0f;
-
- /* Re-lock commit register */
- LM4_GPIO_CR(LM4_GPIO_C) &= ~0x0f;
- LM4_GPIO_LOCK(LM4_GPIO_C) = 0;
-}
-
-void system_pre_init(void)
-{
- uint32_t hibctl;
-#ifdef CONFIG_SOFTWARE_PANIC
- uint32_t reason, info;
- uint8_t exception, panic_flags;
-#endif
-
- /*
- * Enable clocks to the hibernation module in run, sleep,
- * and deep sleep modes.
- */
- clock_enable_peripheral(CGC_OFFSET_HIB, 0x1, CGC_MODE_ALL);
-
- /*
- * Enable the hibernation oscillator, if it's not already enabled.
- * This should only need setting if the EC completely lost power (for
- * example, the battery was pulled).
- */
- if (!(LM4_HIBERNATE_HIBCTL & LM4_HIBCTL_CLK32EN)) {
- int i;
-
- /* Enable clock to hibernate module */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBCTL |= LM4_HIBCTL_CLK32EN;
-
- /* Wait for write-complete */
- for (i = 0; i < 1000000; i++) {
- if (LM4_HIBERNATE_HIBRIS & 0x10)
- break;
- }
-
- /* Enable and reset RTC */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBCTL |= LM4_HIBCTL_RTCEN;
- system_set_rtc(0);
-
- /* Clear all hibernate data entries */
- for (i = 0; i < LM4_HIBERNATE_HIBDATA_ENTRIES; i++)
- hibdata_write(i, 0);
- }
-
- /*
- * Set wake reasons to RTC match and WAKE pin by default.
- * Before going in to hibernate, these may change.
- */
- hibctl = LM4_HIBERNATE_HIBCTL;
- hibctl |= LM4_HIBCTL_RTCWEN;
- hibctl |= LM4_HIBCTL_PINWEN;
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBCTL = hibctl;
-
- /*
- * Initialize registers after reset to work around LM4 chip errata
- * (still present in A3 chip stepping).
- */
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBRTCT = 0x7fff;
- wait_for_hibctl_wc();
- LM4_HIBERNATE_HIBIM = 0;
-
- check_reset_cause();
-
-#ifdef CONFIG_SOFTWARE_PANIC
- /* Restore then clear saved panic reason */
- reason = hibdata_read(HIBDATA_INDEX_SAVED_PANIC_REASON);
- info = hibdata_read(HIBDATA_INDEX_SAVED_PANIC_INFO);
- exception = hibdata_read(HIBDATA_INDEX_SAVED_PANIC_EXCEPTION);
- panic_flags = hibdata_read(HIBDATA_INDEX_SAVED_PANIC_FLAGS);
-
- if (reason || info || exception) {
- panic_set_reason(reason, info, exception);
- panic_get_data()->flags = panic_flags;
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_REASON, 0);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_INFO, 0);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_EXCEPTION, 0);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_FLAGS, 0);
- }
-#endif
-
- /* Initialize bootcfg if needed */
- if (LM4_SYSTEM_BOOTCFG != CONFIG_BOOTCFG_VALUE) {
- /* read-modify-write */
- LM4_FLASH_FMD = (LM4_SYSTEM_BOOTCFG_MASK & LM4_SYSTEM_BOOTCFG)
- | (~LM4_SYSTEM_BOOTCFG_MASK & CONFIG_BOOTCFG_VALUE);
- LM4_FLASH_FMA = 0x75100000;
- LM4_FLASH_FMC = 0xa4420008; /* WRKEY | COMT */
- while (LM4_FLASH_FMC & 0x08)
- ;
- }
-
- /* Brown-outs should trigger a reset */
- LM4_SYSTEM_PBORCTL |= 0x02;
-}
-
-void system_reset(int flags)
-{
- uint32_t save_flags = 0;
-
- /* Disable interrupts to avoid task swaps during reboot */
- interrupt_disable();
-
- /* Save current reset reasons if necessary */
- if (flags & SYSTEM_RESET_PRESERVE_FLAGS)
- save_flags = system_get_reset_flags() | EC_RESET_FLAG_PRESERVED;
-
- if (flags & SYSTEM_RESET_LEAVE_AP_OFF)
- save_flags |= EC_RESET_FLAG_AP_OFF;
-
- chip_save_reset_flags(save_flags);
-
- if (flags & SYSTEM_RESET_HARD) {
-#ifdef CONFIG_SOFTWARE_PANIC
- uint32_t reason, info;
- uint8_t exception, panic_flags;
-
- panic_flags = panic_get_data()->flags;
-
- /* Panic data will be wiped by hard reset, so save it */
- panic_get_reason(&reason, &info, &exception);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_REASON, reason);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_INFO, info);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_EXCEPTION, exception);
- hibdata_write(HIBDATA_INDEX_SAVED_PANIC_FLAGS, panic_flags);
-#endif
-
- /*
- * Bounce through hibernate to trigger a hard reboot. Do
- * not wake on wake pin, since we need the full duration.
- */
- hibernate(0, HIB_RESET_USEC, HIBDATA_WAKE_HARD_RESET);
- } else
- CPU_NVIC_APINT = 0x05fa0004;
-
- /* Spin and wait for reboot; should never return */
- while (1)
- ;
-}
-
-int system_set_scratchpad(uint32_t value)
-{
- return hibdata_write(HIBDATA_INDEX_SCRATCHPAD, value);
-}
-
-int system_get_scratchpad(uint32_t *value)
-{
- *value = hibdata_read(HIBDATA_INDEX_SCRATCHPAD);
- return EC_SUCCESS;
-}
-
-const char *system_get_chip_vendor(void)
-{
- return "ti";
-}
-
-static char to_hex(int x)
-{
- if (x >= 0 && x <= 9)
- return '0' + x;
- return 'a' + x - 10;
-}
-
-const char *system_get_chip_id_string(void)
-{
- static char str[15] = "Unknown-";
- char *p = str + 8;
- uint32_t did = LM4_SYSTEM_DID1 >> 16;
-
- if (*p)
- return (const char *)str;
-
- *p = to_hex(did >> 12);
- *(p + 1) = to_hex((did >> 8) & 0xf);
- *(p + 2) = to_hex((did >> 4) & 0xf);
- *(p + 3) = to_hex(did & 0xf);
- *(p + 4) = '\0';
-
- return (const char *)str;
-}
-
-const char *system_get_raw_chip_name(void)
-{
- switch ((LM4_SYSTEM_DID1 & 0xffff0000) >> 16) {
- case 0x10de:
- return "tm4e1g31h6zrb";
- case 0x10e2:
- return "lm4fsxhh5bb";
- case 0x10e3:
- return "lm4fs232h5bb";
- case 0x10e4:
- return "lm4fs99h5bb";
- case 0x10e6:
- return "lm4fs1ah5bb";
- case 0x10ea:
- return "lm4fs1gh5bb";
- default:
- return system_get_chip_id_string();
- }
-}
-
-const char *system_get_chip_name(void)
-{
- const char *postfix = "-tm"; /* test mode */
- static char str[20];
- const char *raw_chip_name = system_get_raw_chip_name();
- char *p = str;
-
- if (LM4_TEST_MODE_ENABLED) {
- /* Debug mode is enabled. Postfix chip name. */
- while (*raw_chip_name)
- *(p++) = *(raw_chip_name++);
- while (*postfix)
- *(p++) = *(postfix++);
- *p = '\0';
- return (const char *)str;
- } else {
- return raw_chip_name;
- }
-}
-
-int system_get_bbram(enum system_bbram_idx idx, uint8_t *value)
-{
- return EC_ERROR_UNIMPLEMENTED;
-}
-
-int system_set_bbram(enum system_bbram_idx idx, uint8_t value)
-{
- return EC_ERROR_UNIMPLEMENTED;
-}
-
-const char *system_get_chip_revision(void)
-{
- static char rev[3];
-
- /* Extract the major[15:8] and minor[7:0] revisions. */
- rev[0] = 'A' + ((LM4_SYSTEM_DID0 >> 8) & 0xff);
- rev[1] = '0' + (LM4_SYSTEM_DID0 & 0xff);
- rev[2] = 0;
-
- return rev;
-}
-
-/*****************************************************************************/
-/* Console commands */
-void print_system_rtc(enum console_channel ch)
-{
- uint32_t rtc;
- uint32_t rtcss;
-
- rtc = system_get_rtc_sec_subsec(&rtcss);
- cprintf(ch, "RTC: 0x%08x.%04x (%d.%06d s)\n",
- rtc, rtcss, rtc, HIB_RTC_SUBSEC_TO_USEC(rtcss));
-}
-
-#ifdef CONFIG_CMD_RTC
-static int command_system_rtc(int argc, char **argv)
-{
- if (argc == 3 && !strcasecmp(argv[1], "set")) {
- char *e;
- uint32_t t = strtoi(argv[2], &e, 0);
- if (*e)
- return EC_ERROR_PARAM2;
-
- system_set_rtc(t);
- } else if (argc > 1) {
- return EC_ERROR_INVAL;
- }
-
- print_system_rtc(CC_COMMAND);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(rtc, command_system_rtc,
- "[set <seconds>]",
- "Get/set real-time clock");
-
-#ifdef CONFIG_CMD_RTC_ALARM
-/**
- * Test the RTC alarm by setting an interrupt on RTC match.
- */
-static int command_rtc_alarm_test(int argc, char **argv)
-{
- int s = 1, us = 0;
- char *e;
-
- ccprintf("Setting RTC alarm\n");
- system_enable_hib_interrupt();
-
- if (argc > 1) {
- s = strtoi(argv[1], &e, 10);
- if (*e)
- return EC_ERROR_PARAM1;
-
- }
- if (argc > 2) {
- us = strtoi(argv[2], &e, 10);
- if (*e)
- return EC_ERROR_PARAM2;
-
- }
-
- system_set_rtc_alarm(s, us);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(rtc_alarm, command_rtc_alarm_test,
- "[seconds [microseconds]]",
- "Test alarm");
-#endif /* CONFIG_CMD_RTC_ALARM */
-#endif /* CONFIG_CMD_RTC */
-
-/*****************************************************************************/
-/* Host commands */
-
-#ifdef CONFIG_HOSTCMD_RTC
-static enum ec_status system_rtc_get_value(struct host_cmd_handler_args *args)
-{
- struct ec_response_rtc *r = args->response;
-
- r->time = system_get_rtc_sec_subsec(NULL);
- args->response_size = sizeof(*r);
-
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_GET_VALUE,
- system_rtc_get_value,
- EC_VER_MASK(0));
-
-static enum ec_status system_rtc_set_value(struct host_cmd_handler_args *args)
-{
- const struct ec_params_rtc *p = args->params;
-
- system_set_rtc(p->time);
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_SET_VALUE,
- system_rtc_set_value,
- EC_VER_MASK(0));
-#endif /* CONFIG_HOSTCMD_RTC */
diff --git a/chip/lm4/uart.c b/chip/lm4/uart.c
deleted file mode 100644
index 7ccea9eb75..0000000000
--- a/chip/lm4/uart.c
+++ /dev/null
@@ -1,352 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* UART module for Chrome EC */
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "gpio.h"
-#include "lpc.h"
-#include "registers.h"
-#include "system.h"
-#include "task.h"
-#include "uart.h"
-#include "util.h"
-
-#ifdef CONFIG_UART_HOST
-#define IRQ_UART_HOST CONCAT2(LM4_IRQ_UART, CONFIG_UART_HOST)
-#endif
-
-static int init_done;
-
-int uart_init_done(void)
-{
- return init_done;
-}
-
-void uart_tx_start(void)
-{
- /* If interrupt is already enabled, nothing to do */
- if (LM4_UART_IM(0) & 0x20)
- return;
-
- /* Do not allow deep sleep while transmit in progress */
- disable_sleep(SLEEP_MASK_UART);
-
- /*
- * Re-enable the transmit interrupt, then forcibly trigger the
- * interrupt. This works around a hardware problem with the
- * UART where the FIFO only triggers the interrupt when its
- * threshold is _crossed_, not just met.
- */
- LM4_UART_IM(0) |= 0x20;
- task_trigger_irq(LM4_IRQ_UART0);
-}
-
-void uart_tx_stop(void)
-{
- LM4_UART_IM(0) &= ~0x20;
-
- /* Re-allow deep sleep */
- enable_sleep(SLEEP_MASK_UART);
-}
-
-void uart_tx_flush(void)
-{
- /* Wait for transmit FIFO empty */
- while (!(LM4_UART_FR(0) & 0x80))
- ;
-}
-
-int uart_tx_ready(void)
-{
- return !(LM4_UART_FR(0) & 0x20);
-}
-
-int uart_tx_in_progress(void)
-{
- /* Transmit is in progress if the TX busy bit is set. */
- return LM4_UART_FR(0) & 0x08;
-}
-
-int uart_rx_available(void)
-{
- return !(LM4_UART_FR(0) & 0x10);
-}
-
-void uart_write_char(char c)
-{
- /* Wait for space in transmit FIFO. */
- while (!uart_tx_ready())
- ;
-
- LM4_UART_DR(0) = c;
-}
-
-int uart_read_char(void)
-{
- return LM4_UART_DR(0);
-}
-
-static void uart_clear_rx_fifo(int channel)
-{
- int scratch __attribute__ ((unused));
- while (!(LM4_UART_FR(channel) & 0x10))
- scratch = LM4_UART_DR(channel);
-}
-
-/**
- * Interrupt handler for UART0
- */
-void uart_ec_interrupt(void)
-{
- /* Clear transmit and receive interrupt status */
- LM4_UART_ICR(0) = 0x70;
-
-
- /* Read input FIFO until empty, then fill output FIFO */
- uart_process_input();
- uart_process_output();
-}
-DECLARE_IRQ(LM4_IRQ_UART0, uart_ec_interrupt, 1);
-
-#ifdef CONFIG_UART_HOST
-
-/**
- * Interrupt handler for Host UART
- */
-void uart_host_interrupt(void)
-{
- /* Clear transmit and receive interrupt status */
- LM4_UART_ICR(CONFIG_UART_HOST) = 0x70;
-
-#ifdef CONFIG_HOSTCMD_LPC
- /*
- * If we have space in our FIFO and a character is pending in LPC,
- * handle that character.
- */
- if (!(LM4_UART_FR(CONFIG_UART_HOST) & 0x20) && lpc_comx_has_char()) {
- /* Copy the next byte then disable transmit interrupt */
- LM4_UART_DR(CONFIG_UART_HOST) = lpc_comx_get_char();
- LM4_UART_IM(CONFIG_UART_HOST) &= ~0x20;
- }
-
- /*
- * Handle received character. There is no flow control on input;
- * received characters are blindly forwarded to LPC. This is ok
- * because LPC is much faster than UART, and we don't have flow control
- * on the UART receive-side either.
- */
- if (!(LM4_UART_FR(CONFIG_UART_HOST) & 0x10))
- lpc_comx_put_char(LM4_UART_DR(CONFIG_UART_HOST));
-#endif
-}
-/* Must be same prio as LPC interrupt handler so they don't preempt */
-DECLARE_IRQ(IRQ_UART_HOST, uart_host_interrupt, 2);
-
-#endif /* CONFIG_UART_HOST */
-
-static void uart_config(int port)
-{
- /* Disable the port */
- LM4_UART_CTL(port) = 0x0300;
- /* Use the internal oscillator */
- LM4_UART_CC(port) = 0x1;
- /* Set the baud rate divisor */
- LM4_UART_IBRD(port) = (INTERNAL_CLOCK / 16) / CONFIG_UART_BAUD_RATE;
- LM4_UART_FBRD(port) =
- (((INTERNAL_CLOCK / 16) % CONFIG_UART_BAUD_RATE) * 64
- + CONFIG_UART_BAUD_RATE / 2) / CONFIG_UART_BAUD_RATE;
- /*
- * 8-N-1, FIFO enabled. Must be done after setting
- * the divisor for the new divisor to take effect.
- */
- LM4_UART_LCRH(port) = 0x70;
- /*
- * Interrupt when RX fifo at minimum (>= 1/8 full), and TX fifo
- * when <= 1/4 full
- */
- LM4_UART_IFLS(port) = 0x01;
- /*
- * Unmask receive-FIFO, receive-timeout. We need
- * receive-timeout because the minimum RX FIFO depth is 1/8 = 2
- * bytes; without the receive-timeout we'd never be notified
- * about single received characters.
- */
- LM4_UART_IM(port) = 0x50;
- /* Enable the port */
- LM4_UART_CTL(port) |= 0x0001;
-}
-
-void uart_init(void)
-{
- uint32_t mask = 0;
-
- /*
- * Enable UART0 in run, sleep, and deep sleep modes. Enable the Host
- * UART in run and sleep modes.
- */
- mask |= 1;
- clock_enable_peripheral(CGC_OFFSET_UART, mask, CGC_MODE_ALL);
-
-#ifdef CONFIG_UART_HOST
- mask |= BIT(CONFIG_UART_HOST);
-#endif
-
- clock_enable_peripheral(CGC_OFFSET_UART, mask,
- CGC_MODE_RUN | CGC_MODE_SLEEP);
-
- gpio_config_module(MODULE_UART, 1);
-
- /* Configure UARTs (identically) */
- uart_config(0);
-
-#ifdef CONFIG_UART_HOST
- uart_config(CONFIG_UART_HOST);
-#endif
-
- /*
- * Enable interrupts for UART0 only. Host UART will have to wait
- * until the LPC bus is initialized.
- */
- uart_clear_rx_fifo(0);
- task_enable_irq(LM4_IRQ_UART0);
-
- init_done = 1;
-}
-
-#ifdef CONFIG_LOW_POWER_IDLE
-void uart_enter_dsleep(void)
-{
- const struct gpio_info g = gpio_list[GPIO_UART0_RX];
-
- /* Disable the UART0 module interrupt. */
- task_disable_irq(LM4_IRQ_UART0);
-
- /* Disable UART0 peripheral in deep sleep. */
- clock_disable_peripheral(CGC_OFFSET_UART, 0x1, CGC_MODE_DSLEEP);
-
- /*
- * Set the UART0 RX pin to be a generic GPIO with the flags defined
- * in the board.c file.
- */
- gpio_reset(GPIO_UART0_RX);
-
- /* Clear any pending GPIO interrupts on the UART0 RX pin. */
- LM4_GPIO_ICR(g.port) = g.mask;
-
- /* Enable GPIO interrupts on the UART0 RX pin. */
- gpio_enable_interrupt(GPIO_UART0_RX);
-}
-
-void uart_exit_dsleep(void)
-{
- const struct gpio_info g = gpio_list[GPIO_UART0_RX];
-
- /*
- * If the UART0 RX GPIO interrupt has not fired, then no edge has been
- * detected. Disable the GPIO interrupt so that switching the pin over
- * to a UART pin doesn't inadvertently cause a GPIO edge interrupt.
- * Note: we can't disable this interrupt if it has already fired
- * because then the IRQ will not get called.
- */
- if (!(LM4_GPIO_MIS(g.port) & g.mask))
- gpio_disable_interrupt(GPIO_UART0_RX);
-
- /* Configure UART0 pins for use in UART peripheral. */
- gpio_config_module(MODULE_UART, 1);
-
- /* Clear pending interrupts on UART peripheral and enable interrupts. */
- uart_clear_rx_fifo(0);
- task_enable_irq(LM4_IRQ_UART0);
-
- /* Enable UART0 peripheral in deep sleep */
- clock_enable_peripheral(CGC_OFFSET_UART, 0x1, CGC_MODE_DSLEEP);
-}
-
-void uart_deepsleep_interrupt(enum gpio_signal signal)
-{
- /*
- * Activity seen on UART RX pin while UART was disabled for deep sleep.
- * The console won't see that character because the UART is disabled,
- * so we need to inform the clock module of UART activity ourselves.
- */
- clock_refresh_console_in_use();
-
- /* Disable interrupts on UART0 RX pin to avoid repeated interrupts. */
- gpio_disable_interrupt(GPIO_UART0_RX);
-}
-#endif /* CONFIG_LOW_POWER_IDLE */
-
-
-/*****************************************************************************/
-/* COMx functions */
-
-#ifdef CONFIG_UART_HOST
-
-void uart_comx_enable(void)
-{
- uart_clear_rx_fifo(CONFIG_UART_HOST);
- task_enable_irq(IRQ_UART_HOST);
-}
-
-int uart_comx_putc_ok(void)
-{
- if (LM4_UART_FR(CONFIG_UART_HOST) & 0x20) {
- /*
- * FIFO is full, so enable transmit interrupt to let us know
- * when it empties.
- */
- LM4_UART_IM(CONFIG_UART_HOST) |= 0x20;
- return 0;
- } else {
- return 1;
- }
-}
-
-void uart_comx_putc(int c)
-{
- LM4_UART_DR(CONFIG_UART_HOST) = c;
-}
-
-#endif /* CONFIG_UART_HOST */
-
-/*****************************************************************************/
-/* Console commands */
-
-#ifdef CONFIG_CMD_COMXTEST
-
-/**
- * Write a character to COMx, waiting for space in the output buffer if
- * necessary.
- */
-static void uart_comx_putc_wait(int c)
-{
- while (!uart_comx_putc_ok())
- ;
- uart_comx_putc(c);
-}
-
-static int command_comxtest(int argc, char **argv)
-{
- /* Put characters to COMX port */
- const char *c = argc > 1 ? argv[1] : "testing comx output!";
-
- ccprintf("Writing \"%s\\r\\n\" to COMx UART...\n", c);
-
- while (*c)
- uart_comx_putc_wait(*c++);
-
- uart_comx_putc_wait('\r');
- uart_comx_putc_wait('\n');
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(comxtest, command_comxtest,
- "[string]",
- "Write test data to COMx uart");
-
-#endif /* CONFIG_CMD_COMXTEST */
diff --git a/chip/lm4/watchdog.c b/chip/lm4/watchdog.c
deleted file mode 100644
index 50f122bf02..0000000000
--- a/chip/lm4/watchdog.c
+++ /dev/null
@@ -1,120 +0,0 @@
-/* Copyright 2012 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.
- */
-
-/* Watchdog driver */
-
-#include "clock.h"
-#include "common.h"
-#include "registers.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "task.h"
-#include "util.h"
-#include "watchdog.h"
-
-/*
- * We use watchdog 0 which is clocked on the system clock
- * to avoid the penalty cycles on each write access
- */
-
-/* magic value to unlock the watchdog registers */
-#define LM4_WATCHDOG_MAGIC_WORD 0x1ACCE551
-
-static uint32_t watchdog_period; /* Watchdog counter initial value */
-
-void IRQ_HANDLER(LM4_IRQ_WATCHDOG)(void) __attribute__((naked));
-void IRQ_HANDLER(LM4_IRQ_WATCHDOG)(void)
-{
- /* Naked call so we can extract raw LR and SP */
- asm volatile("mov r0, lr\n"
- "mov r1, sp\n"
- /* Must push registers in pairs to keep 64-bit aligned
- * stack for ARM EABI. This also conveniently saves
- * R0=LR so we can pass it to task_resched_if_needed. */
- "push {r0, lr}\n"
- "bl watchdog_trace\n"
- /* Do NOT reset the watchdog interrupt here; it will
- * be done in watchdog_reload(), or reset will be
- * triggered if we don't call that by the next watchdog
- * period. Instead, de-activate the interrupt in the
- * NVIC, so the watchdog trace will only be printed
- * once.
- */
- "mov r0, %[irq]\n"
- "bl task_disable_irq\n"
- "pop {r0, lr}\n"
- "b task_resched_if_needed\n"
- : : [irq] "i" (LM4_IRQ_WATCHDOG));
-}
-const struct irq_priority __keep IRQ_PRIORITY(LM4_IRQ_WATCHDOG)
- __attribute__((section(".rodata.irqprio")))
- = {LM4_IRQ_WATCHDOG, 0}; /* put the watchdog at the highest
- priority */
-
-void watchdog_reload(void)
-{
- uint32_t status = LM4_WATCHDOG_RIS(0);
-
- /* Unlock watchdog registers */
- LM4_WATCHDOG_LOCK(0) = LM4_WATCHDOG_MAGIC_WORD;
-
- /* As we reboot only on the second timeout, if we have already reached
- * the first timeout we need to reset the interrupt bit. */
- if (status) {
- LM4_WATCHDOG_ICR(0) = status;
- /* That doesn't seem to unpend the watchdog interrupt (even if
- * we do writes to force the write to be committed), so
- * explicitly unpend the interrupt before re-enabling it. */
- task_clear_pending_irq(LM4_IRQ_WATCHDOG);
- task_enable_irq(LM4_IRQ_WATCHDOG);
- }
-
- /* Reload the watchdog counter */
- LM4_WATCHDOG_LOAD(0) = watchdog_period;
-
- /* Re-lock watchdog registers */
- LM4_WATCHDOG_LOCK(0) = 0xdeaddead;
-}
-DECLARE_HOOK(HOOK_TICK, watchdog_reload, HOOK_PRIO_DEFAULT);
-
-static void watchdog_freq_changed(void)
-{
- /* Set the timeout period */
- watchdog_period = CONFIG_WATCHDOG_PERIOD_MS * (clock_get_freq() / 1000);
-
- /* Reload the watchdog timer now */
- watchdog_reload();
-}
-DECLARE_HOOK(HOOK_FREQ_CHANGE, watchdog_freq_changed, HOOK_PRIO_DEFAULT);
-
-int watchdog_init(void)
-{
- /* Enable watchdog 0 clock in run, sleep, and deep sleep modes */
- clock_enable_peripheral(CGC_OFFSET_WD, 0x1, CGC_MODE_ALL);
-
- /* Set initial timeout period */
- watchdog_freq_changed();
-
- /* Unlock watchdog registers */
- LM4_WATCHDOG_LOCK(0) = LM4_WATCHDOG_MAGIC_WORD;
-
- /* De-activate the watchdog when the JTAG stops the CPU */
- LM4_WATCHDOG_TEST(0) |= BIT(8);
-
- /* Reset after 2 time-out, activate the watchdog and lock the control
- * register. */
- LM4_WATCHDOG_CTL(0) = 0x3;
-
- /* Reset watchdog interrupt bits */
- LM4_WATCHDOG_ICR(0) = LM4_WATCHDOG_RIS(0);
-
- /* Lock watchdog registers against unintended accesses */
- LM4_WATCHDOG_LOCK(0) = 0xdeaddead;
-
- /* Enable watchdog interrupt */
- task_enable_irq(LM4_IRQ_WATCHDOG);
-
- return EC_SUCCESS;
-}