summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--baseboard/octopus/baseboard.h2
-rw-r--r--board/bip/battery.c93
-rw-r--r--board/bip/board.c132
-rw-r--r--board/bip/board.h79
-rw-r--r--board/bip/build.mk15
-rw-r--r--board/bip/ec.tasklist36
-rw-r--r--board/bip/gpio.inc144
-rw-r--r--board/bip/led.c75
-rw-r--r--util/iteflash.c6
9 files changed, 4 insertions, 578 deletions
diff --git a/baseboard/octopus/baseboard.h b/baseboard/octopus/baseboard.h
index fc34912096..cb923fb385 100644
--- a/baseboard/octopus/baseboard.h
+++ b/baseboard/octopus/baseboard.h
@@ -282,7 +282,7 @@
/*
* Sensor stack in EC/Kernel depends on a hardware interrupt pin from EC->AP, so
* do not define CONFIG_MKBP_USE_HOST_EVENT since all octopus boards use
- * hardware pin to send interrupt from EC -> AP (except bip and casta).
+ * hardware pin to send interrupt from EC -> AP (except casta).
*/
#define CONFIG_MKBP_EVENT
#define CONFIG_MKBP_USE_GPIO
diff --git a/board/bip/battery.c b/board/bip/battery.c
deleted file mode 100644
index e37ffbc3b7..0000000000
--- a/board/bip/battery.c
+++ /dev/null
@@ -1,93 +0,0 @@
-/* Copyright 2018 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.
- *
- * Battery pack vendor provided charging profile
- */
-
-#include "battery_fuel_gauge.h"
-#include "common.h"
-#include "util.h"
-
-/*
- * Battery info for all bip battery types. Note that the fields
- * start_charging_min/max and charging_min/max are not used for the charger.
- * The effective temperature limits are given by discharging_min/max_c.
- *
- * Fuel Gauge (FG) parameters which are used for determining if the battery
- * is connected, the appropriate ship mode (battery cutoff) command, and the
- * charge/discharge FETs status.
- *
- * Ship mode (battery cutoff) requires 2 writes to the appropriate smart battery
- * register. For some batteries, the charge/discharge FET bits are set when
- * charging/discharging is active, in other types, these bits set mean that
- * charging/discharging is disabled. Therefore, in addition to the mask for
- * these bits, a disconnect value must be specified. Note that for TI fuel
- * gauge, the charge/discharge FET status is found in Operation Status (0x54),
- * but a read of Manufacturer Access (0x00) will return the lower 16 bits of
- * Operation status which contains the FET status bits.
- *
- * The assumption for battery types supported is that the charge/discharge FET
- * status can be read with a sb_read() command and therefore, only the register
- * address, mask, and disconnect value need to be provided.
- */
-const struct board_batt_params board_battery_info[] = {
- /* Panasonic AP1505L Battery Information */
- [BATTERY_PANASONIC] = {
- .fuel_gauge = {
- .manuf_name = "PANASONIC",
- .ship_mode = {
- .reg_addr = 0x3A,
- .reg_data = { 0xC574, 0xC574 },
- },
- .fet = {
- .reg_addr = 0x0,
- .reg_mask = 0x4000,
- .disconnect_val = 0x0,
- }
- },
- .batt_info = {
- .voltage_max = 13200,
- .voltage_normal = 11550, /* mV */
- .voltage_min = 9000, /* mV */
- .precharge_current = 256, /* mA */
- .start_charging_min_c = 0,
- .start_charging_max_c = 50,
- .charging_min_c = 0,
- .charging_max_c = 60,
- .discharging_min_c = 0,
- .discharging_max_c = 60,
- },
- },
-
- /* SANYO AC15A3J Battery Information */
- [BATTERY_SANYO] = {
- .fuel_gauge = {
- .manuf_name = "SANYO",
- .ship_mode = {
- .reg_addr = 0x3A,
- .reg_data = { 0xC574, 0xC574 },
- },
- .fet = {
- .reg_addr = 0x0,
- .reg_mask = 0x4000,
- .disconnect_val = 0x0,
- }
- },
- .batt_info = {
- .voltage_max = TARGET_WITH_MARGIN(13200, 5),
- .voltage_normal = 11550, /* mV */
- .voltage_min = 9000, /* mV */
- .precharge_current = 256, /* mA */
- .start_charging_min_c = 0,
- .start_charging_max_c = 50,
- .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_PANASONIC;
diff --git a/board/bip/board.c b/board/bip/board.c
deleted file mode 100644
index fb4ff5e39a..0000000000
--- a/board/bip/board.c
+++ /dev/null
@@ -1,132 +0,0 @@
-/* Copyright 2018 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.
- */
-
-/* Bip board-specific configuration */
-
-#include "adc.h"
-#include "adc_chip.h"
-#include "charge_state.h"
-#include "common.h"
-#include "driver/ppc/sn5s330.h"
-#include "driver/tcpm/it83xx_pd.h"
-#include "driver/tcpm/ps8xxx.h"
-#include "driver/usb_mux_it5205.h"
-#include "extpower.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "intc.h"
-#include "keyboard_scan.h"
-#include "lid_switch.h"
-#include "power.h"
-#include "power_button.h"
-#include "spi.h"
-#include "switch.h"
-#include "system.h"
-#include "tcpci.h"
-#include "tablet_mode.h"
-#include "temp_sensor.h"
-#include "thermistor.h"
-#include "uart.h"
-#include "usb_mux.h"
-#include "usbc_ppc.h"
-#include "util.h"
-
-static void ppc_interrupt(enum gpio_signal signal)
-{
- if (signal == GPIO_USB_C0_PD_INT_ODL)
- sn5s330_interrupt(0);
- else if (signal == GPIO_USB_C1_PD_INT_ODL)
- sn5s330_interrupt(1);
-}
-
-int ppc_get_alert_status(int port)
-{
- if (port == 0)
- return gpio_get_level(GPIO_USB_C0_PD_INT_ODL) == 0;
- else
- return gpio_get_level(GPIO_USB_C1_PD_INT_ODL) == 0;
-}
-
-#include "gpio_list.h" /* Must come after other header files. */
-
-/******************************************************************************/
-/* ADC channels */
-const struct adc_t adc_channels[] = {
- /* Vbus C0 sensing (10x voltage divider). PPVAR_USB_C0_VBUS */
- [ADC_VBUS_C0] = {.name = "VBUS_C0",
- .factor_mul = 10 * ADC_MAX_MVOLT,
- .factor_div = ADC_READ_MAX + 1,
- .shift = 0,
- .channel = CHIP_ADC_CH13},
- /* Vbus C1 sensing (10x voltage divider). PPVAR_USB_C1_VBUS */
- [ADC_VBUS_C1] = {.name = "VBUS_C1",
- .factor_mul = 10 * ADC_MAX_MVOLT,
- .factor_div = ADC_READ_MAX + 1,
- .shift = 0,
- .channel = CHIP_ADC_CH14},
- /* Convert to raw mV for thermistor table lookup */
- [ADC_TEMP_SENSOR_AMB] = {.name = "TEMP_AMB",
- .factor_mul = ADC_MAX_MVOLT,
- .factor_div = ADC_READ_MAX + 1,
- .shift = 0,
- .channel = CHIP_ADC_CH3},
- /* Convert to raw mV for thermistor table lookup */
- [ADC_TEMP_SENSOR_CHARGER] = {.name = "TEMP_CHARGER",
- .factor_mul = ADC_MAX_MVOLT,
- .factor_div = ADC_READ_MAX + 1,
- .shift = 0,
- .channel = CHIP_ADC_CH5},
-};
-BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
-
-static int read_charger_temp(int idx, int *temp_ptr) {
- if (!gpio_get_level(GPIO_AC_PRESENT))
- return EC_ERROR_NOT_POWERED;
- return get_temp_6v0_51k1_47k_4050b(idx, temp_ptr);
-}
-
-const struct temp_sensor_t temp_sensors[] = {
- [TEMP_SENSOR_BATTERY] = {.name = "Battery",
- .type = TEMP_SENSOR_TYPE_BATTERY,
- .read = charge_get_battery_temp,
- .action_delay_sec = 1},
- [TEMP_SENSOR_AMBIENT] = {.name = "Ambient",
- .type = TEMP_SENSOR_TYPE_BOARD,
- .read = get_temp_3v3_51k1_47k_4050b,
- .idx = ADC_TEMP_SENSOR_AMB,
- .action_delay_sec = 5},
- [TEMP_SENSOR_CHARGER] = {.name = "Charger",
- .type = TEMP_SENSOR_TYPE_BOARD,
- .read = read_charger_temp,
- .idx = ADC_TEMP_SENSOR_CHARGER,
- .action_delay_sec = 1},
-};
-BUILD_ASSERT(ARRAY_SIZE(temp_sensors) == TEMP_SENSOR_COUNT);
-
-void board_hibernate_late(void)
-{
- /*
- * Set KSO/KSI pins to GPIO input function to disable keyboard scan
- * while hibernating. This also prevent leakage current caused
- * by internal pullup of keyboard scan module.
- */
- gpio_set_flags_by_mask(GPIO_KSO_H, 0xff, GPIO_INPUT);
- gpio_set_flags_by_mask(GPIO_KSO_L, 0xff, GPIO_INPUT);
- gpio_set_flags_by_mask(GPIO_KSI, 0xff, GPIO_INPUT);
-}
-
-/******************************************************************************/
-/* SPI devices */
-/* TODO(b/75972988): Fill out correctly (SPI FLASH) */
-const struct spi_device_t spi_devices[] = {
-};
-const unsigned int spi_devices_used = ARRAY_SIZE(spi_devices);
-
-void board_overcurrent_event(int port, int is_overcurrented)
-{
- /* TODO(b/78344554): pass this signal upstream once hardware reworked */
- cprints(CC_USBPD, "p%d: overcurrent!", port);
-}
diff --git a/board/bip/board.h b/board/bip/board.h
deleted file mode 100644
index 7a0604660e..0000000000
--- a/board/bip/board.h
+++ /dev/null
@@ -1,79 +0,0 @@
-/* Copyright 2018 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.
- */
-
-/* Bip board configuration */
-
-#ifndef __CROS_EC_BOARD_H
-#define __CROS_EC_BOARD_H
-
-/* Select Baseboard features */
-#define VARIANT_OCTOPUS_EC_ITE8320
-#define VARIANT_OCTOPUS_CHARGER_BQ25703
-#include "baseboard.h"
-
-/* Optional features */
-#define CONFIG_SYSTEM_UNLOCKED /* Allow dangerous commands while in dev. */
-
-#define CONFIG_LED_COMMON
-
-/* Sensors */
-#define CONFIG_TEMP_SENSOR
-#define CONFIG_THERMISTOR
-#define CONFIG_STEINHART_HART_3V3_51K1_47K_4050B
-#define CONFIG_STEINHART_HART_6V0_51K1_47K_4050B
-
-/* Hardware for proto bip does not support ec keyboard backlight control. */
-#undef CONFIG_PWM
-#undef CONFIG_PWM_KBLIGHT
-
-/* Old hardware does not support dedicated EC->AP interrupt for MKBP */
-#undef CONFIG_MKBP_USE_GPIO
-#define CONFIG_MKBP_USE_HOST_EVENT
-
-#undef CONFIG_UART_TX_BUF_SIZE
-#define CONFIG_UART_TX_BUF_SIZE 4096
-
-/* Remove commands to give more flash space */
-#undef CONFIG_CMD_ADC
-#undef CONFIG_CMD_ACCELSPOOF
-#undef CONFIG_CMD_BATTFAKE
-#undef CONFIG_CMD_FLASH
-#undef CONFIG_CMD_KEYBOARD
-#undef CONFIG_CMD_HASH
-#undef CONFIG_CMD_HCDEBUG
-#undef CONFIG_CMD_MD
-#undef CONFIG_CMD_POWERINDEBUG
-#undef CONFIG_CMD_TIMERINFO
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-#include "registers.h"
-
-enum adc_channel {
- ADC_VBUS_C0,
- ADC_VBUS_C1,
- ADC_TEMP_SENSOR_AMB,
- ADC_TEMP_SENSOR_CHARGER,
- ADC_CH_COUNT
-};
-
-enum temp_sensor_id {
- TEMP_SENSOR_BATTERY,
- TEMP_SENSOR_AMBIENT,
- TEMP_SENSOR_CHARGER,
- TEMP_SENSOR_COUNT
-};
-
-/* List of possible batteries */
-enum battery_type {
- BATTERY_PANASONIC,
- BATTERY_SANYO,
- BATTERY_TYPE_COUNT,
-};
-
-#endif /* !__ASSEMBLER__ */
-
-#endif /* __CROS_EC_BOARD_H */
diff --git a/board/bip/build.mk b/board/bip/build.mk
deleted file mode 100644
index 19af8444e5..0000000000
--- a/board/bip/build.mk
+++ /dev/null
@@ -1,15 +0,0 @@
-# -*- makefile -*-
-# Copyright 2018 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
-#
-
-CHIP:=it83xx
-CHIP_FAMILY:=it8320
-CHIP_VARIANT:=it8320bx
-BASEBOARD:=octopus
-
-board-y=board.o led.o
-board-$(CONFIG_BATTERY_SMART)+=battery.o \ No newline at end of file
diff --git a/board/bip/ec.tasklist b/board/bip/ec.tasklist
deleted file mode 100644
index 75447efa1f..0000000000
--- a/board/bip/ec.tasklist
+++ /dev/null
@@ -1,36 +0,0 @@
-/* Copyright 2018 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.
- */
-
-/*
- * List of enabled tasks in the priority order
- *
- * The first one has the lowest priority.
- *
- * For each task, use the macro TASK_ALWAYS(n, r, d, s) for base tasks and
- * TASK_NOTEST(n, r, d, s) for tasks that can be excluded in test binaries,
- * where :
- * 'n' in the name of the task
- * 'r' in the main routine of the task
- * 'd' in an opaque parameter passed to the routine at startup
- * 's' is the stack size in bytes; must be a multiple of 8
- *
- * For USB PD tasks, IDs must be in consecutive order and correspond to
- * the port which they are for. See TASK_ID_TO_PD_PORT() macro.
- */
-
-#define CONFIG_TASK_LIST \
- TASK_ALWAYS(HOOKS, hook_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P0, usb_charger_task, 0, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(USB_CHG_P1, usb_charger_task, 1, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(CHARGER, charger_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_NOTEST(CHIPSET, chipset_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_NOTEST(KEYPROTO, keyboard_protocol_task, NULL, TASK_STACK_SIZE) \
- TASK_NOTEST(PDCMD, pd_command_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(HOSTCMD, host_command_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(CONSOLE, console_task, NULL, VENTI_TASK_STACK_SIZE) \
- TASK_ALWAYS(POWERBTN, power_button_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_NOTEST(KEYSCAN, keyboard_scan_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(PD_C0, pd_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(PD_C1, pd_task, NULL, LARGER_TASK_STACK_SIZE)
diff --git a/board/bip/gpio.inc b/board/bip/gpio.inc
deleted file mode 100644
index 1e90024762..0000000000
--- a/board/bip/gpio.inc
+++ /dev/null
@@ -1,144 +0,0 @@
-/* -*- mode:c -*-
- *
- * Copyright 2018 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(LID_OPEN, PIN(E, 2), GPIO_INT_BOTH, lid_interrupt)
-GPIO_INT(WP_L, PIN(I, 4), GPIO_INT_BOTH, switch_interrupt) /* EC_WP_ODL */
-GPIO_INT(POWER_BUTTON_L, PIN(E, 4), GPIO_INT_BOTH, power_button_interrupt) /* MECH_PWR_BTN_ODL */
-#ifdef CONFIG_LOW_POWER_IDLE
-/* Used to wake up the EC from Deep Doze mode when writing to console */
-GPIO_INT(UART1_RX, PIN(B, 0), GPIO_INT_BOTH, uart_deepsleep_interrupt) /* UART_SERVO_TX_EC_RX */
-#endif
-
-/* USB-C interrupts */
-GPIO_INT(USB_C0_PD_INT_ODL, PIN(H, 6), GPIO_INT_FALLING, ppc_interrupt)
-GPIO_INT(USB_C1_PD_INT_ODL, PIN(H, 5), GPIO_INT_FALLING, ppc_interrupt)
-
-/* Power State interrupts */
-#ifdef CONFIG_POWER_S0IX
-GPIO_INT(PCH_SLP_S0_L, PIN(G, 6), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S0_L */
-#endif
-GPIO_INT(PCH_SLP_S4_L, PIN(F, 3), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S4_L */
-GPIO_INT(PCH_SLP_S3_L, PIN(F, 2), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S3_L */
-GPIO_INT(SUSPWRDNACK, PIN(E, 1), GPIO_INT_BOTH, power_signal_interrupt) /* SUSPWRDNACK */
-GPIO_INT(RSMRST_L_PGOOD, PIN(F, 1), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_RSMRST_ODL */
-GPIO_INT(ALL_SYS_PGOOD, PIN(F, 0), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_PWROK_OD */
-GPIO_INT(AC_PRESENT, PIN(A, 7), GPIO_INT_BOTH, extpower_interrupt) /* ACOK_OD */
-
-#ifdef CONFIG_HOSTCMD_ESPI
-/* enable 1.8v input of EC's espi_reset pin, and then this pin takes effect. */
-GPIO_INT(ESPI_RESET_L, PIN(D, 2), GPIO_INT_FALLING | GPIO_SEL_1P8V, espi_reset_pin_asserted_interrupt) /* eSPI_reset# */
-#endif
-
-/* Other interrupts */
-GPIO_INT(TABLET_MODE_L, PIN(H, 4), GPIO_INT_BOTH, hall_sensor_isr)
-
-GPIO(PCH_PLTRST_L, PIN(E, 3), GPIO_INPUT) /* PLT_RST_L: Platform Reset from SoC */
-GPIO(SYS_RESET_L, PIN(B, 6), GPIO_ODR_HIGH) /* SYS_RST_ODL */
-GPIO(PCH_RTCRST, PIN(K, 7), GPIO_OUT_LOW) /* EC_PCH_RTCRST */
-
-/*
- * TODO(b/76023457): Move below 2 signals to virtual wires over eSPI
- */
-GPIO(PCH_SMI_L, PIN(D, 4), GPIO_OUT_LOW) /* EC_SMI_R_ODL */
-GPIO(PCH_SCI_L, PIN(D, 3), GPIO_OUT_LOW) /* EC_SCI_R_ODL */
-
-GPIO(ENTERING_RW, PIN(C, 5), GPIO_OUT_LOW) /* EC_ENTERING_RW */
-GPIO(PCH_WAKE_L, PIN(D, 1), GPIO_ODR_HIGH) /* EC_PCH_WAKE_ODL */
-GPIO(PCH_PWRBTN_L, PIN(D, 0), GPIO_ODR_HIGH) /* EC_PCH_PWR_BTN_ODL */
-
-GPIO(EN_PP5000, PIN(K, 2), GPIO_OUT_LOW) /* EN_PP5000_A */
-GPIO(PP5000_PG, PIN(K, 3), GPIO_INPUT) /* PP5000_PG_OD */
-GPIO(EN_PP3300, PIN(K, 5), GPIO_OUT_LOW) /* EN_PP3300_A */
-GPIO(PP3300_PG, PIN(K, 1), GPIO_INPUT) /* PP3300_PG_OD */
-GPIO(PMIC_EN, PIN(D, 7), GPIO_OUT_LOW) /* Enable A Rails via PMIC */
-GPIO(PCH_RSMRST_L, PIN(C, 6), GPIO_OUT_LOW) /* RSMRST# to SOC. All _A rails now up. */
-GPIO(PCH_SYS_PWROK, PIN(K, 4), GPIO_OUT_LOW) /* EC_PCH_PWROK. All S0 rails now up. */
-
-/* Peripheral rails */
-GPIO(ENABLE_BACKLIGHT, PIN(B, 5), GPIO_ODR_HIGH |
- GPIO_SEL_1P8V) /* EC_BL_EN_OD */
-GPIO(EN_P3300_TRACKPAD_ODL, PIN(A, 2), GPIO_ODR_HIGH)
-
-GPIO(EC_BATT_PRES_L, PIN(C, 0), GPIO_INPUT)
-
-/*
- * PCH_PROCHOT_ODL is primarily for monitoring the PROCHOT# signal which is
- * normally driven by the PMIC. The EC can also drive this signal in the event
- * that the ambient or charger temperature sensors exceeds their thresholds.
- */
-GPIO(CPU_PROCHOT, PIN(C, 7), GPIO_INPUT | GPIO_SEL_1P8V) /* PCH_PROCHOT_ODL */
-
-/* I2C pins - Alternate function below configures I2C module on these pins */
-GPIO(I2C0_SCL, PIN(B, 3), GPIO_INPUT) /* EC_I2C_POWER_3V3_SCL */
-GPIO(I2C0_SDA, PIN(B, 4), GPIO_INPUT) /* EC_I2C_POWER_3V3_SDA */
-GPIO(I2C1_SCL, PIN(C, 1), GPIO_INPUT |
- GPIO_SEL_1P8V) /* EC_I2C_SENSOR_U_SCL */
-GPIO(I2C1_SDA, PIN(C, 2), GPIO_INPUT |
- GPIO_SEL_1P8V) /* EC_I2C_SENSOR_U_SDA */
-GPIO(I2C2_SCL, PIN(F, 6), GPIO_INPUT) /* EC_I2C_USB_C0_MUX_SCL */
-GPIO(I2C2_SDA, PIN(F, 7), GPIO_INPUT) /* EC_I2C_USB_C0_MUX_SDA */
-GPIO(I2C4_SCL, PIN(E, 0), GPIO_INPUT) /* EC_I2C_USB_C1_MUX_SCL */
-GPIO(I2C4_SDA, PIN(E, 7), GPIO_INPUT) /* EC_I2C_USB_C1_MUX_SDA */
-GPIO(I2C5_SCL, PIN(A, 4), GPIO_INPUT) /* EC_I2C_PROG_SCL */
-GPIO(I2C5_SDA, PIN(A, 5), GPIO_INPUT) /* EC_I2C_PROG_SDA */
-
-/* USB pins */
-GPIO(EN_USB_A0_5V, PIN(B, 7), GPIO_OUT_LOW) /* Enable A0 5V Charging */
-GPIO(EN_USB_A1_5V, PIN(H, 3), GPIO_OUT_LOW) /* Enable A1 5V Charging */
-GPIO(USB_A0_CHARGE_EN_L, PIN(K, 0), GPIO_OUT_HIGH) /* Enable A0 1.5A Charging */
-GPIO(USB_A1_CHARGE_EN_L, PIN(K, 6), GPIO_OUT_HIGH) /* Enable A1 1.5A Charging */
-GPIO(USB_C0_HPD_1V8_ODL, PIN(J, 0), GPIO_ODR_HIGH |
- GPIO_SEL_1P8V) /* C0 DP Hotplug Detect */
-GPIO(USB_C1_HPD_1V8_ODL, PIN(J, 1), GPIO_ODR_HIGH |
- GPIO_SEL_1P8V) /* C1 DP Hotplug Detect */
-GPIO(USB_C0_BC12_CHG_DET_L, PIN(A, 0), GPIO_INPUT) /* C0 BC1.2 Detect */
-GPIO(USB_C1_BC12_CHG_DET_L, PIN(A, 1), GPIO_INPUT) /* C1 BC1.2 Detect */
-GPIO(USB_C0_BC12_VBUS_ON, PIN(J, 4), GPIO_OUT_LOW) /* C0 BC1.2 Power */
-GPIO(USB_C1_BC12_VBUS_ON, PIN(J, 5), GPIO_OUT_LOW) /* C1 BC1.2 Power */
-GPIO(USB_C0_PD_RST_ODL, PIN(L, 6), GPIO_ODR_HIGH) /* NC, defined for shared reset code with ampton */
-GPIO(USB_C1_PD_RST_ODL, PIN(L, 7), GPIO_ODR_HIGH) /* C1 PD Reset */
-/*
- * Configure USB2_OTG_ID as ODR so that the EC never drives it high thus
- * preventing any leakage when SoC is not up.
- */
-GPIO(USB2_OTG_ID, PIN(I, 2), GPIO_ODR_LOW |
- GPIO_SEL_1P8V) /* OTG ID */
-
-/* LED */
-GPIO(BAT_LED_ORANGE, PIN(A, 6), GPIO_OUT_LOW) /* LED_1_L NOTE: actually active high, but labeled _L in the schematics */
-GPIO(BAT_LED_BLUE, PIN(A, 3), GPIO_OUT_LOW) /* LED_2_L NOTE: actually active high, but labeled _L in the schematics */
-
-/* NC pins, enable internal pull-down to avoid floating state. */
-GPIO(GPIOB2_NC, PIN(B, 2), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOE6_NC, PIN(E, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOG0_NC, PIN(G, 0), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOG1_NC, PIN(G, 1), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOH0_NC, PIN(H, 0), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOL2_NC, PIN(L, 2), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOL3_NC, PIN(L, 3), GPIO_INPUT | GPIO_PULL_DOWN)
-GPIO(GPIOM6_NC, PIN(M, 6), GPIO_INPUT | GPIO_PULL_DOWN)
-
-/* Misc. */
-GPIO(CCD_MODE_ODL, PIN(C, 4), GPIO_INPUT)
-
-/* Not implemented in hardware yet */
-UNIMPLEMENTED(KB_BL_PWR_EN)
-
-/* Alternate functions GPIO definitions */
-/* Cr50 requires no pull-ups on UART pins. */
-ALTERNATE(PIN_MASK(B, 0x03), 0, MODULE_UART, 0) /* UART from EC to Servo */
-ALTERNATE(PIN_MASK(B, 0x18), 0, MODULE_I2C, 0) /* I2C0 */
-ALTERNATE(PIN_MASK(C, 0x06), 0, MODULE_I2C, GPIO_SEL_1P8V) /* I2C1 - 1.8V */
-ALTERNATE(PIN_MASK(F, 0xC0), 0, MODULE_I2C, 0) /* I2C2 */
-ALTERNATE(PIN_MASK(E, 0x81), 0, MODULE_I2C, 0) /* I2C4 */
-ALTERNATE(PIN_MASK(A, 0x30), 0, MODULE_I2C, 0) /* I2C5 */
-ALTERNATE(PIN_MASK(L, 0x03), 0, MODULE_ADC, 0) /* ADC13 & ADC14: ADC_USB_C0_VBUS & ADC_USB_C1_VBUS */
-ALTERNATE(PIN_MASK(I, 0x28), 0, MODULE_ADC, 0) /* ADC3 & ADC5 */
diff --git a/board/bip/led.c b/board/bip/led.c
deleted file mode 100644
index 69a20342be..0000000000
--- a/board/bip/led.c
+++ /dev/null
@@ -1,75 +0,0 @@
-/* Copyright 2018 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.
- *
- * Power and battery LED control for Bip
- */
-
-#include "ec_commands.h"
-#include "gpio.h"
-#include "led_common.h"
-#include "led_states.h"
-
-#define LED_OFF_LVL 0
-#define LED_ON_LVL 1
-
-const int led_charge_lvl_1 = 0;
-
-const int led_charge_lvl_2 = 100;
-
-/* Bip: Note there is only LED for charge / power */
-struct led_descriptor led_bat_state_table[LED_NUM_STATES][LED_NUM_PHASES] = {
- [STATE_CHARGING_LVL_1] = {{EC_LED_COLOR_BLUE, 2 * LED_ONE_SEC},
- {EC_LED_COLOR_AMBER, 2 * LED_ONE_SEC} },
- [STATE_CHARGING_LVL_2] = {{EC_LED_COLOR_AMBER, LED_INDEFINITE} },
- [STATE_CHARGING_FULL_CHARGE] = {{EC_LED_COLOR_BLUE, LED_INDEFINITE} },
- [STATE_DISCHARGE_S0] = {{EC_LED_COLOR_BLUE, LED_INDEFINITE} },
- [STATE_DISCHARGE_S3] = {{EC_LED_COLOR_AMBER, 4 * LED_ONE_SEC},
- {LED_OFF, 1 * LED_ONE_SEC} },
- [STATE_DISCHARGE_S5] = {{LED_OFF, LED_INDEFINITE} },
- [STATE_BATTERY_ERROR] = {{EC_LED_COLOR_BLUE, 2 * LED_ONE_SEC},
- {EC_LED_COLOR_AMBER, 2 * LED_ONE_SEC} },
- [STATE_FACTORY_TEST] = {{EC_LED_COLOR_BLUE, LED_INDEFINITE} },
-};
-BUILD_ASSERT(ARRAY_SIZE(led_bat_state_table) == LED_NUM_STATES);
-
-const enum ec_led_id supported_led_ids[] = { EC_LED_ID_BATTERY_LED };
-
-const int supported_led_ids_count = ARRAY_SIZE(supported_led_ids);
-
-void led_set_color_battery(enum ec_led_colors color)
-{
- switch (color) {
- case EC_LED_COLOR_BLUE:
- gpio_set_level(GPIO_BAT_LED_BLUE, LED_ON_LVL);
- gpio_set_level(GPIO_BAT_LED_ORANGE, LED_OFF_LVL);
- break;
- case EC_LED_COLOR_AMBER:
- gpio_set_level(GPIO_BAT_LED_BLUE, LED_OFF_LVL);
- gpio_set_level(GPIO_BAT_LED_ORANGE, LED_ON_LVL);
- break;
- default: /* LED_OFF and other unsupported colors */
- gpio_set_level(GPIO_BAT_LED_BLUE, LED_OFF_LVL);
- gpio_set_level(GPIO_BAT_LED_ORANGE, LED_OFF_LVL);
- break;
- }
-}
-
-void led_get_brightness_range(enum ec_led_id led_id, uint8_t *brightness_range)
-{
- brightness_range[EC_LED_COLOR_BLUE] = 1;
- brightness_range[EC_LED_COLOR_AMBER] = 1;
-}
-
-int led_set_brightness(enum ec_led_id led_id, const uint8_t *brightness)
-{
- if (brightness[EC_LED_COLOR_BLUE] != 0)
- led_set_color_battery(EC_LED_COLOR_BLUE);
- else if (brightness[EC_LED_COLOR_AMBER] != 0)
- led_set_color_battery(EC_LED_COLOR_AMBER);
- else
- led_set_color_battery(LED_OFF);
-
- return EC_SUCCESS;
-}
-
diff --git a/util/iteflash.c b/util/iteflash.c
index d96464ccda..480756e71e 100644
--- a/util/iteflash.c
+++ b/util/iteflash.c
@@ -1713,9 +1713,9 @@ static const struct i2c_interface linux_i2c_interface = {
* can be increased to match FTDI_BLOCK_WRITE_SIZE would be a useful
* speedup.
*
- * While 254 bytes works with Bip, it causes corruption with Ampton
- * (using any kind of servo). 128 bytes is the largest block_write_size
- * compatible with both Ampton and Servo Micro.
+ * 254 byte block sizes cause corruption with Ampton (using any kind of
+ * servo). 128 bytes is the largest block_write_size compatible with
+ * both Ampton and Servo Micro.
*
* See https://issuetracker.google.com/79684405 for background.
*/