summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorScott Worley <scott.worley@microchip.corp-partner.google.com>2017-12-21 16:14:04 -0500
committerchrome-bot <chrome-bot@chromium.org>2018-02-08 23:41:17 -0800
commitbbbef02a6368fce9949860146363f8b433730fde (patch)
tree409a04840d7cf2a6de222dee6e1e427fdd5d9acc
parentd54cdec85b61f27f13bb6c089b5bd3fd05f014f2 (diff)
downloadchrome-ec-bbbef02a6368fce9949860146363f8b433730fde.tar.gz
mchpevb1: Add mchpevb1 board files
Add Microchip EVB plus SKL RVP3 main board files. BRANCH=none BUG= TEST=Review only. CQ-DEPEND=CL:840654,CL:841043 Change-Id: I2f3cc33989e911c464f761374c0d2d26b054b7d7 Signed-off-by: Scott Worley <scott.worley@microchip.corp-partner.google.com> Reviewed-on: https://chromium-review.googlesource.com/841022 Commit-Ready: Randall Spangler <rspangler@chromium.org> Tested-by: Randall Spangler <rspangler@chromium.org> Reviewed-by: Randall Spangler <rspangler@chromium.org>
-rw-r--r--board/mchpevb1/board.c1080
-rw-r--r--board/mchpevb1/board.h502
2 files changed, 1582 insertions, 0 deletions
diff --git a/board/mchpevb1/board.c b/board/mchpevb1/board.c
new file mode 100644
index 0000000000..59d33572d3
--- /dev/null
+++ b/board/mchpevb1/board.c
@@ -0,0 +1,1080 @@
+/* Copyright 2017 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.
+ */
+
+/*
+ * Microchip Evaluation Board(EVB) with
+ * MEC1701H 144-pin processor card.
+ * EVB connected to Intel SKL RVP3 configured
+ * for eSPI with Kabylake silicon.
+ */
+
+#include "adc.h"
+#include "adc_chip.h"
+#include "als.h"
+#include "bd99992gw.h"
+#include "button.h"
+#include "charge_manager.h"
+#include "charge_state.h"
+#include "charger.h"
+#include "chipset.h"
+#include "console.h"
+#include "driver/als_opt3001.h"
+#include "driver/accel_kionix.h"
+#include "driver/accel_kx022.h"
+#include "driver/accelgyro_bmi160.h"
+#include "driver/tcpm/tcpci.h"
+#include "extpower.h"
+#include "gpio_chip.h"
+#include "gpio.h"
+#include "hooks.h"
+#include "host_command.h"
+#include "i2c.h"
+#include "espi.h"
+#include "lpc_chip.h"
+#include "keyboard_scan.h"
+#include "lid_switch.h"
+#include "math_util.h"
+#include "motion_sense.h"
+#include "motion_lid.h"
+#include "pi3usb9281.h"
+#include "power.h"
+#include "power_button.h"
+#include "spi.h"
+#include "spi_chip.h"
+#include "switch.h"
+#include "system.h"
+#include "task.h"
+#include "temp_sensor.h"
+#include "timer.h"
+#include "uart.h"
+#include "usb_charge.h"
+#include "usb_mux.h"
+#include "usb_pd.h"
+#include "usb_pd_tcpm.h"
+#include "util.h"
+#include "espi.h"
+#include "battery_smart.h"
+
+/* Console output macros */
+#define CPUTS(outstr) cputs(CC_LPC, outstr)
+#define CPRINTS(format, args...) cprints(CC_USBCHARGE, format, ## args)
+#define CPRINTF(format, args...) cprintf(CC_USBCHARGE, format, ## args)
+
+
+/* NOTE: MEC17xx EVB + SKL RVP3 does not use BD99992 PMIC.
+ * RVP3 PMIC controlled by RVP3 logic.
+ */
+#define I2C_ADDR_BD99992 0x60
+
+/*
+ * Maxim DS1624 I2C temperature sensor used for testing I2C.
+ * DS1624 contains one internal temperature sensor
+ * and EEPROM. It has no external temperature inputs.
+ */
+#define DS1624_I2C_ADDR 0x90 /* 7-bit address is 0x48 */
+#define DS1624_IDX_LOCAL 0
+#define DS1624_READ_TEMP16 0xAA /* read 16-bit temperature */
+#define DS1624_ACCESS_CFG 0xAC /* read/write 8-bit config */
+#define DS1624_CMD_START 0xEE
+#define DS1624_CMD_STOP 0x22
+
+/*
+ * static global and routine to return smart battery
+ * temperature when we do not build with charger task.
+ */
+static int smart_batt_temp;
+static int ds1624_temp;
+static int sb_temp(int idx, int *temp_ptr);
+static int ds1624_get_val(int idx, int *temp_ptr);
+#ifdef HAS_TASK_MOTIONSENSE
+static void board_spi_enable(void);
+static void board_spi_disable(void);
+#endif
+
+#ifdef CONFIG_BOARD_PRE_INIT
+/*
+ * Used to enable JTAG debug during development.
+ * NOTE: If ARM Serial Wire Viewer not used then SWV pin can be
+ * be disabled and used for another purpose. Change mode to
+ * MCHP_JTAG_MODE_SWD.
+ * For low power idle testing enable GPIO060 as function 2(48MHZ_OUT)
+ * to check PLL is turning off in heavy sleep. Note, do not put GPIO060
+ * in gpio.inc
+ * GPIO060 is port 1 bit[16].
+ */
+void board_config_pre_init(void)
+{
+ smart_batt_temp = 0;
+ ds1624_temp = 0;
+
+#ifdef CONFIG_CHIPSET_DEBUG
+ MCHP_EC_JTAG_EN = MCHP_JTAG_ENABLE + MCHP_JTAG_MODE_SWD_SWV;
+#endif
+
+#if defined(CONFIG_LOW_POWER_IDLE) && defined(CONFIG_MCHP_48MHZ_OUT)
+ gpio_set_alternate_function(1, 0x10000, 2);
+#endif
+}
+#endif /* #ifdef CONFIG_BOARD_PRE_INIT */
+
+
+/*
+ * Use EC to handle ALL_SYS_PWRGD signal.
+ * MEC17xx connected to SKL/KBL RVP3 reference board
+ * is required to monitor ALL_SYS_PWRGD and drive SYS_RESET_L
+ * after a 10 to 100 ms delay.
+ */
+#ifdef CONFIG_BOARD_EC_HANDLES_ALL_SYS_PWRGD
+
+static void board_all_sys_pwrgd(void)
+{
+ int allsys_in = gpio_get_level(GPIO_ALL_SYS_PWRGD);
+ int allsys_out = gpio_get_level(GPIO_SYS_RESET_L);
+
+ if (allsys_in == allsys_out)
+ return;
+
+ CPRINTS("ALL_SYS_PWRGD=%d SYS_RESET_L=%d", allsys_in, allsys_out);
+
+ trace2(0, BRD, 0, "ALL_SYS_PWRGD=%d SYS_RESET_L=%d",
+ allsys_in, allsys_out);
+
+ /*
+ * Wait at least 10 ms between power signals going high
+ */
+ if (allsys_in)
+ msleep(100);
+
+ if (!allsys_out) {
+ /* CPRINTS("Set SYS_RESET_L = %d", allsys_in); */
+ trace1(0, BRD, 0, "Set SYS_RESET_L=%d", allsys_in);
+ gpio_set_level(GPIO_SYS_RESET_L, allsys_in);
+ /* Force fan on for kabylake RVP */
+ gpio_set_level(GPIO_EC_FAN1_PWM, 1);
+ }
+}
+DECLARE_DEFERRED(board_all_sys_pwrgd);
+
+void all_sys_pwrgd_interrupt(enum gpio_signal signal)
+{
+ trace0(0, ISR, 0, "ALL_SYS_PWRGD Edge");
+ hook_call_deferred(&board_all_sys_pwrgd_data, 0);
+}
+#endif /* #ifdef CONFIG_BOARD_HAS_ALL_SYS_PWRGD */
+
+
+#ifdef HAS_TASK_PDCMD
+/* Exchange status with PD MCU. */
+static void pd_mcu_interrupt(enum gpio_signal signal)
+{
+ /* Exchange status with PD MCU to determine interrupt cause */
+ host_command_pd_send_status(0);
+
+}
+#endif
+
+#ifdef CONFIG_USB_POWER_DELIVERY
+void vbus0_evt(enum gpio_signal signal)
+{
+ /* VBUS present GPIO is inverted */
+ usb_charger_vbus_change(0, !gpio_get_level(signal));
+ task_wake(TASK_ID_PD_C0);
+}
+
+void vbus1_evt(enum gpio_signal signal)
+{
+ /* VBUS present GPIO is inverted */
+ usb_charger_vbus_change(1, !gpio_get_level(signal));
+ task_wake(TASK_ID_PD_C1);
+}
+
+void usb0_evt(enum gpio_signal signal)
+{
+ task_set_event(TASK_ID_USB_CHG_P0, USB_CHG_EVENT_BC12, 0);
+}
+
+void usb1_evt(enum gpio_signal signal)
+{
+ task_set_event(TASK_ID_USB_CHG_P1, USB_CHG_EVENT_BC12, 0);
+}
+#endif
+
+/*
+ * enable_input_devices() is called by the tablet_mode ISR, but changes the
+ * state of GPIOs, so its definition must reside after including gpio_list.
+ */
+static void enable_input_devices(void);
+DECLARE_DEFERRED(enable_input_devices);
+
+void tablet_mode_interrupt(enum gpio_signal signal)
+{
+ hook_call_deferred(&enable_input_devices_data, 0);
+}
+
+#include "gpio_list.h"
+
+/* power signal list. Must match order of enum power_signal. */
+const struct power_signal_info power_signal_list[] = {
+ {GPIO_RSMRST_L_PGOOD, POWER_SIGNAL_ACTIVE_HIGH, "RSMRST_N_PWRGD"},
+ {VW_SLP_S3_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_S3_DEASSERTED"},
+ {VW_SLP_S4_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_S4_DEASSERTED"},
+ {GPIO_PCH_SLP_SUS_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_SUS_DEASSERTED"},
+ {GPIO_PMIC_DPWROK, POWER_SIGNAL_ACTIVE_HIGH, "PMIC_DPWROK"},
+ {GPIO_ALL_SYS_PWRGD, POWER_SIGNAL_ACTIVE_HIGH, "ALL_SYS_PWRGD"}
+};
+BUILD_ASSERT(ARRAY_SIZE(power_signal_list) == POWER_SIGNAL_COUNT);
+
+/* ADC channels
+ * name, factor multiplier, factor divider, shift, channel
+ */
+const struct adc_t adc_channels[] = {
+ /* Vbus sensing. Converted to mV, full ADC is equivalent to 30V. */
+ [ADC_VBUS] = {"VBUS", 30000, 1024, 0, 1},
+ /* Adapter current output or battery discharging current */
+ [ADC_AMON_BMON] = {"AMON_BMON", 25000, 3072, 0, 3},
+ /* System current consumption */
+ [ADC_PSYS] = {"PSYS", 1, 1, 0, 4},
+ [ADC_CASE] = {"CASE", 1, 1, 0, 7},
+};
+BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
+
+/*
+ * MCHP EVB connected to KBL RVP3
+ */
+const struct i2c_port_t i2c_ports[] = {
+ {"sensors", MCHP_I2C_PORT4, 100, GPIO_SMB04_SCL, GPIO_SMB04_SDA},
+ {"batt", MCHP_I2C_PORT5, 100, GPIO_SMB05_SCL, GPIO_SMB05_SDA},
+};
+const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
+
+/*
+ * Map ports to controller.
+ * Ports may map to the same controller.
+ */
+const uint16_t i2c_port_to_ctrl[I2C_PORT_COUNT] = {
+ (MCHP_I2C_CTRL0 << 8) + MCHP_I2C_PORT4,
+ (MCHP_I2C_CTRL1 << 8) + MCHP_I2C_PORT5
+};
+
+/*
+ * default to I2C0 because callers may not check
+ * return value if we returned an error code.
+ */
+int board_i2c_p2c(int port)
+{
+ int i;
+
+ for (i = 0; i < I2C_PORT_COUNT; i++)
+ if ((i2c_port_to_ctrl[i] & 0xFF) == port)
+ return (int)(i2c_port_to_ctrl[i] >> 8);
+
+ return -1;
+}
+
+#ifdef CONFIG_USB_POWER_DELIVERY
+const struct tcpc_config_t tcpc_config[CONFIG_USB_PD_PORT_COUNT] = {
+ {I2C_PORT_TCPC, CONFIG_TCPC_I2C_BASE_ADDR, &tcpci_tcpm_drv},
+ {I2C_PORT_TCPC, CONFIG_TCPC_I2C_BASE_ADDR + 2, &tcpci_tcpm_drv},
+};
+#endif
+
+const uint32_t i2c_ctrl_slave_addrs[I2C_CONTROLLER_COUNT] = {
+#ifdef CONFIG_BOARD_MCHP_I2C0_SLAVE_ADDRS
+ (MCHP_I2C_CTRL0 + (CONFIG_BOARD_MCHP_I2C0_SLAVE_ADDRS << 16)),
+#else
+ (MCHP_I2C_CTRL0 + (CONFIG_MCHP_I2C0_SLAVE_ADDRS << 16)),
+#endif
+#ifdef CONFIG_BOARD_MCHP_I2C1_SLAVE_ADDRS
+ (MCHP_I2C_CTRL1 + (CONFIG_BOARD_MCHP_I2C1_SLAVE_ADDRS << 16)),
+#else
+ (MCHP_I2C_CTRL1 + (CONFIG_MCHP_I2C1_SLAVE_ADDRS << 16)),
+#endif
+};
+
+/* Return the two slave addresses the specified
+ * controller will respond to when controller
+ * is acting as a slave.
+ * b[6:0] = b[7:1] of I2C address 1
+ * b[14:8] = b[7:1] of I2C address 2
+ * When not using I2C controllers as slaves we can use
+ * the same value for all controllers. The address should
+ * not be 0x00 as this is the general call address.
+ */
+uint16_t board_i2c_slave_addrs(int controller)
+{
+ int i;
+
+ for (i = 0; i < I2C_CONTROLLER_COUNT; i++)
+ if ((i2c_ctrl_slave_addrs[i] & 0xffff) == controller)
+ return (i2c_ctrl_slave_addrs[i] >> 16);
+
+ return CONFIG_MCHP_I2C0_SLAVE_ADDRS;
+}
+
+
+/* SPI devices */
+const struct spi_device_t spi_devices[] = {
+ { QMSPI0_PORT, 4, GPIO_QMSPI_CS0},
+#if defined(CONFIG_SPI_ACCEL_PORT)
+ { GPSPI0_PORT, 2, GPIO_SPI0_CS0 },
+#endif
+};
+const unsigned int spi_devices_used = ARRAY_SIZE(spi_devices);
+
+const enum gpio_signal hibernate_wake_pins[] = {
+ GPIO_AC_PRESENT,
+ GPIO_LID_OPEN,
+ GPIO_POWER_BUTTON_L,
+};
+const int hibernate_wake_pins_used = ARRAY_SIZE(hibernate_wake_pins);
+
+
+/*
+ * Deep sleep support, called by chip level.
+ */
+#if defined(CONFIG_LOW_POWER_IDLE) && defined(CONFIG_BOARD_DEEP_SLEEP)
+
+/*
+ * Perform any board level prepare for sleep actions.
+ * For example, disabling pin/pads to further reduce
+ * current during sleep.
+ */
+void board_prepare_for_deep_sleep(void)
+{
+#if defined(CONFIG_GPIO_POWER_DOWN) && \
+ defined(CONFIG_MCHP_DEEP_SLP_GPIO_PWR_DOWN)
+ gpio_power_down_module(MODULE_SPI_FLASH);
+ gpio_power_down_module(MODULE_SPI_MASTER);
+ gpio_power_down_module(MODULE_I2C);
+ /* powering down keyscan is causing an issue with keyscan task
+ * probably due to spurious interrupts on keyscan pins.
+ * gpio_config_module(MODULE_KEYBOARD_SCAN, 0);
+ */
+
+#ifndef CONFIG_POWER_S0IX
+ gpio_power_down_module(MODULE_LPC);
+#endif
+#endif
+}
+
+/*
+ * Perform any board level resume from sleep actions.
+ * For example, re-enabling pins powered off in
+ * board_prepare_for_deep_sleep().
+ */
+void board_resume_from_deep_sleep(void)
+{
+#if defined(CONFIG_GPIO_POWER_DOWN) && \
+ defined(CONFIG_MCHP_DEEP_SLP_GPIO_PWR_DOWN)
+#ifndef CONFIG_POWER_S0IX
+ gpio_config_module(MODULE_LPC, 1);
+#endif
+ /* gpio_config_module(MODULE_KEYBOARD_SCAN, 1); */
+ gpio_config_module(MODULE_SPI_FLASH, 1);
+ gpio_config_module(MODULE_SPI_MASTER, 1);
+ gpio_config_module(MODULE_I2C, 1);
+#endif
+}
+#endif
+
+#ifdef CONFIG_USB_MUX_PI3USB30532
+struct pi3usb9281_config pi3usb9281_chips[] = {
+ {
+ .i2c_port = I2C_PORT_USB_CHARGER_1,
+ .mux_lock = NULL,
+ },
+ {
+ .i2c_port = I2C_PORT_USB_CHARGER_2,
+ .mux_lock = NULL,
+ },
+};
+BUILD_ASSERT(ARRAY_SIZE(pi3usb9281_chips) ==
+ CONFIG_BC12_DETECT_PI3USB9281_CHIP_COUNT);
+
+struct usb_mux usb_muxes[CONFIG_USB_PD_PORT_COUNT] = {
+ {
+ .port_addr = 0xa8,
+ .driver = &pi3usb30532_usb_mux_driver,
+ },
+ {
+ .port_addr = 0x20,
+ .driver = &ps874x_usb_mux_driver,
+ }
+};
+#endif
+
+/**
+ * Reset PD MCU
+ */
+void board_reset_pd_mcu(void)
+{
+ gpio_set_level(GPIO_PD_RST_L, 0);
+ usleep(100);
+ gpio_set_level(GPIO_PD_RST_L, 1);
+}
+
+/*
+ *
+ */
+static int therm_get_val(int idx, int *temp_ptr)
+{
+ if (temp_ptr != NULL) {
+ *temp_ptr = adc_read_channel(idx);
+ return EC_SUCCESS;
+ }
+
+ return EC_ERROR_PARAM2;
+}
+
+#ifdef CONFIG_TEMP_SENSOR
+#if 0 /* Chromebook design uses ADC in BD99992GW PMIC */
+const struct temp_sensor_t temp_sensors[] = {
+ {"Battery", TEMP_SENSOR_TYPE_BATTERY, charge_get_battery_temp, 0, 4},
+
+ /* These BD99992GW temp sensors are only readable in S0 */
+ {"Ambient", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM0, 4},
+ {"Charger", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM1, 4},
+ {"DRAM", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM2, 4},
+ {"Wifi", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM3, 4},
+};
+BUILD_ASSERT(ARRAY_SIZE(temp_sensors) == TEMP_SENSOR_COUNT);
+#else /* mec1701_evb test I2C and EC ADC */
+/*
+ * battery charge_get_battery_temp requires CONFIG_CHARGER_V2 and
+ * charger task running.
+ * OR can we call into driver/battery/smart.c
+ * int sb_read(int cmd, int *param)
+ * sb_read(SB_TEMPERATURE, &batt_new.temperature)
+ * Issue is functions in this table return a value from a memory array.
+ * There's a task or hook that is actually reading the temperature.
+ * We could implement a one second hook to call sb_read() and fill in
+ * a static global in this module.
+ */
+const struct temp_sensor_t temp_sensors[] = {
+ {"Battery", TEMP_SENSOR_TYPE_BATTERY, sb_temp, 0, 4},
+ {"Ambient", TEMP_SENSOR_TYPE_BOARD, ds1624_get_val, 0, 4},
+ {"Case", TEMP_SENSOR_TYPE_CASE, therm_get_val, (int)ADC_CASE, 4},
+};
+BUILD_ASSERT(ARRAY_SIZE(temp_sensors) == TEMP_SENSOR_COUNT);
+#endif
+#endif
+
+#ifdef CONFIG_ALS
+/* ALS instances. Must be in same order as enum als_id. */
+struct als_t als[] = {
+ {"TI", opt3001_init, opt3001_read_lux, 5},
+};
+BUILD_ASSERT(ARRAY_SIZE(als) == ALS_COUNT);
+#endif
+
+const struct button_config buttons[CONFIG_BUTTON_COUNT] = {
+ {"Volume Down", KEYBOARD_BUTTON_VOLUME_DOWN, GPIO_VOLUME_DOWN_L,
+ 30 * MSEC, 0},
+ {"Volume Up", KEYBOARD_BUTTON_VOLUME_UP, GPIO_VOLUME_UP_L,
+ 30 * MSEC, 0},
+};
+
+/* MCHP mec1701_evb connected to Intel SKL RVP3 with Kabylake
+ * processor we do not control the PMIC on SKL.
+ */
+static void board_pmic_init(void)
+{
+ int rv, cfg;
+
+ /* No need to re-init PMIC since settings are sticky across sysjump */
+ if (system_jumped_to_this_image())
+ return;
+
+#if 0 /* BD99992GW PMIC on a real Chromebook */
+ /* Set CSDECAYEN / VCCIO decays to 0V at assertion of SLP_S0# */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x30, 0x4a);
+
+ /*
+ * Set V100ACNT / V1.00A Control Register:
+ * Nominal output = 1.0V.
+ */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x37, 0x1a);
+
+ /*
+ * Set V085ACNT / V0.85A Control Register:
+ * Lower power mode = 0.7V.
+ * Nominal output = 1.0V.
+ */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x38, 0x7a);
+
+ /* VRMODECTRL - enable low-power mode for VCCIO and V0.85A */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x3b, 0x18);
+#else
+ CPRINTS("HOOK_INIT - called board_pmic_init");
+ trace0(0, HOOK, 0, "HOOK_INIT - call board_pmic_init");
+
+ /* Config DS1624 temperature sensor for continuous conversion */
+ cfg = 0x66;
+ rv = i2c_read8(I2C_PORT_THERMAL, DS1624_I2C_ADDR,
+ DS1624_ACCESS_CFG, &cfg);
+ trace2(0, BRD, 0, "Read DS1624 Config rv = %d cfg = 0x%02X",
+ rv, cfg);
+
+ if ((rv == EC_SUCCESS) && (cfg & (1u << 0))) {
+ /* one-shot mode switch to continuous */
+ rv = i2c_write8(I2C_PORT_THERMAL, DS1624_I2C_ADDR,
+ DS1624_ACCESS_CFG, 0);
+ trace1(0, BRD, 0, "Write DS1624 Config to 0, rv = %d", rv);
+ /* writes to config require 10ms until next I2C command */
+ if (rv == EC_SUCCESS)
+ udelay(10000);
+ }
+
+ /* Send start command */
+ rv = i2c_write8(I2C_PORT_THERMAL, DS1624_I2C_ADDR,
+ DS1624_CMD_START, 1);
+ trace1(0, BRD, 0, "Send Start command to DS1624 rv = %d", rv);
+
+ return;
+#endif
+}
+DECLARE_HOOK(HOOK_INIT, board_pmic_init, HOOK_PRIO_DEFAULT);
+
+/* Initialize board. */
+static void board_init(void)
+{
+ CPRINTS("MEC1701 HOOK_INIT - called board_init");
+ trace0(0, HOOK, 0, "HOOK_INIT - call board_init");
+
+#ifdef CONFIG_USB_POWER_DELIVERY
+ /* Enable PD MCU interrupt */
+ gpio_enable_interrupt(GPIO_PD_MCU_INT);
+ /* Enable VBUS interrupt */
+ gpio_enable_interrupt(GPIO_USB_C0_VBUS_WAKE_L);
+ gpio_enable_interrupt(GPIO_USB_C1_VBUS_WAKE_L);
+
+ /* Enable pericom BC1.2 interrupts */
+ gpio_enable_interrupt(GPIO_USB_C0_BC12_INT_L);
+ gpio_enable_interrupt(GPIO_USB_C1_BC12_INT_L);
+#endif
+ /* Enable tablet mode interrupt for input device enable */
+ gpio_enable_interrupt(GPIO_TABLET_MODE_L);
+
+ /* Provide AC status to the PCH */
+ gpio_set_level(GPIO_PCH_ACOK, extpower_is_present());
+
+#ifdef HAS_TASK_MOTIONSENSE
+ if (system_jumped_to_this_image() &&
+ chipset_in_state(CHIPSET_STATE_ON)) {
+ trace0(0, BRD, 0, "board_init: S0 call board_spi_enable");
+ board_spi_enable();
+ }
+#endif
+
+}
+DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);
+
+
+/**
+ * Buffer the AC present GPIO to the PCH.
+ */
+static void board_extpower(void)
+{
+ CPRINTS("MEC1701 HOOK_AC_CHANGE - called board_extpower");
+ trace0(0, HOOK, 0, "HOOK_AC_CHANGET - call board_extpower");
+ gpio_set_level(GPIO_PCH_ACOK, extpower_is_present());
+}
+DECLARE_HOOK(HOOK_AC_CHANGE, board_extpower, HOOK_PRIO_DEFAULT);
+
+#ifdef CONFIG_CHARGER
+/**
+ * Set active charge port -- only one port can be active at a time.
+ *
+ * @param charge_port Charge port to enable.
+ *
+ * Returns EC_SUCCESS if charge port is accepted and made active,
+ * EC_ERROR_* otherwise.
+ */
+int board_set_active_charge_port(int charge_port)
+{
+ /* charge port is a realy physical port */
+ int is_real_port = (charge_port >= 0 &&
+ charge_port < CONFIG_USB_PD_PORT_COUNT);
+ /* check if we are source vbus on that port */
+ int source = gpio_get_level(charge_port == 0 ? GPIO_USB_C0_5V_EN :
+ GPIO_USB_C1_5V_EN);
+
+ if (is_real_port && source) {
+ CPRINTS("MEC1701 Skip enable p%d", charge_port);
+ trace1(0, BOARD, 0, "Skip enable charge port %d",
+ charge_port);
+ return EC_ERROR_INVAL;
+ }
+
+ CPRINTS("MEC1701 New chg p%d", charge_port);
+ trace1(0, BOARD, 0, "New charge port %d", charge_port);
+
+ if (charge_port == CHARGE_PORT_NONE) {
+ /* Disable both ports */
+ gpio_set_level(GPIO_USB_C0_CHARGE_EN_L, 1);
+ gpio_set_level(GPIO_USB_C1_CHARGE_EN_L, 1);
+ } else {
+ /* Make sure non-charging port is disabled */
+ gpio_set_level(charge_port ? GPIO_USB_C0_CHARGE_EN_L :
+ GPIO_USB_C1_CHARGE_EN_L, 1);
+ /* Enable charging port */
+ gpio_set_level(charge_port ? GPIO_USB_C1_CHARGE_EN_L :
+ GPIO_USB_C0_CHARGE_EN_L, 0);
+ }
+
+ return EC_SUCCESS;
+}
+
+/**
+ * Set the charge limit based upon desired maximum.
+ *
+ * @param port Port number.
+ * @param supplier Charge supplier type.
+ * @param charge_ma Desired charge limit (mA).
+ * @param charge_mv Negotiated charge voltage (mV).
+ */
+void board_set_charge_limit(int port, int supplier, int charge_ma,
+ int max_ma, int charge_mv)
+{
+ charge_set_input_current_limit(MAX(charge_ma,
+ CONFIG_CHARGER_INPUT_CURRENT), charge_mv);
+}
+#else
+/*
+ * TODO HACK providing functions from common/charge_state_v2.c
+ * which is not compiled in when no charger
+ */
+int charge_want_shutdown(void)
+{
+ return 0;
+}
+
+int charge_prevent_power_on(int power_button_pressed)
+{
+ return 0;
+}
+
+
+#endif
+
+/*
+ * Enable or disable input devices,
+ * based upon chipset state and tablet mode
+ */
+static void enable_input_devices(void)
+{
+ int kb_enable = 1;
+ int tp_enable = 1;
+
+ /* Disable both TP and KB in tablet mode */
+ if (!gpio_get_level(GPIO_TABLET_MODE_L))
+ kb_enable = tp_enable = 0;
+ /* Disable TP if chipset is off */
+ else if (chipset_in_state(CHIPSET_STATE_ANY_OFF))
+ tp_enable = 0;
+
+ keyboard_scan_enable(kb_enable, KB_SCAN_DISABLE_LID_ANGLE);
+ gpio_set_level(GPIO_ENABLE_TOUCHPAD, tp_enable);
+}
+
+/* Called on AP S5 -> S3 transition */
+static void board_chipset_startup(void)
+{
+ CPRINTS("MEC1701 HOOK_CHIPSET_STARTUP - called board_chipset_startup");
+ trace0(0, HOOK, 0, "HOOK_CHIPSET_STARTUP - board_chipset_startup");
+ gpio_set_level(GPIO_USB1_ENABLE, 1);
+ gpio_set_level(GPIO_USB2_ENABLE, 1);
+ hook_call_deferred(&enable_input_devices_data, 0);
+}
+DECLARE_HOOK(HOOK_CHIPSET_STARTUP,
+ board_chipset_startup,
+ HOOK_PRIO_DEFAULT);
+
+/* Called on AP S3 -> S5 transition */
+static void board_chipset_shutdown(void)
+{
+ CPRINTS("MEC1701 HOOK_CHIPSET_SHUTDOWN board_chipset_shutdown");
+ trace0(0, HOOK, 0,
+ "HOOK_CHIPSET_SHUTDOWN board_chipset_shutdown");
+ gpio_set_level(GPIO_USB1_ENABLE, 0);
+ gpio_set_level(GPIO_USB2_ENABLE, 0);
+ hook_call_deferred(&enable_input_devices_data, 0);
+}
+DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN,
+ board_chipset_shutdown,
+ HOOK_PRIO_DEFAULT);
+
+/* Called on AP S3 -> S0 transition */
+static void board_chipset_resume(void)
+{
+ CPRINTS("MEC1701_EVG HOOK_CHIPSET_RESUME");
+ trace0(0, HOOK, 0, "HOOK_CHIPSET_RESUME - board_chipset_resume");
+ gpio_set_level(GPIO_ENABLE_BACKLIGHT, 1);
+#if 0 /* TODO not implemented in gpio.inc */
+ gpio_set_level(GPIO_PP1800_DX_AUDIO_EN, 1);
+ gpio_set_level(GPIO_PP1800_DX_SENSOR_EN, 1);
+#endif
+
+}
+DECLARE_HOOK(HOOK_CHIPSET_RESUME, board_chipset_resume,
+ MOTION_SENSE_HOOK_PRIO-1);
+
+/* Called on AP S0 -> S3 transition */
+static void board_chipset_suspend(void)
+{
+ CPRINTS("MEC1701 HOOK_CHIPSET_SUSPEND - called board_chipset_resume");
+ trace0(0, HOOK, 0, "HOOK_CHIPSET_SUSPEND - board_chipset_suspend");
+ gpio_set_level(GPIO_ENABLE_BACKLIGHT, 0);
+#if 0 /* TODO not implemented in gpio.inc */
+ gpio_set_level(GPIO_PP1800_DX_AUDIO_EN, 0);
+ gpio_set_level(GPIO_PP1800_DX_SENSOR_EN, 0);
+#endif
+}
+DECLARE_HOOK(HOOK_CHIPSET_SUSPEND,
+ board_chipset_suspend,
+ HOOK_PRIO_DEFAULT);
+
+void board_hibernate_late(void)
+{
+ /* put host chipset into reset */
+ gpio_set_level(GPIO_SYS_RESET_L, 0);
+
+ /* Turn off LEDs in hibernate */
+ gpio_set_level(GPIO_CHARGE_LED_1, 0);
+ gpio_set_level(GPIO_CHARGE_LED_2, 0);
+
+ /*
+ * Set PD wake low so that it toggles high to generate a wake
+ * event once we leave hibernate.
+ */
+ gpio_set_level(GPIO_USB_PD_WAKE, 0);
+
+#ifdef CONFIG_USB_PD_PORT_COUNT
+ /*
+ * Leave USB-C charging enabled in hibernate, in order to
+ * allow wake-on-plug. 5V enable must be pulled low.
+ */
+#if CONFIG_USB_PD_PORT_COUNT > 0
+ gpio_set_flags(GPIO_USB_C0_5V_EN, GPIO_PULL_DOWN | GPIO_INPUT);
+ gpio_set_level(GPIO_USB_C0_CHARGE_EN_L, 0);
+#endif
+#if CONFIG_USB_PD_PORT_COUNT > 1
+ gpio_set_flags(GPIO_USB_C1_5V_EN, GPIO_PULL_DOWN | GPIO_INPUT);
+ gpio_set_level(GPIO_USB_C1_CHARGE_EN_L, 0);
+#endif
+#endif /* CONFIG_USB_PD_PORT_COUNT */
+}
+
+/* Any glados boards post version 2 should have ROP_LDO_EN stuffed. */
+#define BOARD_MIN_ID_LOD_EN 2
+/* Make the pmic re-sequence the power rails under these conditions. */
+#define PMIC_RESET_FLAGS \
+ (RESET_FLAG_WATCHDOG | RESET_FLAG_SOFT | RESET_FLAG_HARD)
+static void board_handle_reboot(void)
+{
+#if 0 /* MEC17xx EVB + SKL-RVP3 does not use chromebook PMIC design */
+ int flags;
+#endif
+ CPRINTS("MEC HOOK_INIT - called board_handle_reboot");
+ trace0(0, HOOK, 0, "HOOK_INIT - board_handle_reboot");
+
+ if (system_jumped_to_this_image())
+ return;
+
+ if (system_get_board_version() < BOARD_MIN_ID_LOD_EN)
+ return;
+
+#if 0 /* TODO MCHP KBL hack not PMIC system */
+ /* Interrogate current reset flags from previous reboot. */
+ flags = system_get_reset_flags();
+
+ if (!(flags & PMIC_RESET_FLAGS))
+ return;
+
+ /* Preserve AP off request. */
+ if (flags & RESET_FLAG_AP_OFF)
+ chip_save_reset_flags(RESET_FLAG_AP_OFF);
+
+ ccprintf("Restarting system with PMIC.\n");
+ /* Flush console */
+ cflush();
+
+ /* Bring down all rails but RTC rail (including EC power). */
+ gpio_set_flags(GPIO_BATLOW_L_PMIC_LDO_EN, GPIO_OUT_HIGH);
+ while (1)
+ ; /* wait here */
+#else
+ return;
+#endif
+}
+DECLARE_HOOK(HOOK_INIT, board_handle_reboot, HOOK_PRIO_FIRST);
+
+
+static int sb_temp(int idx, int *temp_ptr)
+{
+ if (idx != 0)
+ return EC_ERROR_PARAM1;
+
+ if (temp_ptr == NULL)
+ return EC_ERROR_PARAM2;
+
+ *temp_ptr = smart_batt_temp;
+
+ return EC_SUCCESS;
+}
+
+static int ds1624_get_val(int idx, int *temp_ptr)
+{
+ if (idx != 0)
+ return EC_ERROR_PARAM1;
+
+ if (temp_ptr == NULL)
+ return EC_ERROR_PARAM2;
+
+ *temp_ptr = ds1624_temp;
+
+ return EC_SUCCESS;
+}
+
+/* call smart battery code to get its temperature
+ * output is in tenth degrees C
+ */
+static void sb_update(void)
+{
+ int rv __attribute__((unused));
+
+ rv = sb_read(SB_TEMPERATURE, &smart_batt_temp);
+ smart_batt_temp = smart_batt_temp / 10;
+
+ trace12(0, BRD, 0, "sb_read temperature rv=%d temp=%d K",
+ rv, smart_batt_temp);
+}
+
+/*
+ * Read temperature from Maxim DS1624 sensor. It only has internal sensor
+ * and is configured for continuous reading mode by default.
+ * DS1624 does not implement temperature limits or other features of
+ * sensors like the TMP411.
+ * Output format is 16-bit MSB first signed celcius temperature in units
+ * of 0.0625 degree Celsius.
+ * b[15]=sign bit
+ * b[14]=2^6, b[13]=2^5, ..., b[8]=2^0
+ * b[7]=1/2, b[6]=1/4, b[5]=1/8, b[4]=1/16
+ * b[3:0]=0000b
+ *
+ */
+static void ds1624_update(void)
+{
+ uint32_t d;
+ int temp;
+ int rv __attribute__((unused));
+
+ rv = i2c_read16(I2C_PORT_THERMAL,
+ (DS1624_I2C_ADDR | I2C_FLAG_BIG_ENDIAN),
+ DS1624_READ_TEMP16, &temp);
+
+ d = (temp & 0x7FFF) >> 8;
+ if ((uint32_t)temp & (1 << 7))
+ d++;
+
+ if ((uint32_t)temp & (1 << 15))
+ d |= (1u << 31);
+
+ ds1624_temp = (int32_t)d;
+
+ trace3(0, BRD, 0, "ds1624_update: rv=%d raw temp = 0x%04X tempC = %d",
+ rv, temp, ds1624_temp);
+}
+
+/* Indicate scheduler is alive by blinking an LED.
+ * Test I2C by reading a smart battery and temperature sensor.
+ * Smart battery 16 bit temperature is in units of 1/10 degree C.
+ */
+static void board_one_sec(void)
+{
+ trace0(0, BRD, 0, "HOOK_SECOND");
+
+ if (gpio_get_level(GPIO_CHARGE_LED_2))
+ gpio_set_level(GPIO_CHARGE_LED_2, 0);
+ else
+ gpio_set_level(GPIO_CHARGE_LED_2, 1);
+
+ sb_update();
+ ds1624_update();
+}
+DECLARE_HOOK(HOOK_SECOND, board_one_sec, HOOK_PRIO_DEFAULT);
+
+#ifdef HAS_TASK_MOTIONSENSE
+/* Motion sensors */
+
+static struct mutex g_base_mutex;
+/* BMI160 private data */
+static struct bmi160_drv_data_t g_bmi160_data;
+
+#ifdef CONFIG_ACCEL_KX022
+static struct mutex g_lid_mutex;
+/* KX022 private data */
+static struct kionix_accel_data g_kx022_data;
+#endif
+
+struct motion_sensor_t motion_sensors[] = {
+ /*
+ * Note: bmi160: supports accelerometer and gyro sensor
+ * Requirement: accelerometer sensor must init before gyro sensor
+ * DO NOT change the order of the following table.
+ */
+ {.name = "Base Accel",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_BMI160,
+ .type = MOTIONSENSE_TYPE_ACCEL,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &bmi160_drv,
+ .mutex = &g_base_mutex,
+ .drv_data = &g_bmi160_data,
+ .port = CONFIG_SPI_ACCEL_PORT,
+ .addr = BMI160_SET_SPI_ADDRESS(CONFIG_SPI_ACCEL_PORT),
+ .rot_standard_ref = NULL, /* Identity matrix. */
+ .default_range = 2, /* g, enough for laptop. */
+ .min_frequency = BMI160_ACCEL_MIN_FREQ,
+ .max_frequency = BMI160_ACCEL_MAX_FREQ,
+ .config = {
+ /* AP: by default use EC settings */
+ [SENSOR_CONFIG_AP] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* EC use accel for angle detection */
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 100 * MSEC,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 0,
+ .ec_rate = 0
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0
+ },
+ },
+ },
+
+ {.name = "Base Gyro",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_BMI160,
+ .type = MOTIONSENSE_TYPE_GYRO,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &bmi160_drv,
+ .mutex = &g_base_mutex,
+ .drv_data = &g_bmi160_data,
+ .port = CONFIG_SPI_ACCEL_PORT,
+ .addr = BMI160_SET_SPI_ADDRESS(CONFIG_SPI_ACCEL_PORT),
+ .default_range = 1000, /* dps */
+ .rot_standard_ref = NULL, /* Identity Matrix. */
+ .min_frequency = BMI160_GYRO_MIN_FREQ,
+ .max_frequency = BMI160_GYRO_MAX_FREQ,
+ .config = {
+ /* AP: by default shutdown all sensors */
+ [SENSOR_CONFIG_AP] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* EC does not need in S0 */
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ },
+ },
+#ifdef CONFIG_ACCEL_KX022
+ {.name = "Lid Accel",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_KX022,
+ .type = MOTIONSENSE_TYPE_ACCEL,
+ .location = MOTIONSENSE_LOC_LID,
+ .drv = &kionix_accel_drv,
+ .mutex = &g_lid_mutex,
+ .drv_data = &g_kx022_data,
+ .port = I2C_PORT_ACCEL,
+ .addr = KX022_ADDR1,
+ .rot_standard_ref = NULL, /* Identity matrix. */
+ .default_range = 2, /* g, enough for laptop. */
+ .min_frequency = KX022_ACCEL_MIN_FREQ,
+ .max_frequency = KX022_ACCEL_MAX_FREQ,
+ .config = {
+ /* AP: by default use EC settings */
+ [SENSOR_CONFIG_AP] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 100 * MSEC,
+ },
+ /* EC use accel for angle detection */
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 100 * MSEC,
+ },
+ /* unused */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ },
+ },
+#endif /* #ifdef CONFIG_ACCEL_KX022 */
+};
+const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
+
+static void board_spi_enable(void)
+{
+ trace0(0, BRD, 0, "HOOK_CHIPSET_STARTUP - board_spi_enable");
+
+ spi_enable(CONFIG_SPI_ACCEL_PORT, 1);
+
+ /* Toggle SPI chip select to switch BMI160 from I2C mode
+ * to SPI mode
+ */
+ gpio_set_level(GPIO_SPI0_CS0, 0);
+ udelay(10);
+ gpio_set_level(GPIO_SPI0_CS0, 1);
+}
+DECLARE_HOOK(HOOK_CHIPSET_STARTUP, board_spi_enable,
+ MOTION_SENSE_HOOK_PRIO - 1);
+
+static void board_spi_disable(void)
+{
+ trace0(0, BRD, 0, "HOOK_CHIPSET_SHUTDOWN - board_spi_disable");
+ spi_enable(CONFIG_SPI_ACCEL_PORT, 0);
+}
+DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, board_spi_disable,
+ MOTION_SENSE_HOOK_PRIO + 1);
+#endif /* defined(HAS_TASK_MOTIONSENSE) */
+
+#ifdef MEC1701_EVB_TACH_TEST /* PWM/TACH test */
+void tach0_isr(void)
+{
+ MCHP_INT_DISABLE(MCHP_TACH_GIRQ) = MCHP_TACH_GIRQ_BIT(0);
+ MCHP_INT_SOURCE(MCHP_TACH_GIRQ) = MCHP_TACH_GIRQ_BIT(0);
+}
+DECLARE_IRQ(MCHP_IRQ_TACH_0, tach0_isr, 1);
+#endif
diff --git a/board/mchpevb1/board.h b/board/mchpevb1/board.h
new file mode 100644
index 0000000000..9a5a6e580a
--- /dev/null
+++ b/board/mchpevb1/board.h
@@ -0,0 +1,502 @@
+/* Copyright 2017 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.
+ */
+
+/*
+ * Microchip Evaluation Board (EVB) with
+ * MEC1701H 144-pin processor card.
+ * EVB connected to Intel SKL RVP3 configured
+ * for eSPI with Kabylake silicon.
+ */
+
+#ifndef __CROS_EC_BOARD_H
+#define __CROS_EC_BOARD_H
+
+/*
+ * Initial board bringup and prevent power button task from
+ * generating event to exit G3 state.
+ *
+ * #define CONFIG_BRINGUP
+ */
+
+/*
+ * Debug on EVB with CONFIG_CHIPSET_DEBUG
+ * Keep WDG disabled and JTAG enabled.
+ * CONFIG_BOARD_PRE_INIT enables JTAG early
+ */
+/* #define CONFIG_CHIPSET_DEBUG */
+
+#ifdef CONFIG_CHIPSET_DEBUG
+#ifndef CONFIG_BOARD_PRE_INIT
+#define CONFIG_BOARD_PRE_INIT
+#endif
+#endif
+
+/*
+ * DEBUG: Add CRC32 in last 4 bytes of EC_RO/RW binaries
+ * in SPI. LFW will use DMA CRC32 HW to check data integrity.
+ * #define CONFIG_MCHP_LFW_DEBUG
+ */
+
+
+/*
+ * Override Boot-ROM JTAG mode
+ * 0x01 = 4-pin standard JTAG
+ * 0x03 = ARM 2-pin SWD + 1-pin SWV
+ * 0x05 = ARM 2-pin SWD no SWV
+ */
+#define CONFIG_MCHP_JTAG_MODE 0x03
+
+/*
+ * Enable Trace FIFO Debug port
+ * When this is undefined all TRACEn() and tracen()
+ * macros are defined as blank.
+ * Uncomment this define to enable these messages.
+ * Only enable if GPIO's 0171 & 0171 are available therefore
+ * define this at the board level.
+ */
+/* #define CONFIG_MCHP_TFDP */
+
+/*
+ * Enable MCHP specific GPIO EC UART commands
+ * for debug.
+ */
+/* #define CONFIG_MEC_GPIO_EC_CMDS */
+
+/*
+ * Enable CPRINT in chip eSPI module
+ * and EC UART test command.
+ */
+/* #define CONFIG_MCHP_ESPI_DEBUG */
+
+/*
+ * Enable board specific ISR on ALL_SYS_PWRGD signal.
+ * Requires for handling Kabylake/Skylake RVP3 board's
+ * ALL_SYS_PWRGD signal.
+ */
+#define CONFIG_BOARD_EC_HANDLES_ALL_SYS_PWRGD
+
+/*
+ * EVB eSPI test mode (no eSPI master connected)
+ */
+/*
+ * #define EVB_NO_ESPI_TEST_MODE
+ */
+
+
+/*
+ * DEBUG
+ * Disable ARM Cortex-M4 write buffer so
+ * exceptions become synchronous.
+ *
+ * #define CONFIG_DEBUG_DISABLE_WRITE_BUFFER
+ */
+
+/* New eSPI slave configuration items */
+
+/*
+ * Maximum clock frequence eSPI EC slave advertises
+ * Values in MHz are 20, 25, 33, 50, and 66
+ */
+/* KBL + EVB fly-wire hook up only supports 20MHz */
+#define CONFIG_ESPI_EC_MAX_FREQ 20
+
+/*
+ * EC eSPI slave advertises IO lanes
+ * 0 = Single
+ * 1 = Single and Dual
+ * 2 = Single and Quad
+ * 3 = Single, Dual, and Quad
+ */
+/* KBL + EVB fly-wire hook up only support Single mode */
+#define CONFIG_ESPI_EC_MODE 0
+
+/*
+ * Bit map of eSPI channels EC advertises
+ * bit[0] = 1 Peripheral channel
+ * bit[1] = 1 Virtual Wire channel
+ * bit[2] = 1 OOB channel
+ * bit[3] = 1 Flash channel
+ */
+#define CONFIG_ESPI_EC_CHAN_BITMAP 0x0F
+
+/*
+ * MEC17xx EVB + KBL RVP3 board uses eSPI default of
+ * Platform Reset being a virtual wire.
+ */
+#define CONFIG_ESPI_PLTRST_IS_VWIRE
+
+#define CONFIG_MCHP_ESPI_VW_SAVE_ON_SLEEP
+
+/*
+ * Allow dangerous commands.
+ * TODO(shawnn): Remove this config before production.
+ */
+#define CONFIG_SYSTEM_UNLOCKED
+
+/* Optional features */
+#define CONFIG_ACCELGYRO_BMI160
+/* #define CONFIG_ACCEL_KX022 */
+/* #define CONFIG_ALS */
+/* #define CONFIG_ALS_OPT3001 */
+#define CONFIG_BATTERY_CUT_OFF
+#define CONFIG_BATTERY_PRESENT_GPIO GPIO_BAT_PRESENT_L
+#define CONFIG_BATTERY_SMART
+#define CONFIG_BOARD_VERSION
+#define CONFIG_BUTTON_COUNT 2
+/* #define CONFIG_CHARGE_MANAGER */
+/* #define CONFIG_CHARGE_RAMP_SW */
+
+
+/* #define CONFIG_CHARGER */
+/* #define CONFIG_CHARGER_V2 */
+
+/* #define CONFIG_CHARGER_DISCHARGE_ON_AC */
+/* #define CONFIG_CHARGER_ISL9237 */
+/* #define CONFIG_CHARGER_ILIM_PIN_DISABLED */
+/* #define CONFIG_CHARGER_INPUT_CURRENT 512 */
+
+/*
+ * MCHP disable this for Kabylake eSPI bring up
+ * #define CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON 1
+ */
+
+/* #define CONFIG_CHARGER_NARROW_VDC */
+/* #define CONFIG_CHARGER_PROFILE_OVERRIDE */
+/* #define CONFIG_CHARGER_SENSE_RESISTOR 10 */
+/* #define CONFIG_CHARGER_SENSE_RESISTOR_AC 20 */
+/* #define CONFIG_CMD_CHARGER_ADC_AMON_BMON */
+
+#define CONFIG_CHIPSET_SKYLAKE
+#define CONFIG_CHIPSET_RESET_HOOK
+
+#define CONFIG_ESPI
+#define CONFIG_ESPI_VW_SIGNALS
+
+#define CONFIG_CLOCK_CRYSTAL
+#define CONFIG_EXTPOWER_GPIO
+/* #define CONFIG_HOSTCMD_PD */
+/* #define CONFIG_HOSTCMD_PD_PANIC */
+#define CONFIG_I2C
+#define CONFIG_I2C_MASTER
+#define CONFIG_KEYBOARD_PROTOCOL_8042
+#define CONFIG_LED_COMMON
+#define CONFIG_LID_ANGLE
+#define CONFIG_LID_ANGLE_SENSOR_BASE 0
+#define CONFIG_LID_ANGLE_SENSOR_LID 2
+#define CONFIG_LID_SWITCH
+/*
+ * Enable MCHP Low Power Idle support
+ * and API to power down pins
+ * #define CONFIG_LOW_POWER_IDLE
+ */
+
+
+/* #define CONFIG_GPIO_POWER_DOWN */
+
+/*
+ * Turn off pin modules during deep sleep.
+ * Requires CONFIG_GPIO_POWER_DOWN
+ */
+/* #define CONFIG_MCHP_DEEP_SLP_GPIO_PWR_DOWN */
+
+/*
+ * DEBUG: Configure MEC17xx GPIO060 as 48MHZ_OUT to
+ * verify & debug clock is shutdown in heavy sleep.
+ */
+#define CONFIG_MCHP_48MHZ_OUT
+
+/*
+ * DEBUG: Save and print out PCR sleep enables,
+ * clock required, and interrupt aggregator result
+ * registers.
+ */
+#define CONFIG_MCHP_DEEP_SLP_DEBUG
+
+/*
+ * MCHP debug EC code turn off GCC link-time-optimization
+ * #define CONFIG_LTO
+ */
+#define CONFIG_POWER_BUTTON
+#define CONFIG_POWER_BUTTON_X86
+#define CONFIG_POWER_COMMON
+#define CONFIG_POWER_SIGNAL_INTERRUPT_STORM_DETECT_THRESHOLD 30
+
+/*
+ * MEC1701H SCI is virtual wire on eSPI
+ *#define CONFIG_SCI_GPIO GPIO_PCH_SCI_L
+ */
+
+#if 0 /* MCHP EVB + KBL/SKL RVP3 no USB charging hardware */
+#define CONFIG_USB_CHARGER
+#define CONFIG_USB_MUX_PI3USB30532
+#define CONFIG_USB_MUX_PS8740
+#define CONFIG_USB_POWER_DELIVERY
+#define CONFIG_USB_PD_ALT_MODE
+#define CONFIG_USB_PD_ALT_MODE_DFP
+#define CONFIG_USB_PD_CUSTOM_VDM
+#define CONFIG_USB_PD_DUAL_ROLE
+#define CONFIG_USB_PD_LOGGING
+#define CONFIG_USB_PD_PORT_COUNT 2
+#define CONFIG_USB_PD_TCPM_TCPCI
+#endif
+/*
+ * #define CONFIG_USB_PD_TCPC
+ * #define CONFIG_USB_PD_TCPM_STUB
+ */
+#if 0
+#define CONFIG_USB_PD_TRY_SRC
+#define CONFIG_USB_PD_VBUS_DETECT_GPIO
+#define CONFIG_BC12_DETECT_PI3USB9281
+#define CONFIG_BC12_DETECT_PI3USB9281_CHIP_COUNT 2
+#define CONFIG_USBC_SS_MUX
+#define CONFIG_USBC_SS_MUX_DFP_ONLY
+#define CONFIG_USBC_VCONN
+#define CONFIG_USBC_VCONN_SWAP
+#endif
+
+#define CONFIG_VBOOT_HASH
+
+/*
+ * MEC1701H loads firmware using QMSPI controller
+ * CONFIG_SPI_FLASH_PORT is the index into
+ * spi_devices[] in board.c
+ */
+#define CONFIG_SPI_FLASH_PORT 0
+#define CONFIG_SPI_FLASH
+/*
+ * Google uses smaller flashes on chromebook boards
+ * MCHP SPI test dongle for EVB uses 16MB W25Q128F
+ * Configure for smaller flash is OK for testing except
+ * for SPI flash lock bit.
+ */
+ #define CONFIG_FLASH_SIZE 524288
+ #define CONFIG_SPI_FLASH_W25X40
+/*
+ * #define CONFIG_FLASH_SIZE 0x1000000
+ * #define CONFIG_SPI_FLASH_W25Q128
+ */
+
+/*
+ * Enable extra SPI flash and generic SPI
+ * commands via EC UART
+ */
+#define CONFIG_CMD_SPI_FLASH
+#define CONFIG_CMD_SPI_XFER
+
+/* common software SHA256 required by vboot and rollback */
+#define CONFIG_SHA256
+
+/*
+ * Enable MCHP SHA256 hardware accelerator module.
+ * API is same as software SHA256 but prefixed with "chip_"
+ * #define CONFIG_SHA256_HW
+ */
+
+/* enable console command to test HW Hash engine
+ * #define CONFIG_CMD_SHA256_TEST
+ */
+
+/*
+ * MEC17xx EVB + SKL/KBL RVP3 does not have
+ * BD99992GW PMIC with NCP15WB thermistor.
+ * We have connected a Maxim DS1624 I2C temperature
+ * sensor. The sensor board has a thermistor on it
+ * we connect to an EC ADC channel.
+ */
+#if 0
+#define CONFIG_TEMP_SENSOR
+#define CONFIG_TEMP_SENSOR_BD99992GW
+#define CONFIG_THERMISTOR_NCP15WB
+#define CONFIG_DPTF
+#else
+#define CONFIG_TEMP_SENSOR
+#define CONFIG_DPTF
+#endif
+
+/* Enable GPSPI0 controller and port for
+ * SPI Accelerometer.
+ * bit[0] == 1 GPSPI0
+ * bit[1] == 0 board does not use GPSPI1
+ * Make sure to not include GPSPI in little-firmware(LFW)
+ */
+#ifndef LFW
+#define CONFIG_MCHP_GPSPI 0x01
+#endif
+
+/* SPI Accelerometer
+ * CONFIG_SPI_FLASH_PORT is the index into
+ * spi_devices[] in board.c
+ */
+#define CONFIG_SPI_ACCEL_PORT 1
+
+/*
+ * Enable EC UART commands to read/write
+ * motion sensor.
+ */
+#define CONFIG_CMD_ACCELS
+
+/*
+ * Enable 1 slot of secure temporary storage to support
+ * suspend/resume with read/write memory training.
+ */
+#define CONFIG_VSTORE
+#define CONFIG_VSTORE_SLOT_COUNT 1
+
+#define CONFIG_WATCHDOG_HELP
+
+#if 0 /* TODO - No wireless on EVB */
+#define CONFIG_WIRELESS
+#define CONFIG_WIRELESS_SUSPEND \
+ (EC_WIRELESS_SWITCH_WLAN | EC_WIRELESS_SWITCH_WLAN_POWER)
+
+/* Wireless signals */
+#define WIRELESS_GPIO_WLAN GPIO_WLAN_OFF_L
+#define WIRELESS_GPIO_WLAN_POWER GPIO_PP3300_WLAN_EN
+#endif
+
+/* LED signals */
+#define GPIO_BAT_LED_RED GPIO_CHARGE_LED_1
+#define GPIO_BAT_LED_GREEN GPIO_CHARGE_LED_2
+
+/* I2C ports */
+#define I2C_CONTROLLER_COUNT 2
+#define I2C_PORT_COUNT 2
+
+
+/*
+ * Map I2C Ports to Controllers for this board.
+ *
+ * I2C Controller 0 ---- Port 0 -> PMIC, USB Charger 2
+ * |-- Port 2 -> USB Charger 1, USB Mux
+ *
+ * I2C Controller 1 ---- Port 3 -> PD MCU, TCPC
+ * I2C Controller 2 ---- Port 4 -> ALS, Accel
+ * I2C Controller 3 ---- Port 5 -> Battery, Charger
+ *
+ * All other ports set to 0xff (not used)
+ */
+
+#define I2C_PORT_PMIC MCHP_I2C_PORT10
+#define I2C_PORT_USB_CHARGER_1 MCHP_I2C_PORT2
+#define I2C_PORT_USB_MUX MCHP_I2C_PORT2
+#define I2C_PORT_USB_CHARGER_2 MCHP_I2C_PORT2
+#define I2C_PORT_PD_MCU MCHP_I2C_PORT3
+#define I2C_PORT_TCPC MCHP_I2C_PORT3
+#define I2C_PORT_ALS MCHP_I2C_PORT4
+#define I2C_PORT_ACCEL MCHP_I2C_PORT4
+#define I2C_PORT_BATTERY MCHP_I2C_PORT5
+#define I2C_PORT_CHARGER MCHP_I2C_PORT5
+
+/* Thermal sensors read through PMIC ADC interface */
+#if 0
+#define I2C_PORT_THERMAL I2C_PORT_PMIC
+#else
+#define I2C_PORT_THERMAL MCHP_I2C_PORT4
+#endif
+
+/* Ambient Light Sensor address */
+#define OPT3001_I2C_ADDR OPT3001_I2C_ADDR1
+
+/* Modules we want to exclude */
+#undef CONFIG_CMD_HASH
+#undef CONFIG_CMD_TEMP_SENSOR
+#undef CONFIG_CMD_TIMERINFO
+/* #undef CONFIG_CONSOLE_CMDHELP */
+
+#ifndef __ASSEMBLER__
+
+#include "gpio_signal.h"
+#include "registers.h"
+
+/* ADC signal */
+enum adc_channel {
+ ADC_VBUS,
+ ADC_AMON_BMON,
+ ADC_PSYS,
+ ADC_CASE,
+ /* Number of ADC channels */
+ ADC_CH_COUNT
+};
+
+/* power signal definitions */
+enum power_signal {
+ X86_RSMRST_L_PWRGD = 0,
+ X86_SLP_S3_DEASSERTED,
+ X86_SLP_S4_DEASSERTED,
+ X86_SLP_SUS_DEASSERTED,
+ X86_PMIC_DPWROK,
+ X86_ALL_SYS_PWRGD, /* MCHP mec1701_evb + SKL/KBL RVP3 */
+
+ /* Number of X86 signals */
+ POWER_SIGNAL_COUNT
+};
+
+enum temp_sensor_id {
+ TEMP_SENSOR_BATTERY,
+
+ /* These temp sensors are only readable in S0 */
+ TEMP_SENSOR_AMBIENT,
+ TEMP_SENSOR_CASE,
+/* TEMP_SENSOR_CHARGER, */
+/* TEMP_SENSOR_DRAM, */
+/* TEMP_SENSOR_WIFI, */
+
+ TEMP_SENSOR_COUNT
+};
+
+/* Light sensors */
+enum als_id {
+ ALS_OPT3001 = 0,
+
+ ALS_COUNT
+};
+
+/* TODO: determine the following board specific type-C power constants */
+/*
+ * delay to turn on the power supply max is ~16ms.
+ * delay to turn off the power supply max is about ~180ms.
+ */
+#define PD_POWER_SUPPLY_TURN_ON_DELAY 30000 /* us */
+#define PD_POWER_SUPPLY_TURN_OFF_DELAY 250000 /* us */
+
+/* delay to turn on/off vconn */
+#define PD_VCONN_SWAP_DELAY 5000 /* us */
+
+/* Define typical operating power and max power */
+#define PD_OPERATING_POWER_MW 15000
+#define PD_MAX_POWER_MW 45000
+#define PD_MAX_CURRENT_MA 3000
+
+/* Try to negotiate to 20V since i2c noise problems should be fixed. */
+#define PD_MAX_VOLTAGE_MV 20000
+
+/*
+ * include TFDP macros from mchp chip level
+ */
+#include "tfdp_chip.h"
+
+
+/* Map I2C port to controller */
+int board_i2c_p2c(int port);
+
+/* Return the two slave addresses the specified
+ * controller will respond to when controller
+ * is acting as a slave.
+ * b[6:0] = b[7:1] of I2C address 1
+ * b[14:8] = b[7:1] of I2C address 2
+ */
+uint16_t board_i2c_slave_addrs(int controller);
+
+/* Reset PD MCU */
+void board_reset_pd_mcu(void);
+
+#ifdef CONFIG_LOW_POWER_IDLE
+void board_prepare_for_deep_sleep(void);
+void board_resume_from_deep_sleep(void);
+#endif
+
+#endif /* !__ASSEMBLER__ */
+
+#endif /* __CROS_EC_BOARD_H */