summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorEric Yilun Lin <yllin@chromium.org>2021-11-18 14:51:09 +0800
committerCommit Bot <commit-bot@chromium.org>2021-11-24 08:47:26 +0000
commit5f96a5bd38931aa7d935874ee6dcf611e9c1738e (patch)
tree26f8b044b8f5124d656645553822ca24cfa6f9c4
parent9548d4102490b0a80d597499b7f4f3c2f4a3577d (diff)
downloadchrome-ec-5f96a5bd38931aa7d935874ee6dcf611e9c1738e.tar.gz
corsola: drop corsola cros-EC board
Move corsola baseboard files and krabby files under zephyr/projects/corsola. Also, drop kingler cros-ec board since we are not using it yet, all the development is under zephyr. BUG=b:206553789 TEST=zmake testall BRANCH=main Change-Id: I7b0b56e4598ec049c0a1fecb8920d9134e0b3ae1 Signed-off-by: Eric Yilun Lin <yllin@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/3289582 Commit-Queue: Eric Yilun Lin <yllin@google.com> Tested-by: Eric Yilun Lin <yllin@google.com> Auto-Submit: Eric Yilun Lin <yllin@google.com> Reviewed-by: Ting Shen <phoenixshen@chromium.org>
-rw-r--r--baseboard/corsola/baseboard.c82
-rw-r--r--baseboard/corsola/baseboard.h196
-rw-r--r--baseboard/corsola/build.mk15
-rw-r--r--board/kingler/board.c188
-rw-r--r--board/kingler/board.h118
-rw-r--r--board/kingler/build.mk16
-rw-r--r--board/kingler/ec.tasklist22
-rw-r--r--board/kingler/gpio.inc160
-rw-r--r--board/kingler/usbc_config.c28
-rw-r--r--board/kingler/vif_override.xml3
-rw-r--r--board/krabby/battery.c47
-rw-r--r--board/krabby/board.h116
-rw-r--r--board/krabby/build.mk16
-rw-r--r--board/krabby/ec.tasklist22
-rw-r--r--board/krabby/gpio.inc157
-rw-r--r--board/krabby/led.c120
-rw-r--r--board/krabby/vif_override.xml3
-rw-r--r--zephyr/projects/corsola/CMakeLists.txt34
-rw-r--r--zephyr/projects/corsola/Kconfig11
-rw-r--r--zephyr/projects/corsola/prj_krabby.conf2
-rw-r--r--zephyr/projects/corsola/src/baseboard_common.h (renamed from baseboard/corsola/baseboard_common.h)0
-rw-r--r--zephyr/projects/corsola/src/board_chipset.c (renamed from baseboard/corsola/board_chipset.c)0
-rw-r--r--zephyr/projects/corsola/src/board_id.c (renamed from baseboard/corsola/board_id.c)0
-rw-r--r--zephyr/projects/corsola/src/hibernate.c (renamed from baseboard/corsola/hibernate.c)0
-rw-r--r--zephyr/projects/corsola/src/krabby/battery.c (renamed from board/kingler/battery.c)0
-rw-r--r--zephyr/projects/corsola/src/krabby/board.c (renamed from board/krabby/board.c)0
-rw-r--r--zephyr/projects/corsola/src/krabby/hooks.c (renamed from board/krabby/hooks.c)0
-rw-r--r--zephyr/projects/corsola/src/krabby/led.c (renamed from board/kingler/led.c)0
-rw-r--r--zephyr/projects/corsola/src/krabby/usbc_config.c (renamed from board/krabby/usbc_config.c)0
-rw-r--r--zephyr/projects/corsola/src/regulator.c (renamed from baseboard/corsola/regulator.c)0
-rw-r--r--zephyr/projects/corsola/src/usb_pd_policy.c (renamed from baseboard/corsola/usb_pd_policy.c)0
-rw-r--r--zephyr/projects/corsola/src/usbc_config.c (renamed from baseboard/corsola/usbc_config.c)0
32 files changed, 27 insertions, 1329 deletions
diff --git a/baseboard/corsola/baseboard.c b/baseboard/corsola/baseboard.c
deleted file mode 100644
index 4d8fea6c7c..0000000000
--- a/baseboard/corsola/baseboard.c
+++ /dev/null
@@ -1,82 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/* Corsola baseboard-specific configuration */
-
-#include "adc.h"
-#include "button.h"
-#include "charge_manager.h"
-#include "charger.h"
-#include "charger.h"
-#include "charge_state.h"
-#include "charge_state_v2.h"
-#include "chipset.h"
-#include "common.h"
-#include "console.h"
-#include "driver/accel_lis2dw12.h"
-#include "driver/accelgyro_icm426xx.h"
-#include "driver/bc12/mt6360.h"
-#include "driver/charger/isl923x.h"
-#include "driver/ppc/syv682x.h"
-#include "driver/tcpm/it83xx_pd.h"
-#include "driver/temp_sensor/thermistor.h"
-#include "extpower.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "keyboard_scan.h"
-#include "lid_switch.h"
-#include "motion_sense.h"
-#include "power_button.h"
-#include "power.h"
-#include "regulator.h"
-#include "spi.h"
-#include "switch.h"
-#include "tablet_mode.h"
-#include "task.h"
-#include "temp_sensor.h"
-#include "timer.h"
-#include "uart.h"
-
-#include "gpio_list.h"
-
-/* Wake-up pins for hibernate */
-enum gpio_signal hibernate_wake_pins[] = {
- GPIO_AC_PRESENT,
- GPIO_LID_OPEN,
- GPIO_POWER_BUTTON_L,
-};
-int hibernate_wake_pins_used = ARRAY_SIZE(hibernate_wake_pins);
-
-/*
- * I2C channels (A, B, and C) are using the same timing registers (00h~07h)
- * at default.
- * In order to set frequency independently for each channels,
- * We use timing registers 09h~0Bh, and the supported frequency will be:
- * 50KHz, 100KHz, 400KHz, or 1MHz.
- * I2C channels (D, E and F) can be set different frequency on different ports.
- * The I2C(D/E/F) frequency depend on the frequency of SMBus Module and
- * the individual prescale register.
- * The frequency of SMBus module is 24MHz on default.
- * The allowed range of I2C(D/E/F) frequency is as following setting.
- * SMBus Module Freq = PLL_CLOCK / ((IT83XX_ECPM_SCDCR2 & 0x0F) + 1)
- * (SMBus Module Freq / 510) <= I2C Freq <= (SMBus Module Freq / 8)
- * Channel D has multi-function and can be used as UART interface.
- * Channel F is reserved for EC debug.
- */
-
-/* I2C ports */
-const struct i2c_port_t i2c_ports[] = {
- {"bat_chg", IT83XX_I2C_CH_A, 100, GPIO_I2C_A_SCL, GPIO_I2C_A_SDA},
- {"sensor", IT83XX_I2C_CH_B, 400, GPIO_I2C_B_SCL, GPIO_I2C_B_SDA},
- {"usb0", IT83XX_I2C_CH_C, 400, GPIO_I2C_C_SCL, GPIO_I2C_C_SDA},
- {"usb1", IT83XX_I2C_CH_E, 400, GPIO_I2C_E_SCL, GPIO_I2C_E_SDA},
-};
-const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
-
-int board_allow_i2c_passthru(int port)
-{
- return (port == I2C_PORT_VIRTUAL_BATTERY);
-}
diff --git a/baseboard/corsola/baseboard.h b/baseboard/corsola/baseboard.h
deleted file mode 100644
index 95d3b1d20c..0000000000
--- a/baseboard/corsola/baseboard.h
+++ /dev/null
@@ -1,196 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/* Corsola board configuration */
-
-#ifndef __CROS_EC_BASEBOARD_H
-#define __CROS_EC_BASEBOARD_H
-
-/* IT81202-bx config */
-/*
- * NOTE: we need to make correct VCC voltage selection here if EC's VCC isn't
- * connect to 1.8v on other versions.
- */
-#define CONFIG_IT83XX_VCC_1P8V
-
-/*
- * On power-on, H1 releases the EC from reset but then quickly asserts and
- * releases the reset a second time. This means the EC sees 2 resets:
- * (1) power-on reset, (2) reset-pin reset. This config will
- * allow the second reset to be treated as a power-on.
- */
-#define CONFIG_BOARD_RESET_AFTER_POWER_ON
-#define CONFIG_CHIPSET_MT8192
-#define CONFIG_EXTPOWER_GPIO
-#define CONFIG_HIBERNATE_WAKE_PINS_DYNAMIC
-#define CONFIG_POWER_SLEEP_FAILURE_DETECTION
-#define CONFIG_POWER_TRACK_HOST_SLEEP_STATE
-
-/* Chipset */
-#define CONFIG_CMD_AP_RESET_LOG
-#define CONFIG_CMD_POWERINDEBUG
-#define CONFIG_HOST_COMMAND_STATUS
-#define CONFIG_LOW_POWER_IDLE
-#define CONFIG_LOW_POWER_S0
-#define CONFIG_POWER_BUTTON
-#define CONFIG_POWER_COMMON
-#define CONFIG_PWM
-#define CONFIG_VBOOT_HASH
-#define CONFIG_VOLUME_BUTTONS
-#define CONFIG_WP_ACTIVE_HIGH
-
-/* Battery */
-#define CONFIG_BATTERY_CUT_OFF
-#define CONFIG_BATTERY_FUEL_GAUGE
-#define CONFIG_BATTERY_PRESENT_GPIO GPIO_EC_BATT_PRES_ODL
-#define CONFIG_BATTERY_SMART
-
-/* BC12 */
-#define CONFIG_BC12_DETECT_MT6360
-#define CONFIG_BC12_DETECT_PI3USB9201
-#undef CONFIG_BC12_SINGLE_DRIVER
-#define CONFIG_USB_CHARGER
-
-/* Charger */
-#define ADC_AMON_BMON ADC_CHARGER_AMON_R /* ADC name remap */
-#define ADC_PSYS ADC_CHARGER_PMON /* ADC name remap */
-#define CONFIG_CHARGE_MANAGER
-#define CONFIG_CHARGER
-#define CONFIG_CHARGE_RAMP_HW
-#define CONFIG_CHARGER_DISCHARGE_ON_AC
-#define CONFIG_CHARGER_INPUT_CURRENT 512
-#define CONFIG_CHARGER_ISL9238C
-#define CONFIG_CHARGER_MAINTAIN_VBAT
-#define CONFIG_CHARGER_OTG
-#define CONFIG_CHARGER_PSYS
-#define CONFIG_CHARGER_PSYS_READ
-#define CONFIG_CHARGER_SENSE_RESISTOR 10 /* BOARD_RS2 */
-#define CONFIG_CHARGER_SENSE_RESISTOR_AC 20 /* BOARD_RS1 */
-#define CONFIG_CMD_CHARGER_ADC_AMON_BMON
-
-/* Keyboard */
-#define CONFIG_CMD_KEYBOARD
-#define CONFIG_KEYBOARD_COL2_INVERTED
-#define CONFIG_KEYBOARD_PROTOCOL_MKBP
-#define CONFIG_MKBP_USE_GPIO
-
-/* I2C */
-#define CONFIG_I2C
-#define CONFIG_I2C_CONTROLLER
-#define CONFIG_I2C_PASSTHRU_RESTRICTED
-#define CONFIG_I2C_VIRTUAL_BATTERY
-#define I2C_PORT_CHARGER IT83XX_I2C_CH_A
-#define I2C_PORT_BATTERY IT83XX_I2C_CH_A
-#define I2C_PORT_POWER IT83XX_I2C_CH_A
-#define I2C_PORT_ACCEL IT83XX_I2C_CH_B
-#define I2C_PORT_PPC0 IT83XX_I2C_CH_C
-#define I2C_PORT_PPC1 IT83XX_I2C_CH_E
-#define I2C_PORT_USB_MUX0 IT83XX_I2C_CH_C
-#define I2C_PORT_USB_MUX1 IT83XX_I2C_CH_E
-#define I2C_PORT_VIRTUAL_BATTERY I2C_PORT_BATTERY
-#define CONFIG_SMBUS_PEC
-
-/* LED */
-#define CONFIG_LED_COMMON
-
-/* PD / USB-C / PPC */
-#define CONFIG_CMD_PPC_DUMP
-#define CONFIG_HOSTCMD_PD_CONTROL
-#define CONFIG_IT83XX_TUNE_CC_PHY
-#define CONFIG_USB_MUX_VIRTUAL
-#define CONFIG_USBC_PPC
-#define CONFIG_USBC_PPC_DEDICATED_INT
-#define CONFIG_USBC_PPC_POLARITY
-#define CONFIG_USBC_PPC_SYV682C
-#define CONFIG_USBC_PPC_VCONN
-#define CONFIG_USBC_SS_MUX
-#define CONFIG_USBC_VCONN
-#define CONFIG_USBC_VCONN_SWAP
-#define CONFIG_USB_DRP_ACC_TRYSRC
-#define CONFIG_USB_MUX_IT5205 /* C0 */
-#define CONFIG_USB_MUX_PS8743 /* C1 */
-#define CONFIG_USB_PD_ALT_MODE
-#define CONFIG_USB_PD_ALT_MODE_DFP
-#define CONFIG_USB_PD_DECODE_SOP
-#define CONFIG_USB_PD_DISCHARGE
-#define CONFIG_USB_PD_DISCHARGE_PPC
-#define CONFIG_USB_PD_DP_HPD_GPIO
-#define CONFIG_USB_PD_DP_HPD_GPIO_CUSTOM
-#define CONFIG_USB_PD_DUAL_ROLE
-#define CONFIG_USB_PD_FRS_PPC
-#define CONFIG_USB_PD_ITE_ACTIVE_PORT_COUNT 2
-#define CONFIG_USB_PD_LOGGING
-#define CONFIG_USB_PD_PORT_MAX_COUNT 2
-#define CONFIG_USB_PD_REV30
-#define CONFIG_USB_PD_TCPC_LOW_POWER
-#define CONFIG_USB_PD_TCPM_ITE_ON_CHIP
-#define CONFIG_USB_PD_TCPM_TCPCI
-#define CONFIG_USB_PD_TCPMV2
-#define CONFIG_USB_PD_TRY_SRC
-#define CONFIG_USB_PD_VBUS_DETECT_PPC
-#define CONFIG_USB_PD_VBUS_MEASURE_ADC_EACH_PORT
-#define CONFIG_USB_PID 0x5053
-#define CONFIG_USB_POWER_DELIVERY
-
-/* USB-A */
-#define CONFIG_USB_PORT_POWER_DUMB
-#define CONFIG_USB_PORT_POWER_DUMB_CUSTOM_HOOK
-#define USB_PORT_COUNT USBA_PORT_COUNT
-
-/* UART */
-#undef CONFIG_UART_TX_BUF_SIZE
-#define CONFIG_UART_TX_BUF_SIZE 4096
-
-/* Sensor */
-#ifdef HAS_TASK_MOTIONSENSE
-#define CONFIG_CMD_ACCEL_INFO
-#define CONFIG_CMD_ACCELS
-
-#define CONFIG_ACCEL_FIFO
-#define CONFIG_ACCEL_FIFO_SIZE 256
-#define CONFIG_ACCEL_FIFO_THRES (CONFIG_ACCEL_FIFO_SIZE / 3)
-#define CONFIG_ACCEL_INTERRUPTS
-#endif
-
-/* SPI / Host Command */
-#define CONFIG_SPI
-
-/* MKBP */
-#define CONFIG_MKBP_EVENT
-
-#define CONFIG_KEYBOARD_PROTOCOL_MKBP
-#define CONFIG_MKBP_USE_GPIO
-
-/* Voltage regulator control */
-#define CONFIG_HOSTCMD_REGULATOR
-
-/* Define the host events which are allowed to wakeup AP in S3. */
-#define CONFIG_MKBP_HOST_EVENT_WAKEUP_MASK \
- (EC_HOST_EVENT_MASK(EC_HOST_EVENT_AC_CONNECTED) | \
- EC_HOST_EVENT_MASK(EC_HOST_EVENT_AC_DISCONNECTED) | \
- EC_HOST_EVENT_MASK(EC_HOST_EVENT_LID_OPEN) | \
- EC_HOST_EVENT_MASK(EC_HOST_EVENT_HANG_DETECT) | \
- EC_HOST_EVENT_MASK(EC_HOST_EVENT_MODE_CHANGE) | \
- EC_HOST_EVENT_MASK(EC_HOST_EVENT_POWER_BUTTON))
-
-/* And the MKBP events */
-#define CONFIG_MKBP_EVENT_WAKEUP_MASK \
- (BIT(EC_MKBP_EVENT_KEY_MATRIX) | \
- BIT(EC_MKBP_EVENT_HOST_EVENT))
-
-#include "baseboard_common.h"
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-#include "registers.h"
-#include "power/mt8192.h"
-
-void board_reset_pd_mcu(void);
-enum board_sub_board board_get_sub_board(void);
-void usb_a0_interrupt(enum gpio_signal signal);
-
-#endif /* !__ASSEMBLER__ */
-#endif /* __CROS_EC_BASEBOARD_H */
diff --git a/baseboard/corsola/build.mk b/baseboard/corsola/build.mk
deleted file mode 100644
index ce7b7272bd..0000000000
--- a/baseboard/corsola/build.mk
+++ /dev/null
@@ -1,15 +0,0 @@
-# -*- makefile -*-
-# Copyright 2021 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.
-#
-# Baseboard specific files build
-#
-
-baseboard-y=baseboard.o
-baseboard-y+=board_chipset.o
-baseboard-y+=board_id.o
-baseboard-y+=hibernate.o
-baseboard-y+=regulator.o
-baseboard-y+=usbc_config.o
-baseboard-$(CONFIG_USB_POWER_DELIVERY)+=usb_pd_policy.o
diff --git a/board/kingler/board.c b/board/kingler/board.c
deleted file mode 100644
index e01d64c386..0000000000
--- a/board/kingler/board.c
+++ /dev/null
@@ -1,188 +0,0 @@
-/* Copyright 2021 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.
- */
-/* Corsola board configuration */
-
-#include "adc.h"
-#include "button.h"
-#include "charge_manager.h"
-#include "charge_state_v2.h"
-#include "charger.h"
-#include "chipset.h"
-#include "common.h"
-#include "console.h"
-#include "driver/accel_lis2dw12.h"
-#include "driver/accelgyro_icm_common.h"
-#include "driver/accelgyro_icm426xx.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "keyboard_scan.h"
-#include "lid_switch.h"
-#include "motion_sense.h"
-#include "power.h"
-#include "pwm.h"
-#include "pwm_chip.h"
-#include "regulator.h"
-#include "spi.h"
-#include "switch.h"
-#include "tablet_mode.h"
-#include "task.h"
-#include "timer.h"
-#include "uart.h"
-
-/* Initialize board. */
-static void board_init(void)
-{
- /* Enable motion sensor interrupt */
- gpio_enable_interrupt(GPIO_BASE_IMU_INT_L);
- gpio_enable_interrupt(GPIO_LID_ACCEL_INT_L);
-}
-DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);
-
-/* Sensor */
-static struct mutex g_base_mutex;
-static struct mutex g_lid_mutex;
-
-static struct stprivate_data g_lis2dwl_data;
-static struct icm_drv_data_t g_icm426xx_data;
-
-struct motion_sensor_t motion_sensors[] = {
- /*
- * Note: icm426xx: supports accelerometer and gyro sensor
- * Requirement: accelerometer sensor must init before gyro sensor
- * DO NOT change the order of the following table.
- */
- [BASE_ACCEL] = {
- .name = "Base Accel",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_ICM426XX,
- .type = MOTIONSENSE_TYPE_ACCEL,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &icm426xx_drv,
- .mutex = &g_base_mutex,
- .drv_data = &g_icm426xx_data,
- .port = I2C_PORT_ACCEL,
- .i2c_spi_addr_flags = ICM426XX_ADDR0_FLAGS,
- .default_range = 4, /* g, to meet CDD 7.3.1/C-1-4 reqs. */
- .rot_standard_ref = NULL,
- .min_frequency = ICM426XX_ACCEL_MIN_FREQ,
- .max_frequency = ICM426XX_ACCEL_MAX_FREQ,
- .config = {
- /* EC use accel for angle detection */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 10000 | ROUND_UP_FLAG,
- .ec_rate = 100 * MSEC,
- },
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 10000 | ROUND_UP_FLAG,
- },
- },
- },
- [BASE_GYRO] = {
- .name = "Base Gyro",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_ICM426XX,
- .type = MOTIONSENSE_TYPE_GYRO,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &icm426xx_drv,
- .mutex = &g_base_mutex,
- .port = I2C_PORT_ACCEL,
- .i2c_spi_addr_flags = ICM426XX_ADDR0_FLAGS,
- .default_range = 1000, /* dps */
- .rot_standard_ref = NULL,
- .min_frequency = ICM426XX_GYRO_MIN_FREQ,
- .max_frequency = ICM426XX_GYRO_MAX_FREQ,
- },
- [LID_ACCEL] = {
- .name = "Lid Accel",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_LIS2DWL,
- .type = MOTIONSENSE_TYPE_ACCEL,
- .location = MOTIONSENSE_LOC_LID,
- .drv = &lis2dw12_drv,
- .mutex = &g_lid_mutex,
- .drv_data = &g_lis2dwl_data,
- .int_signal = GPIO_LID_ACCEL_INT_L,
- .port = I2C_PORT_ACCEL,
- .i2c_spi_addr_flags = LIS2DWL_ADDR1_FLAGS,
- .flags = MOTIONSENSE_FLAG_INT_SIGNAL,
- .rot_standard_ref = NULL, /* identity matrix */
- .default_range = 2, /* g */
- .min_frequency = LIS2DW12_ODR_MIN_VAL,
- .max_frequency = LIS2DW12_ODR_MAX_VAL,
- .config = {
- /* EC use accel for angle detection */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 12500 | ROUND_UP_FLAG,
- },
- /* Sensor on for lid angle detection */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 10000 | ROUND_UP_FLAG,
- },
- },
- },
-};
-const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
-
-void motion_interrupt(enum gpio_signal signal)
-{
- icm426xx_interrupt(signal);
-}
-
-/* ADC channels. Must be in the exactly same order as in enum adc_channel. */
-const struct adc_t adc_channels[] = {
- /* Convert to mV (3000mV/1024). */
- {"VBUS_C0", ADC_MAX_MVOLT * 10, ADC_READ_MAX + 1, 0, CHIP_ADC_CH0},
- {"BOARD_ID_0", ADC_MAX_MVOLT, ADC_READ_MAX + 1, 0, CHIP_ADC_CH1},
- {"BOARD_ID_1", ADC_MAX_MVOLT, ADC_READ_MAX + 1, 0, CHIP_ADC_CH2},
- /* AMON/BMON gain = 17.97 */
- {"CHARGER_AMON_R", ADC_MAX_MVOLT * 1000 / 17.97, ADC_READ_MAX + 1, 0,
- CHIP_ADC_CH3},
- {"VBUS_C1", ADC_MAX_MVOLT * 10, ADC_READ_MAX + 1, 0, CHIP_ADC_CH5},
- {"CHARGER_PMON", ADC_MAX_MVOLT, ADC_READ_MAX + 1, 0, CHIP_ADC_CH6},
-};
-BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
-
-/* PWM */
-
-/*
- * PWM channels. Must be in the exactly same order as in enum pwm_channel.
- * There total three 16 bits clock prescaler registers for all pwm channels,
- * so use the same frequency and prescaler register setting is required if
- * number of pwm channel greater than three.
- */
-const struct pwm_t pwm_channels[] = {
- [PWM_CH_LED1] = {
- .channel = 0,
- .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
- .freq_hz = 324, /* maximum supported frequency */
- .pcfsr_sel = PWM_PRESCALER_C4
- },
- [PWM_CH_LED2] = {
- .channel = 1,
- .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
- .freq_hz = 324, /* maximum supported frequency */
- .pcfsr_sel = PWM_PRESCALER_C4
- },
- [PWM_CH_LED3] = {
- .channel = 2,
- .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
- .freq_hz = 324, /* maximum supported frequency */
- .pcfsr_sel = PWM_PRESCALER_C4
- },
-};
-BUILD_ASSERT(ARRAY_SIZE(pwm_channels) == PWM_CH_COUNT);
-
-static void board_suspend(void)
-{
- gpio_set_level(GPIO_EN_5V_USM, 0);
-}
-DECLARE_HOOK(HOOK_CHIPSET_SUSPEND, board_suspend, HOOK_PRIO_DEFAULT);
-
-static void board_resume(void)
-{
- gpio_set_level(GPIO_EN_5V_USM, 1);
-}
-DECLARE_HOOK(HOOK_CHIPSET_RESUME, board_resume, HOOK_PRIO_DEFAULT);
diff --git a/board/kingler/board.h b/board/kingler/board.h
deleted file mode 100644
index 857e654787..0000000000
--- a/board/kingler/board.h
+++ /dev/null
@@ -1,118 +0,0 @@
-/* Copyright 2021 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.
- */
-/* Krabby board configuration */
-
-#ifndef __CROS_EC_BOARD_H
-#define __CROS_EC_BOARD_H
-
-#include "baseboard.h"
-
-/* Chipset config */
-
-/* Optional features */
-#define CONFIG_LTO
-
-/*
- * TODO: Remove this option once the VBAT no longer keeps high when
- * system's power isn't presented.
- */
-#define CONFIG_IT83XX_RESET_PD_CONTRACT_IN_BRAM
-
-/* BC12 */
-/* TODO(b/159583342): remove after rev0 deprecated */
-#define CONFIG_MT6360_BC12_GPIO
-
-/* LED */
-#define CONFIG_LED_ONOFF_STATES
-#define CONFIG_LED_ONOFF_STATES_BAT_LOW 10
-
-/* PD / USB-C / PPC */
-#define CONFIG_USB_PD_DEBUG_LEVEL 3
-#define PD_MAX_CURRENT_MA 3000
-#define PD_OPERATING_POWER_MW 15000
-#define PD_MAX_VOLTAGE_MV 15000
-#define PD_MAX_POWER_MW 45000
-#define PD_POWER_SUPPLY_TURN_ON_DELAY 30000 /* us */
-#define PD_POWER_SUPPLY_TURN_OFF_DELAY 250000 /* us */
-
-/* Optional console commands */
-#define CONFIG_CMD_FLASH
-#define CONFIG_CMD_SCRATCHPAD
-#define CONFIG_CMD_STACKOVERFLOW
-
-#define CONFIG_BATT_FULL_CHIPSET_OFF_INPUT_LIMIT_MV 9000
-
-/* Sensor */
-#define CONFIG_GMR_TABLET_MODE
-#define CONFIG_TABLET_MODE
-#define CONFIG_TABLET_MODE_SWITCH
-#define GMR_TABLET_MODE_GPIO_L GPIO_TABLET_MODE_L
-
-#define CONFIG_ACCELGYRO_BMI160 /* Base accel */
-#define CONFIG_ACCELGYRO_BMI160_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(BASE_ACCEL)
-#define CONFIG_ACCELGYRO_ICM426XX /* Base accel */
-#define CONFIG_ACCELGYRO_ICM426XX_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(BASE_ACCEL)
-
-#define CONFIG_ACCEL_LIS2DWL
-#define CONFIG_ACCEL_LIS2DW_AS_BASE
-#define CONFIG_ACCEL_LIS2DW12_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(LID_ACCEL)
-
-#define CONFIG_LID_ANGLE
-#define CONFIG_LID_ANGLE_SENSOR_BASE BASE_ACCEL
-#define CONFIG_LID_ANGLE_SENSOR_LID LID_ACCEL
-#define CONFIG_LID_ANGLE_UPDATE
-
-#define CONFIG_ACCEL_FORCE_MODE_MASK 0
-
-/* SPI / Host Command */
-#undef CONFIG_HOSTCMD_DEBUG_MODE
-#define CONFIG_HOSTCMD_DEBUG_MODE HCDEBUG_OFF
-
-/* USB-A */
-#define USBA_PORT_COUNT 1
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-#include "registers.h"
-
-enum battery_type {
- BATTERY_C235,
- BATTERY_TYPE_COUNT,
-};
-
-enum sensor_id {
- BASE_ACCEL = 0,
- BASE_GYRO,
- LID_ACCEL,
- SENSOR_COUNT,
-};
-
-enum adc_channel {
- ADC_VBUS_C0, /* ADC 0 */
- ADC_BOARD_ID_0, /* ADC 1 */
- ADC_BOARD_ID_1, /* ADC 2 */
- ADC_CHARGER_AMON_R, /* ADC 3 */
- ADC_VBUS_C1, /* ADC 5 */
- ADC_CHARGER_PMON, /* ADC 6 */
-
- /* Number of ADC channels */
- ADC_CH_COUNT,
-};
-
-enum pwm_channel {
- PWM_CH_LED1,
- PWM_CH_LED2,
- PWM_CH_LED3,
- PWM_CH_COUNT,
-};
-
-void motion_interrupt(enum gpio_signal signal);
-
-#endif /* !__ASSEMBLER__ */
-#endif /* __CROS_EC_BOARD_H */
diff --git a/board/kingler/build.mk b/board/kingler/build.mk
deleted file mode 100644
index b355dfd90d..0000000000
--- a/board/kingler/build.mk
+++ /dev/null
@@ -1,16 +0,0 @@
-# -*- makefile -*-
-# Copyright 2021 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.
-#
-# Board specific files build
-
-# the IC is ITE IT8xxx2
-CHIP:=it83xx
-CHIP_FAMILY:=it8xxx2
-CHIP_VARIANT:=it81202bx_1024
-BASEBOARD:=corsola
-
-board-y=led.o
-board-y+=battery.o board.o
-board-y+=usbc_config.o
diff --git a/board/kingler/ec.tasklist b/board/kingler/ec.tasklist
deleted file mode 100644
index 75dbb1a828..0000000000
--- a/board/kingler/ec.tasklist
+++ /dev/null
@@ -1,22 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/**
- * See CONFIG_TASK_LIST in config.h for details.
- */
-#define CONFIG_TASK_LIST \
- TASK_ALWAYS(HOOKS, hook_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_NOTEST(CHIPSET, chipset_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(CHARGER, charger_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P0, usb_charger_task, 0, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P1, usb_charger_task, 1, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(MOTIONSENSE, motion_sense_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_NOTEST(PDCMD, pd_command_task, NULL, 1024) \
- TASK_ALWAYS(HOSTCMD, host_command_task, NULL, 1024) \
- TASK_ALWAYS(CONSOLE, console_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_NOTEST(KEYSCAN, keyboard_scan_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(PD_C0, pd_task, NULL, 1280) \
- TASK_ALWAYS(PD_C1, pd_task, NULL, 1280) \
-
diff --git a/board/kingler/gpio.inc b/board/kingler/gpio.inc
deleted file mode 100644
index 1d4700c1c1..0000000000
--- a/board/kingler/gpio.inc
+++ /dev/null
@@ -1,160 +0,0 @@
-/* -*- mode:c -*-
- *
- * Copyright 2021 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.
- */
-
-/* Declare symbolic names for all the GPIOs that we care about.
- * Note: Those with interrupt handlers must be declared first. */
-
-/* Wake Source interrupts */
-GPIO_INT(POWER_BUTTON_L, PIN(E, 4), GPIO_INT_BOTH | GPIO_PULL_UP |
- GPIO_HIB_WAKE_HIGH, power_button_interrupt) /* H1_EC_PWR_BTN_ODL */
-GPIO_INT(LID_OPEN, PIN(E, 2), GPIO_INT_BOTH | GPIO_HIB_WAKE_HIGH,
- lid_interrupt)
-GPIO_INT(TABLET_MODE_L, PIN(J, 7), GPIO_INT_BOTH,
- gmr_tablet_switch_isr)
-
-/* Chipset interrupts */
-GPIO_INT(AP_EC_WARM_RST_REQ, PIN(D, 3), GPIO_INT_RISING | GPIO_SEL_1P8V,
- chipset_reset_request_interrupt)
-
-/* Power sequencing interrupts */
-GPIO_INT(AP_EC_WATCHDOG_L, PIN(C, 7), GPIO_INT_BOTH | GPIO_SEL_1P8V,
- chipset_watchdog_interrupt)
-GPIO_INT(AP_IN_SLEEP_L, PIN(F, 2),
- GPIO_INT_BOTH | GPIO_PULL_DOWN | GPIO_SEL_1P8V, power_signal_interrupt)
-GPIO_INT(PMIC_EC_PWRGD, PIN(F, 3),
- GPIO_INT_BOTH | GPIO_PULL_DOWN | GPIO_SEL_1P8V, power_signal_interrupt)
-
-/* Sensor Interrupts */
-GPIO_INT(BASE_IMU_INT_L, PIN(J, 2), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- motion_interrupt)
-GPIO_INT(LID_ACCEL_INT_L, PIN(J, 3), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- lis2dw12_interrupt)
-GPIO(ALS_RGB_INT_ODL, PIN(F, 0), GPIO_INPUT)
-
-/* USB-C interrupts */
-/* TODO: driver not ready */
-GPIO(USB_C0_PPC_INT_ODL, PIN(D, 1), GPIO_INT_BOTH)
-GPIO_INT(USB_C0_BC12_INT_ODL,PIN(J, 6), GPIO_INT_FALLING, bc12_interrupt)
-GPIO_INT(USB_C1_BC12_INT_L, PIN(J, 4), GPIO_INT_FALLING, bc12_interrupt)
-
-/* Volume button interrupts */
-GPIO_INT(VOLUME_DOWN_L, PIN(D, 5), GPIO_INT_BOTH | GPIO_PULL_UP,
- button_interrupt) /* EC_VOLDN_BTN_ODL */
-GPIO_INT(VOLUME_UP_L, PIN(D, 6), GPIO_INT_BOTH | GPIO_PULL_UP,
- button_interrupt) /* EC_VOLUP_BTN_ODL */
-
-/* Other interrupts */
-GPIO_INT(AP_XHCI_INIT_DONE, PIN(D, 2), GPIO_INT_BOTH | GPIO_PULL_DOWN | GPIO_SEL_1P8V,
- usb_a0_interrupt)
-GPIO_INT(AC_PRESENT, PIN(E, 5), GPIO_INT_BOTH | GPIO_HIB_WAKE_HIGH,
- extpower_interrupt) /* AC_OK / AC_PRESENT in rev1+ */
-GPIO_INT(UART1_RX, PIN(B, 0), GPIO_INT_FALLING,
- uart_deepsleep_interrupt) /* UART_DEBUG_TX_EC_RX */
-GPIO_INT(WP, PIN(I, 4), GPIO_INT_BOTH | GPIO_SEL_1P8V,
- switch_interrupt) /* EC_FLASH_WP_OD */
-GPIO_INT(SPI0_CS, PIN(M, 5), GPIO_INT_FALLING,
- spi_event) /* SPI slave Chip Select -- AP_SPI_EC_CS_L */
-GPIO_INT(X_EC_GPIO2, PIN(B, 2), GPIO_ODR_HIGH, x_ec_interrupt)
-
-/* Power Sequencing Signals */
-GPIO(EC_PMIC_EN_ODL, PIN(D, 0), GPIO_ODR_HIGH | GPIO_SEL_1P8V)
-GPIO(EC_PMIC_WATCHDOG_L, PIN(H, 0), GPIO_ODR_LOW | GPIO_SEL_1P8V)
-GPIO(EN_PP5000_A, PIN(C, 6), GPIO_OUT_HIGH)
-GPIO(PG_MT6315_PROC_ODL, PIN(E, 1), GPIO_INPUT)
-GPIO(PG_MT6360_ODL, PIN(F, 1), GPIO_INPUT)
-GPIO(PG_PP5000_A_ODL, PIN(A, 6), GPIO_INPUT)
-GPIO(EN_ULP, PIN(E, 3), GPIO_OUT_LOW)
-GPIO(SYS_RST_ODL, PIN(B, 6), GPIO_ODR_LOW)
-GPIO(EC_BL_EN_OD, PIN(B, 5), GPIO_ODR_LOW | GPIO_SEL_1P8V)
-
-/* MKBP event synchronization */
-GPIO(EC_INT_L, PIN(E, 6), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_AP_INT_ODL */
-
-/* USB and USBC Signals */
-GPIO(DP_AUX_PATH_SEL, PIN(G, 0), GPIO_OUT_HIGH)
-GPIO(EC_AP_DP_HPD_ODL, PIN(J, 0), GPIO_ODR_HIGH | GPIO_SEL_1P8V)
-GPIO(EN_PP5000_USB_A0_VBUS, PIN(B, 7), GPIO_OUT_LOW)
-GPIO(USB_C0_FRS_EN, PIN(H, 3), GPIO_OUT_LOW)
-
-/* Misc Signals */
-GPIO(EC_BATT_PRES_ODL, PIN(C, 0), GPIO_INPUT)
-GPIO(BC12_DET_EN, PIN(J, 5), GPIO_OUT_LOW) /* EN_USB_C0_BC12_DET */
-GPIO(EN_EC_ID_ODL, PIN(H, 5), GPIO_ODR_LOW)
-GPIO(ENTERING_RW, PIN(C, 5), GPIO_OUT_LOW) /* EC_ENTERING_RW */
-GPIO(EN_5V_USM, PIN(D, 7), GPIO_OUT_LOW)
-
-/* I2C pins - Alternate function below configures I2C module on these pins */
-GPIO(I2C_A_SCL, PIN(B, 3), GPIO_INPUT) /* I2C_CHG_BATT_SCL */
-GPIO(I2C_A_SDA, PIN(B, 4), GPIO_INPUT) /* I2C_CHG_BATT_SDA */
-GPIO(I2C_B_SCL, PIN(C, 1), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_SENSOR_SCL */
-GPIO(I2C_B_SDA, PIN(C, 2), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_SENSOR_SDA */
-GPIO(I2C_C_SCL, PIN(F, 6), GPIO_INPUT) /* I2C_USB_C0_SCL */
-GPIO(I2C_C_SDA, PIN(F, 7), GPIO_INPUT) /* I2C_USB_C0_SCL */
-GPIO(I2C_E_SCL, PIN(E, 0), GPIO_INPUT) /* I2C_USB_C1_SCL */
-GPIO(I2C_E_SDA, PIN(E, 7), GPIO_INPUT) /* I2C_USB_C1_SDA */
-
-/* SPI pins - Alternate function below configures SPI module on these pins */
-
-/* NC / TP */
-
-/* Keyboard pins */
-
-/* Subboards HDMI/TYPEC */
-GPIO(EC_X_GPIO1, PIN(H, 4), GPIO_OUT_LOW)
-GPIO(EC_X_GPIO3, PIN(J, 1), GPIO_INPUT)
-
-/* Alternate functions GPIO definitions */
-ALTERNATE(PIN_MASK(B, 0x18), 1, MODULE_I2C, 0) /* I2C A */
-ALTERNATE(PIN_MASK(C, 0x06), 1, MODULE_I2C, GPIO_SEL_1P8V) /* I2C B */
-ALTERNATE(PIN_MASK(F, 0xC0), 1, MODULE_I2C, 0) /* I2C C */
-ALTERNATE(PIN_MASK(E, 0x81), 1, MODULE_I2C, 0) /* I2C E */
-
-/* UART */
-ALTERNATE(PIN_MASK(B, 0x03), 1, MODULE_UART, 0) /* EC to Servo */
-
-/* PWM */
-ALTERNATE(PIN_MASK(A, 0x07), 1, MODULE_PWM, 0) /* PWM 0~2 */
-
-/* ADC */
-ALTERNATE(PIN_MASK(I, 0x6F), 0, MODULE_ADC, 0) /* ADC 0,1,2,3,5,6 */
-
-/* SPI */
-ALTERNATE(PIN_MASK(M, 0x33), 0, MODULE_SPI, 0) /* SPI */
-
-/* Unimplemented Pins */
-GPIO(SET_VMC_VOLT_AT_1V8, PIN(D, 4), GPIO_INPUT | GPIO_PULL_DOWN | GPIO_SEL_1P8V)
-GPIO(PACKET_MODE_EN, PIN(A, 3), GPIO_INPUT | GPIO_PULL_DOWN)
-/* b/160218054: behavior not defined */
-/* *_ODL pin has external pullup so don't pull it down. */
-GPIO(USB_A0_FAULT_ODL, PIN(A, 7), GPIO_INPUT)
-GPIO(CHARGER_PROCHOT_ODL, PIN(C, 3), GPIO_INPUT)
-GPIO(PG_MT6315_GPU_ODL, PIN(H, 6), GPIO_INPUT)
-GPIO(EN_PP3000_SD_U, PIN(G, 1), GPIO_INPUT | GPIO_PULL_DOWN | GPIO_SEL_1P8V)
-/* reserved for future use */
-GPIO(CCD_MODE_ODL, PIN(C, 4), GPIO_INPUT)
-/*
- * ADC pins don't have internal pull-down capability,
- * so we set them as output low.
- */
-GPIO(NC_GPI7, PIN(I, 7), GPIO_OUT_LOW)
-/* NC pins, enable internal pull-up/down to avoid floating state. */
-GPIO(NC_GPM2, PIN(M, 2), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPM3, PIN(M, 3), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPM6, PIN(M, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(SPI_CLK_GPG6, PIN(G, 6), GPIO_INPUT | GPIO_PULL_UP)
-/*
- * These 4 pins don't have internal pull-down capability,
- * so we set them as output low.
- */
-GPIO(NC_GPG3, PIN(G, 3), GPIO_OUT_LOW)
-GPIO(SPI_MOSI_GPG4, PIN(G, 4), GPIO_OUT_LOW)
-GPIO(SPI_MISO_GPG5, PIN(G, 5), GPIO_OUT_LOW)
-GPIO(SPI_CS_GPG7, PIN(G, 7), GPIO_OUT_LOW)
-
-UNIMPLEMENTED(USB_C0_PPC_BC12_INT_ODL)
-UNIMPLEMENTED(USB_C0_PPC_FRSINFO)
-UNIMPLEMENTED(USB_C1_BC12_CHARGER_INT_ODL)
diff --git a/board/kingler/usbc_config.c b/board/kingler/usbc_config.c
deleted file mode 100644
index 485a02c10f..0000000000
--- a/board/kingler/usbc_config.c
+++ /dev/null
@@ -1,28 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/* Krabby board-specific USB-C configuration */
-
-#include "driver/tcpm/it83xx_pd.h"
-#include "driver/usb_mux/ps8743.h"
-#include "hooks.h"
-
-void board_usb_mux_init(void)
-{
- if (board_get_sub_board() == SUB_BOARD_TYPEC) {
- ps8743_tune_usb_eq(&usb_muxes[1],
- PS8743_USB_EQ_TX_12_8_DB,
- PS8743_USB_EQ_RX_12_8_DB);
- ps8743_write(&usb_muxes[1],
- PS8743_REG_HS_DET_THRESHOLD,
- PS8743_USB_HS_THRESH_NEG_10);
- }
-}
-DECLARE_HOOK(HOOK_INIT, board_usb_mux_init, HOOK_PRIO_INIT_I2C + 1);
-
-const struct cc_para_t *board_get_cc_tuning_parameter(enum usbpd_port port)
-{
- return NULL;
-}
diff --git a/board/kingler/vif_override.xml b/board/kingler/vif_override.xml
deleted file mode 100644
index 32736caf64..0000000000
--- a/board/kingler/vif_override.xml
+++ /dev/null
@@ -1,3 +0,0 @@
-<!-- Add VIF field overrides here. See genvif.c and the Vendor Info File
- Definition from the USB-IF.
--->
diff --git a/board/krabby/battery.c b/board/krabby/battery.c
deleted file mode 100644
index f07c38e1b8..0000000000
--- a/board/krabby/battery.c
+++ /dev/null
@@ -1,47 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "battery.h"
-#include "battery_fuel_gauge.h"
-#include "battery_smart.h"
-#include "charge_manager.h"
-#include "chipset.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "system.h"
-#include "usb_pd.h"
-
-const struct board_batt_params board_battery_info[] = {
- [BATTERY_C235] = {
- .fuel_gauge = {
- .manuf_name = "AS3GWRc3KA",
- .device_name = "C235-41",
- .ship_mode = {
- .reg_addr = 0x0,
- .reg_data = { 0x10, 0x10 },
- },
- .fet = {
- .reg_addr = 0x99,
- .reg_mask = 0x0c,
- .disconnect_val = 0x0c,
- }
- },
- .batt_info = {
- .voltage_max = 8800,
- .voltage_normal = 7700,
- .voltage_min = 6000,
- .precharge_current = 256,
- .start_charging_min_c = 0,
- .start_charging_max_c = 45,
- .charging_min_c = 0,
- .charging_max_c = 60,
- .discharging_min_c = 0,
- .discharging_max_c = 60,
- },
- },
-};
-BUILD_ASSERT(ARRAY_SIZE(board_battery_info) == BATTERY_TYPE_COUNT);
-
-const enum battery_type DEFAULT_BATTERY_TYPE = BATTERY_C235;
diff --git a/board/krabby/board.h b/board/krabby/board.h
deleted file mode 100644
index 4e3dfc43d6..0000000000
--- a/board/krabby/board.h
+++ /dev/null
@@ -1,116 +0,0 @@
-/* Copyright 2021 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.
- */
-/* Krabby board configuration */
-
-#ifndef __CROS_EC_BOARD_H
-#define __CROS_EC_BOARD_H
-
-#include "baseboard.h"
-
-/* Chipset config */
-
-/* Optional features */
-#define CONFIG_LTO
-
-/*
- * TODO: Remove this option once the VBAT no longer keeps high when
- * system's power isn't presented.
- */
-#define CONFIG_IT83XX_RESET_PD_CONTRACT_IN_BRAM
-
-/* BC12 */
-
-/* LED */
-#define CONFIG_LED_ONOFF_STATES
-#define CONFIG_LED_ONOFF_STATES_BAT_LOW 10
-
-/* PD / USB-C / PPC */
-#define CONFIG_USB_PD_DEBUG_LEVEL 3
-#define PD_MAX_CURRENT_MA 3000
-#define PD_OPERATING_POWER_MW 15000
-#define PD_MAX_VOLTAGE_MV 15000
-#define PD_MAX_POWER_MW 45000
-#define PD_POWER_SUPPLY_TURN_ON_DELAY 30000 /* us */
-#define PD_POWER_SUPPLY_TURN_OFF_DELAY 250000 /* us */
-
-/* Optional console commands */
-#define CONFIG_CMD_FLASH
-#define CONFIG_CMD_SCRATCHPAD
-#define CONFIG_CMD_STACKOVERFLOW
-
-#define CONFIG_BATT_FULL_CHIPSET_OFF_INPUT_LIMIT_MV 9000
-
-/* Sensor */
-#define CONFIG_GMR_TABLET_MODE
-#define CONFIG_TABLET_MODE
-#define CONFIG_TABLET_MODE_SWITCH
-#define GMR_TABLET_MODE_GPIO_L GPIO_TABLET_MODE_L
-
-#define CONFIG_ACCELGYRO_BMI160 /* Base accel */
-#define CONFIG_ACCELGYRO_BMI160_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(BASE_ACCEL)
-#define CONFIG_ACCELGYRO_ICM426XX /* Base accel */
-#define CONFIG_ACCELGYRO_ICM426XX_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(BASE_ACCEL)
-
-#define CONFIG_ACCEL_LIS2DWL
-#define CONFIG_ACCEL_LIS2DW_AS_BASE
-#define CONFIG_ACCEL_LIS2DW12_INT_EVENT \
- TASK_EVENT_MOTION_SENSOR_INTERRUPT(LID_ACCEL)
-
-#define CONFIG_LID_ANGLE
-#define CONFIG_LID_ANGLE_SENSOR_BASE BASE_ACCEL
-#define CONFIG_LID_ANGLE_SENSOR_LID LID_ACCEL
-#define CONFIG_LID_ANGLE_UPDATE
-
-#define CONFIG_ACCEL_FORCE_MODE_MASK 0
-
-/* SPI / Host Command */
-#undef CONFIG_HOSTCMD_DEBUG_MODE
-#define CONFIG_HOSTCMD_DEBUG_MODE HCDEBUG_OFF
-
-/* USB-A */
-#define USBA_PORT_COUNT 1
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-#include "registers.h"
-
-enum battery_type {
- BATTERY_C235,
- BATTERY_TYPE_COUNT,
-};
-
-enum sensor_id {
- BASE_ACCEL = 0,
- BASE_GYRO,
- LID_ACCEL,
- SENSOR_COUNT,
-};
-
-enum adc_channel {
- ADC_VBUS_C0, /* ADC 0 */
- ADC_BOARD_ID_0, /* ADC 1 */
- ADC_BOARD_ID_1, /* ADC 2 */
- ADC_CHARGER_AMON_R, /* ADC 3 */
- ADC_VBUS_C1, /* ADC 5 */
- ADC_CHARGER_PMON, /* ADC 6 */
-
- /* Number of ADC channels */
- ADC_CH_COUNT,
-};
-
-enum pwm_channel {
- PWM_CH_LED1,
- PWM_CH_LED2,
- PWM_CH_LED3,
- PWM_CH_COUNT,
-};
-
-void motion_interrupt(enum gpio_signal signal);
-
-#endif /* !__ASSEMBLER__ */
-#endif /* __CROS_EC_BOARD_H */
diff --git a/board/krabby/build.mk b/board/krabby/build.mk
deleted file mode 100644
index 86903344a1..0000000000
--- a/board/krabby/build.mk
+++ /dev/null
@@ -1,16 +0,0 @@
-# -*- makefile -*-
-# Copyright 2021 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.
-#
-# Board specific files build
-
-# the IC is ITE IT8xxx2
-CHIP:=it83xx
-CHIP_FAMILY:=it8xxx2
-CHIP_VARIANT:=it81202bx_1024
-BASEBOARD:=corsola
-
-board-y=led.o
-board-y+=battery.o board.o hooks.o
-board-y+=usbc_config.o
diff --git a/board/krabby/ec.tasklist b/board/krabby/ec.tasklist
deleted file mode 100644
index 75dbb1a828..0000000000
--- a/board/krabby/ec.tasklist
+++ /dev/null
@@ -1,22 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/**
- * See CONFIG_TASK_LIST in config.h for details.
- */
-#define CONFIG_TASK_LIST \
- TASK_ALWAYS(HOOKS, hook_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_NOTEST(CHIPSET, chipset_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(CHARGER, charger_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P0, usb_charger_task, 0, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P1, usb_charger_task, 1, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(MOTIONSENSE, motion_sense_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_NOTEST(PDCMD, pd_command_task, NULL, 1024) \
- TASK_ALWAYS(HOSTCMD, host_command_task, NULL, 1024) \
- TASK_ALWAYS(CONSOLE, console_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_NOTEST(KEYSCAN, keyboard_scan_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(PD_C0, pd_task, NULL, 1280) \
- TASK_ALWAYS(PD_C1, pd_task, NULL, 1280) \
-
diff --git a/board/krabby/gpio.inc b/board/krabby/gpio.inc
deleted file mode 100644
index be37d43fb8..0000000000
--- a/board/krabby/gpio.inc
+++ /dev/null
@@ -1,157 +0,0 @@
-/* -*- mode:c -*-
- *
- * Copyright 2021 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.
- */
-
-/* Declare symbolic names for all the GPIOs that we care about.
- * Note: Those with interrupt handlers must be declared first. */
-
-/* Wake Source interrupts */
-GPIO_INT(POWER_BUTTON_L, PIN(E, 4),
- GPIO_INT_BOTH | GPIO_HIB_WAKE_HIGH,
- power_button_interrupt) /* GSC_EC_PWR_BTN_ODL */
-GPIO_INT(LID_OPEN, PIN(E, 2), GPIO_INT_BOTH | GPIO_HIB_WAKE_HIGH,
- lid_interrupt) /* LID_OPEN_3V3 */
-GPIO_INT(TABLET_MODE_L, PIN(J, 7), GPIO_INT_BOTH,
- gmr_tablet_switch_isr)
-
-/* Chipset interrupts */
-GPIO_INT(AP_EC_WARM_RST_REQ, PIN(D, 3), GPIO_INT_RISING | GPIO_SEL_1P8V,
- chipset_reset_request_interrupt)
-
-/* Power sequencing interrupts */
-GPIO_INT(AP_IN_SLEEP_L, PIN(B, 6),
- GPIO_INT_BOTH | GPIO_SEL_1P8V, power_signal_interrupt)
-
-/* Sensor Interrupts */
-GPIO_INT(BASE_IMU_INT_L, PIN(M, 3), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- motion_interrupt)
-GPIO_INT(LID_ACCEL_INT_L, PIN(M, 2), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- lis2dw12_interrupt)
-
-/* Volume button interrupts */
-GPIO_INT(VOLUME_DOWN_L, PIN(D, 5), GPIO_INT_BOTH,
- button_interrupt) /* EC_VOLDN_BTN_ODL */
-GPIO_INT(VOLUME_UP_L, PIN(D, 6), GPIO_INT_BOTH,
- button_interrupt) /* EC_VOLUP_BTN_ODL */
-
-/* Other interrupts */
-GPIO_INT(AP_XHCI_INIT_DONE, PIN(J, 5),
- GPIO_INT_BOTH | GPIO_SEL_1P8V,
- usb_a0_interrupt)
-GPIO_INT(AC_PRESENT, PIN(E, 5), GPIO_INT_BOTH | GPIO_HIB_WAKE_HIGH,
- extpower_interrupt) /* GSC_ACOK_OD */
-GPIO_INT(UART1_RX, PIN(B, 0), GPIO_INT_FALLING,
- uart_deepsleep_interrupt) /* UART_DEBUG_TX_EC_RX */
-GPIO_INT(WP, PIN(I, 4), GPIO_INT_BOTH | GPIO_SEL_1P8V,
- switch_interrupt) /* EC_FLASH_WP_OD */
-GPIO_INT(SPI0_CS, PIN(M, 5), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- spi_event) /* SPI slave Chip Select -- AP_EC_SPI_CS_L */
-GPIO_INT(X_EC_GPIO2, PIN(B, 2), GPIO_INT_BOTH | GPIO_ODR_HIGH,
- x_ec_interrupt)
-
-/* USB-C interrupts */
-/* TODO: interrupt function not ready */
-GPIO(USB_C0_PPC_BC12_INT_ODL, PIN(D, 1), GPIO_INT_FALLING)
-GPIO(USB_C1_BC12_CHARGER_INT_ODL, PIN(J, 4), GPIO_INT_FALLING)
-
-/* Power Sequencing Signals */
-GPIO(EC_PMIC_EN_ODL, PIN(D, 0), GPIO_ODR_HIGH | GPIO_SEL_1P8V)
-GPIO(EN_PP5000_Z2, PIN(C, 6), GPIO_OUT_HIGH)
-GPIO(EN_ULP, PIN(E, 3), GPIO_OUT_LOW)
-GPIO(SYS_RST_ODL, PIN(G, 1), GPIO_ODR_LOW)
-GPIO(EC_BL_EN_OD, PIN(B, 5), GPIO_ODR_LOW | GPIO_SEL_1P8V)
-GPIO(AP_EC_SYSRST_ODL, PIN(J, 2), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(AP_EC_WDTRST_L, PIN(C, 7), GPIO_INPUT | GPIO_SEL_1P8V)
-
-/* MKBP event synchronization */
-GPIO(EC_INT_L, PIN(E, 6), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_AP_INT_ODL */
-
-/* USB and USBC Signals */
-GPIO(DP_AUX_PATH_SEL, PIN(G, 0), GPIO_OUT_HIGH)
-GPIO(EC_AP_DP_HPD_ODL, PIN(J, 0), GPIO_ODR_HIGH)
-GPIO(EN_PP5000_USB_A0_VBUS, PIN(B, 7), GPIO_OUT_LOW)
-GPIO(USB_C0_PPC_FRSINFO, PIN(F, 0), GPIO_INPUT)
-
-/* Misc Signals */
-GPIO(EC_BATT_PRES_ODL, PIN(C, 0), GPIO_INPUT)
-GPIO(EN_EC_ID_ODL, PIN(H, 5), GPIO_ODR_LOW)
-GPIO(ENTERING_RW, PIN(C, 5), GPIO_OUT_LOW) /* EC_ENTERING_RW */
-GPIO(EN_5V_USM, PIN(G, 3), GPIO_OUT_LOW)
-GPIO(USB_A0_FAULT_ODL, PIN(J, 6), GPIO_INPUT)
-
-/* I2C pins - Alternate function below configures I2C module on these pins */
-GPIO(I2C_A_SCL, PIN(B, 3), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_PWR_CBI_SCL */
-GPIO(I2C_A_SDA, PIN(B, 4), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_PWR_CBI_SDA */
-GPIO(I2C_B_SCL, PIN(C, 1), GPIO_INPUT) /* I2C_BATT_SCL_3V3 */
-GPIO(I2C_B_SDA, PIN(C, 2), GPIO_INPUT) /* I2C_BATT_SDA_3V3 */
-GPIO(I2C_C_SCL, PIN(F, 6), GPIO_INPUT) /* I2C_USB_C0_SCL */
-GPIO(I2C_C_SDA, PIN(F, 7), GPIO_INPUT) /* I2C_USB_C0_SDA */
-GPIO(I2C_D_SCL, PIN(F, 2), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_SENSOR_SCL */
-GPIO(I2C_D_SDA, PIN(F, 3), GPIO_INPUT | GPIO_SEL_1P8V) /* I2C_SENSOR_SDA */
-GPIO(I2C_E_SCL, PIN(E, 0), GPIO_INPUT) /* I2C_USB_C1_SCL */
-GPIO(I2C_E_SDA, PIN(E, 7), GPIO_INPUT) /* I2C_USB_C1_SDA */
-GPIO(I2C_F_SCL, PIN(A, 4), GPIO_INPUT) /* I2C_PROG_SCL */
-GPIO(I2C_F_SDA, PIN(A, 5), GPIO_INPUT) /* I2C_PROG_SDA */
-
-/* SPI pins - Alternate function below configures SPI module on these pins */
-
-/* Keyboard pins */
-
-/* Subboards HDMI/TYPEC */
-GPIO(EC_X_GPIO1, PIN(H, 4), GPIO_OUT_LOW)
-GPIO(EC_X_GPIO3, PIN(J, 1), GPIO_INPUT)
-GPIO(HDMI_PRSNT_ODL, PIN(J, 3), GPIO_INPUT) /* low -> hdmi, other -> usb */
-
-/* Alternate functions GPIO definitions */
-ALTERNATE(PIN_MASK(B, 0x18), 1, MODULE_I2C, 0) /* I2C A */
-ALTERNATE(PIN_MASK(C, 0x06), 1, MODULE_I2C, GPIO_SEL_1P8V) /* I2C B */
-ALTERNATE(PIN_MASK(F, 0xCC), 1, MODULE_I2C, 0) /* I2C C, D */
-ALTERNATE(PIN_MASK(E, 0x81), 1, MODULE_I2C, 0) /* I2C E */
-
-/* UART */
-ALTERNATE(PIN_MASK(B, 0x03), 1, MODULE_UART, 0) /* EC to Servo */
-
-/* PWM */
-ALTERNATE(PIN_MASK(A, 0x07), 1, MODULE_PWM, 0) /* PWM 0~2 */
-
-/* ADC */
-ALTERNATE(PIN_MASK(I, 0b10010111), 0, MODULE_ADC, 0) /* ADC 0,1,2,4,7 */
-
-/* SPI */
-ALTERNATE(PIN_MASK(M, 0x33), 0, MODULE_SPI, GPIO_SEL_1P8V) /* SPI */
-
-/* Unimplemented Pins */
-GPIO(PACKET_MODE_EN, PIN(D, 4), GPIO_OUT_LOW)
-GPIO(PG_PP5000_Z2_OD, PIN(D, 2), GPIO_INPUT)
-GPIO(PG_MT6315_PROC_B_ODL, PIN(E, 1), GPIO_INPUT)
-GPIO(EC_PEN_CHG_DIS_ODL, PIN(H, 3), GPIO_ODR_HIGH) /* 5V output */
-/* reserved for future use */
-GPIO(CCD_MODE_ODL, PIN(C, 4), GPIO_INPUT)
-
-/* NC pins, enable internal pull-up/down to avoid floating state. */
-GPIO(NC_GPA3, PIN(A, 3), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPA6, PIN(A, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPA7, PIN(A, 7), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPC3, PIN(C, 3), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPD7, PIN(D, 7), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPF1, PIN(F, 1), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(SPI_CLK_GPG6, PIN(G, 6), GPIO_INPUT | GPIO_PULL_UP)
-GPIO(NC_GPH0, PIN(H, 0), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPH6, PIN(H, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPI7, PIN(I, 7), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(NC_GPM6, PIN(M, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-/*
- * These pins don't have internal pull-down capability,
- * so we set them as output low.
- */
-GPIO(SPI_MOSI_GPG4, PIN(G, 4), GPIO_OUT_LOW)
-GPIO(SPI_MISO_GPG5, PIN(G, 5), GPIO_OUT_LOW)
-GPIO(SPI_CS_GPG7, PIN(G, 7), GPIO_OUT_LOW)
-
-/* pins used in power/mt8192, will be removed after mt8186 code ready */
-UNIMPLEMENTED(AP_EC_WATCHDOG_L)
-UNIMPLEMENTED(EC_PMIC_WATCHDOG_L)
-UNIMPLEMENTED(PMIC_EC_PWRGD)
diff --git a/board/krabby/led.c b/board/krabby/led.c
deleted file mode 100644
index 1d3108c47b..0000000000
--- a/board/krabby/led.c
+++ /dev/null
@@ -1,120 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "ec_commands.h"
-#include "gpio.h"
-#include "led_common.h"
-#include "led_onoff_states.h"
-#include "chipset.h"
-#include "driver/bc12/mt6360.h"
-
-__override const int led_charge_lvl_1 = 5;
-__override const int led_charge_lvl_2 = 95;
-
-__override struct led_descriptor
- led_bat_state_table[LED_NUM_STATES][LED_NUM_PHASES] = {
- [STATE_CHARGING_LVL_1] = {{EC_LED_COLOR_AMBER, LED_INDEFINITE} },
- [STATE_CHARGING_LVL_2] = {{EC_LED_COLOR_AMBER, LED_INDEFINITE} },
- [STATE_CHARGING_FULL_CHARGE] = {{EC_LED_COLOR_WHITE, LED_INDEFINITE} },
- [STATE_DISCHARGE_S0] = {{LED_OFF, LED_INDEFINITE} },
- [STATE_DISCHARGE_S0_BAT_LOW] = {{EC_LED_COLOR_AMBER, 1 * LED_ONE_SEC},
- {LED_OFF, 3 * LED_ONE_SEC} },
- [STATE_DISCHARGE_S3] = {{LED_OFF, LED_INDEFINITE} },
- [STATE_DISCHARGE_S5] = {{LED_OFF, LED_INDEFINITE} },
- [STATE_BATTERY_ERROR] = {{EC_LED_COLOR_AMBER, 1 * LED_ONE_SEC},
- {LED_OFF, 1 * LED_ONE_SEC} },
- [STATE_FACTORY_TEST] = {{EC_LED_COLOR_WHITE, 2 * LED_ONE_SEC},
- {EC_LED_COLOR_AMBER, 2 * LED_ONE_SEC} },
-};
-
-__override const struct led_descriptor
- led_pwr_state_table[PWR_LED_NUM_STATES][LED_NUM_PHASES] = {
- [PWR_LED_STATE_ON] = {{EC_LED_COLOR_WHITE, LED_INDEFINITE} },
- [PWR_LED_STATE_SUSPEND_AC] = {{EC_LED_COLOR_WHITE, 1 * LED_ONE_SEC},
- {LED_OFF, 3 * LED_ONE_SEC} },
- [PWR_LED_STATE_SUSPEND_NO_AC] = {{EC_LED_COLOR_WHITE, 1 * LED_ONE_SEC},
- {LED_OFF, 3 * LED_ONE_SEC} },
- [PWR_LED_STATE_OFF] = {{LED_OFF, LED_INDEFINITE} },
-};
-
-
-const enum ec_led_id supported_led_ids[] = {
- EC_LED_ID_BATTERY_LED,
- EC_LED_ID_POWER_LED,
-};
-
-const int supported_led_ids_count = ARRAY_SIZE(supported_led_ids);
-
-__override void led_set_color_battery(enum ec_led_colors color)
-{
- mt6360_led_set_brightness(MT6360_LED_RGB2, 50);
- mt6360_led_set_brightness(MT6360_LED_RGB3, 50);
-
- switch (color) {
- case EC_LED_COLOR_AMBER:
- mt6360_led_enable(MT6360_LED_RGB2, 0);
- mt6360_led_enable(MT6360_LED_RGB3, 1);
- break;
- case EC_LED_COLOR_WHITE:
- mt6360_led_enable(MT6360_LED_RGB2, 1);
- mt6360_led_enable(MT6360_LED_RGB3, 0);
- break;
- default: /* LED_OFF and other unsupported colors */
- mt6360_led_enable(MT6360_LED_RGB2, 0);
- mt6360_led_enable(MT6360_LED_RGB3, 0);
- break;
- }
-}
-
-__override void led_set_color_power(enum ec_led_colors color)
-{
- mt6360_led_set_brightness(MT6360_LED_RGB1, 1);
- mt6360_led_enable(MT6360_LED_RGB1, color == EC_LED_COLOR_WHITE);
-}
-
-void led_get_brightness_range(enum ec_led_id led_id, uint8_t *brightness_range)
-{
- if (led_id == EC_LED_ID_BATTERY_LED) {
- brightness_range[EC_LED_COLOR_AMBER] =
- MT6360_LED_BRIGHTNESS_MAX;
- brightness_range[EC_LED_COLOR_WHITE] =
- MT6360_LED_BRIGHTNESS_MAX;
- } else if (led_id == EC_LED_ID_POWER_LED) {
- brightness_range[EC_LED_COLOR_WHITE] =
- MT6360_LED_BRIGHTNESS_MAX;
- }
-}
-
-int led_set_brightness(enum ec_led_id led_id, const uint8_t *brightness)
-{
- if (led_id == EC_LED_ID_BATTERY_LED) {
- if (brightness[EC_LED_COLOR_AMBER] != 0)
- led_set_color_battery(EC_LED_COLOR_AMBER);
- else if (brightness[EC_LED_COLOR_WHITE] != 0)
- led_set_color_battery(EC_LED_COLOR_WHITE);
- else
- led_set_color_battery(LED_OFF);
- } else if (led_id == EC_LED_ID_POWER_LED) {
- if (brightness[EC_LED_COLOR_WHITE] != 0)
- led_set_color_power(EC_LED_COLOR_WHITE);
- else
- led_set_color_power(LED_OFF);
- }
-
- return EC_SUCCESS;
-}
-
-__override enum led_states board_led_get_state(enum led_states desired_state)
-{
- if (desired_state == STATE_BATTERY_ERROR) {
- if (chipset_in_state(CHIPSET_STATE_ON))
- return desired_state;
- else if (chipset_in_state(CHIPSET_STATE_ANY_SUSPEND))
- return STATE_DISCHARGE_S3;
- else
- return STATE_DISCHARGE_S5;
- }
- return desired_state;
-}
diff --git a/board/krabby/vif_override.xml b/board/krabby/vif_override.xml
deleted file mode 100644
index 32736caf64..0000000000
--- a/board/krabby/vif_override.xml
+++ /dev/null
@@ -1,3 +0,0 @@
-<!-- Add VIF field overrides here. See genvif.c and the Vendor Info File
- Definition from the USB-IF.
--->
diff --git a/zephyr/projects/corsola/CMakeLists.txt b/zephyr/projects/corsola/CMakeLists.txt
index c237bae135..41454213fa 100644
--- a/zephyr/projects/corsola/CMakeLists.txt
+++ b/zephyr/projects/corsola/CMakeLists.txt
@@ -3,31 +3,25 @@
# found in the LICENSE file.
cmake_minimum_required(VERSION 3.13.1)
-add_compile_definitions(BOARD_KRABBY)
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
-project(krabby)
zephyr_library_include_directories(include)
-set(PLATFORM_EC_BASEBOARD "${PLATFORM_EC}/baseboard/corsola" CACHE PATH
- "Path to the platform/ec baseboard directory")
-set(PLATFORM_EC_BOARD "${PLATFORM_EC}/board/krabby" CACHE PATH
- "Path to the platform/ec board directory")
-
# Include selected EC source from the baseboard
zephyr_library_sources(
- "${PLATFORM_EC_BASEBOARD}/board_chipset.c"
- "${PLATFORM_EC_BASEBOARD}/board_id.c"
- "${PLATFORM_EC_BASEBOARD}/hibernate.c"
- "${PLATFORM_EC_BASEBOARD}/regulator.c"
- "${PLATFORM_EC_BASEBOARD}/usbc_config.c"
- "${PLATFORM_EC_BASEBOARD}/usb_pd_policy.c")
-
-# Include selected EC source from the board
-zephyr_library_sources(
- "${PLATFORM_EC_BOARD}/hooks.c"
- "${PLATFORM_EC_BOARD}/led.c")
+ "src/board_chipset.c"
+ "src/board_id.c"
+ "src/hibernate.c"
+ "src/usbc_config.c"
+ "src/regulator.c"
+ "src/usb_pd_policy.c"
+)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_I2C
- "src/krabby/i2c.c")
+if(DEFINED CONFIG_BOARD_KRABBY)
+ project(krabby)
+ zephyr_library_sources("src/krabby/hooks.c")
+ zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_I2C "src/krabby/i2c.c")
+ zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_LED_COMMON
+ "src/krabby/led.c")
+endif()
diff --git a/zephyr/projects/corsola/Kconfig b/zephyr/projects/corsola/Kconfig
new file mode 100644
index 0000000000..5848c137fa
--- /dev/null
+++ b/zephyr/projects/corsola/Kconfig
@@ -0,0 +1,11 @@
+# Copyright 2021 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.
+
+config BOARD_KRABBY
+ bool "Google Krabby Board"
+ help
+ Build Google Krabby reference board. Krabby has MediaTek MT8186 SoC
+ with ITE it81202-bx EC.
+
+source "Kconfig.zephyr"
diff --git a/zephyr/projects/corsola/prj_krabby.conf b/zephyr/projects/corsola/prj_krabby.conf
index ad86923679..b6c6960209 100644
--- a/zephyr/projects/corsola/prj_krabby.conf
+++ b/zephyr/projects/corsola/prj_krabby.conf
@@ -6,6 +6,8 @@ CONFIG_CROS_EC=y
CONFIG_PLATFORM_EC=y
CONFIG_SHIMMED_TASKS=y
+CONFIG_BOARD_KRABBY=y
+
# Bring up options
CONFIG_KERNEL_SHELL=y
CONFIG_PLATFORM_EC_SYSTEM_UNLOCKED=y
diff --git a/baseboard/corsola/baseboard_common.h b/zephyr/projects/corsola/src/baseboard_common.h
index c0328ba4e1..c0328ba4e1 100644
--- a/baseboard/corsola/baseboard_common.h
+++ b/zephyr/projects/corsola/src/baseboard_common.h
diff --git a/baseboard/corsola/board_chipset.c b/zephyr/projects/corsola/src/board_chipset.c
index 7e06a49792..7e06a49792 100644
--- a/baseboard/corsola/board_chipset.c
+++ b/zephyr/projects/corsola/src/board_chipset.c
diff --git a/baseboard/corsola/board_id.c b/zephyr/projects/corsola/src/board_id.c
index c39cf050a8..c39cf050a8 100644
--- a/baseboard/corsola/board_id.c
+++ b/zephyr/projects/corsola/src/board_id.c
diff --git a/baseboard/corsola/hibernate.c b/zephyr/projects/corsola/src/hibernate.c
index c3752358bf..c3752358bf 100644
--- a/baseboard/corsola/hibernate.c
+++ b/zephyr/projects/corsola/src/hibernate.c
diff --git a/board/kingler/battery.c b/zephyr/projects/corsola/src/krabby/battery.c
index f07c38e1b8..f07c38e1b8 100644
--- a/board/kingler/battery.c
+++ b/zephyr/projects/corsola/src/krabby/battery.c
diff --git a/board/krabby/board.c b/zephyr/projects/corsola/src/krabby/board.c
index 1e81aed838..1e81aed838 100644
--- a/board/krabby/board.c
+++ b/zephyr/projects/corsola/src/krabby/board.c
diff --git a/board/krabby/hooks.c b/zephyr/projects/corsola/src/krabby/hooks.c
index cea6667650..cea6667650 100644
--- a/board/krabby/hooks.c
+++ b/zephyr/projects/corsola/src/krabby/hooks.c
diff --git a/board/kingler/led.c b/zephyr/projects/corsola/src/krabby/led.c
index 1d3108c47b..1d3108c47b 100644
--- a/board/kingler/led.c
+++ b/zephyr/projects/corsola/src/krabby/led.c
diff --git a/board/krabby/usbc_config.c b/zephyr/projects/corsola/src/krabby/usbc_config.c
index ee5d9483eb..ee5d9483eb 100644
--- a/board/krabby/usbc_config.c
+++ b/zephyr/projects/corsola/src/krabby/usbc_config.c
diff --git a/baseboard/corsola/regulator.c b/zephyr/projects/corsola/src/regulator.c
index 35670bda82..35670bda82 100644
--- a/baseboard/corsola/regulator.c
+++ b/zephyr/projects/corsola/src/regulator.c
diff --git a/baseboard/corsola/usb_pd_policy.c b/zephyr/projects/corsola/src/usb_pd_policy.c
index d0c576a398..d0c576a398 100644
--- a/baseboard/corsola/usb_pd_policy.c
+++ b/zephyr/projects/corsola/src/usb_pd_policy.c
diff --git a/baseboard/corsola/usbc_config.c b/zephyr/projects/corsola/src/usbc_config.c
index 30859fdc0d..30859fdc0d 100644
--- a/baseboard/corsola/usbc_config.c
+++ b/zephyr/projects/corsola/src/usbc_config.c