summaryrefslogtreecommitdiff
path: root/baseboard/asurada
diff options
context:
space:
mode:
Diffstat (limited to 'baseboard/asurada')
-rw-r--r--baseboard/asurada/baseboard.c101
-rw-r--r--baseboard/asurada/baseboard.h196
-rw-r--r--baseboard/asurada/baseboard_common.h44
-rw-r--r--baseboard/asurada/board_chipset.c24
-rw-r--r--baseboard/asurada/board_id.c107
-rw-r--r--baseboard/asurada/build.mk15
-rw-r--r--baseboard/asurada/hibernate.c37
-rw-r--r--baseboard/asurada/it5205_sbu.c68
-rw-r--r--baseboard/asurada/it5205_sbu.h13
-rw-r--r--baseboard/asurada/regulator.c46
-rw-r--r--baseboard/asurada/usb_pd_policy.c236
-rw-r--r--baseboard/asurada/usbc_config.c431
12 files changed, 0 insertions, 1318 deletions
diff --git a/baseboard/asurada/baseboard.c b/baseboard/asurada/baseboard.c
deleted file mode 100644
index c89348a562..0000000000
--- a/baseboard/asurada/baseboard.c
+++ /dev/null
@@ -1,101 +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.
- */
-
-/* Asurada 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/accelgyro_bmi_common.h"
-#include "driver/accel_lis2dw12.h"
-#include "driver/als_tcs3400.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 "it5205_sbu.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);
-}
-
-const struct cc_para_t *board_get_cc_tuning_parameter(enum usbpd_port port)
-{
- const static struct cc_para_t
- cc_parameter[CONFIG_USB_PD_ITE_ACTIVE_PORT_COUNT] = {
- {
- .rising_time = IT83XX_TX_PRE_DRIVING_TIME_1_UNIT,
- .falling_time = IT83XX_TX_PRE_DRIVING_TIME_2_UNIT,
- },
- {
- .rising_time = IT83XX_TX_PRE_DRIVING_TIME_1_UNIT,
- .falling_time = IT83XX_TX_PRE_DRIVING_TIME_2_UNIT,
- },
- };
-
- return &cc_parameter[port];
-}
diff --git a/baseboard/asurada/baseboard.h b/baseboard/asurada/baseboard.h
deleted file mode 100644
index f3c0808660..0000000000
--- a/baseboard/asurada/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.
- */
-
-/* Asurada 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/asurada/baseboard_common.h b/baseboard/asurada/baseboard_common.h
deleted file mode 100644
index 0245ae42bf..0000000000
--- a/baseboard/asurada/baseboard_common.h
+++ /dev/null
@@ -1,44 +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.
- */
-
-/* Asurada baseboard-specific onfiguration common to ECOS and Zephyr */
-
-#ifndef __CROS_EC_BASEBOARD_COMMON_H
-#define __CROS_EC_BASEBOARD_COMMON_H
-
-/* GPIO name remapping */
-#define GPIO_EN_HDMI_PWR GPIO_EC_X_GPIO1
-#define GPIO_USB_C1_FRS_EN GPIO_EC_X_GPIO1
-#define GPIO_USB_C1_PPC_INT_ODL GPIO_X_EC_GPIO2
-#define GPIO_PS185_EC_DP_HPD GPIO_X_EC_GPIO2
-#define GPIO_USB_C1_DP_IN_HPD GPIO_EC_X_GPIO3
-#define GPIO_PS185_PWRDN_ODL GPIO_EC_X_GPIO3
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-
-enum board_sub_board {
- SUB_BOARD_NONE = -1,
- SUB_BOARD_TYPEC,
- SUB_BOARD_HDMI,
- SUB_BOARD_COUNT,
-};
-
-/**
- * board_get_version() - Get the board version
- *
- * Read the ADC to obtain the board version
- *
- * @return board version in the range 0 to 14 inclusive
- */
-int board_get_version(void);
-
-void ppc_interrupt(enum gpio_signal signal);
-void bc12_interrupt(enum gpio_signal signal);
-void x_ec_interrupt(enum gpio_signal signal);
-
-#endif /* !__ASSEMBLER__ */
-#endif /* __CROS_EC_BASEBOARD_COMMON_H */
diff --git a/baseboard/asurada/board_chipset.c b/baseboard/asurada/board_chipset.c
deleted file mode 100644
index 4d12fb0334..0000000000
--- a/baseboard/asurada/board_chipset.c
+++ /dev/null
@@ -1,24 +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.
- */
-
-/* Asurada baseboard-chipset specific configuration */
-
-#include "common.h"
-#include "gpio.h"
-#include "hooks.h"
-
-/* Called on AP S3 -> S0 transition */
-static void board_chipset_resume(void)
-{
- gpio_set_level(GPIO_EC_BL_EN_OD, 1);
-}
-DECLARE_HOOK(HOOK_CHIPSET_RESUME, board_chipset_resume, HOOK_PRIO_DEFAULT);
-
-/* Called on AP S0 -> S3 transition */
-static void board_chipset_suspend(void)
-{
- gpio_set_level(GPIO_EC_BL_EN_OD, 0);
-}
-DECLARE_HOOK(HOOK_CHIPSET_SUSPEND, board_chipset_suspend, HOOK_PRIO_DEFAULT);
diff --git a/baseboard/asurada/board_id.c b/baseboard/asurada/board_id.c
deleted file mode 100644
index a4590f3199..0000000000
--- a/baseboard/asurada/board_id.c
+++ /dev/null
@@ -1,107 +0,0 @@
-/* Copyright 2020 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 "adc.h"
-#include "common.h"
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "timer.h"
-#include "util.h"
-
-/**
- * Conversion based on following table:
- *
- * ID | Rp | Rd | Voltage
- * | kOhm | kOhm | mV
- * ---+------+------+--------
- * 0 | 51.1 | 2.2 | 136.2
- * 1 | 51.1 | 6.81 | 388.1
- * 2 | 51.1 | 11 | 584.5
- * 3 | 57.6 | 18 | 785.7
- * 4 | 51.1 | 22 | 993.2
- * 5 | 51.1 | 30 | 1220.7
- * 6 | 51.1 | 39.2 | 1432.6
- * 7 | 56 | 56 | 1650.0
- * 8 | 47 | 61.9 | 1875.8
- * 9 | 47 | 80.6 | 2084.5
- * 10 | 56 | 124 | 2273.3
- * 11 | 51.1 | 150 | 2461.5
- * 12 | 47 | 200 | 2672.1
- * 13 | 47 | 330 | 2888.6
- * 14 | 47 | 680 | 3086.7
- */
-const static int voltage_map[] = {
- 136,
- 388,
- 584,
- 785,
- 993,
- 1220,
- 1432,
- 1650,
- 1875,
- 2084,
- 2273,
- 2461,
- 2672,
- 2888,
- 3086,
-};
-
-const int threshold_mv = 100;
-
-/**
- * Convert ADC value to board id using the voltage table above.
- *
- * @param ch ADC channel to read, usually ADC_BOARD_ID_0 or ADC_BOARD_ID_1.
- *
- * @return a non-negative board id, or negative value if error.
- */
-static int adc_value_to_numeric_id(enum adc_channel ch)
-{
- int mv;
-
- gpio_set_level(GPIO_EN_EC_ID_ODL, 0);
- /* Wait to allow cap charge */
- msleep(10);
-
- mv = adc_read_channel(ch);
- if (mv == ADC_READ_ERROR)
- mv = adc_read_channel(ch);
-
- gpio_set_level(GPIO_EN_EC_ID_ODL, 1);
-
- if (mv == ADC_READ_ERROR)
- return -EC_ERROR_UNKNOWN;
-
- for (int i = 0; i < ARRAY_SIZE(voltage_map); i++) {
- if (IN_RANGE(mv, voltage_map[i] - threshold_mv,
- voltage_map[i] + threshold_mv))
- return i;
- }
-
- return -EC_ERROR_UNKNOWN;
-}
-
-static int version = -1;
-
-/* b/163963220: Cache ADC value before board_hibernate_late() reads it */
-static void board_version_init(void)
-{
- version = adc_value_to_numeric_id(ADC_BOARD_ID_0);
- if (version < 0) {
- ccprints("WARN:BOARD_ID_0");
- ccprints("Assuming board id = 0");
-
- version = 0;
- }
-}
-DECLARE_HOOK(HOOK_INIT, board_version_init, HOOK_PRIO_INIT_ADC + 1);
-
-__override int board_get_version(void)
-{
- return version;
-}
diff --git a/baseboard/asurada/build.mk b/baseboard/asurada/build.mk
deleted file mode 100644
index ce7b7272bd..0000000000
--- a/baseboard/asurada/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/baseboard/asurada/hibernate.c b/baseboard/asurada/hibernate.c
deleted file mode 100644
index b26bd44adc..0000000000
--- a/baseboard/asurada/hibernate.c
+++ /dev/null
@@ -1,37 +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 "charger.h"
-#include "driver/charger/isl923x_public.h"
-#include "gpio.h"
-#include "system.h"
-
-/* Hayato board specific hibernate implementation */
-__override void board_hibernate_late(void)
-{
- /*
- * Turn off PP5000_A. Required for devices without Z-state.
- * Don't care for devices with Z-state.
- */
- gpio_set_level(GPIO_EN_PP5000_A, 0);
-
- /*
- * GPIO_EN_SLP_Z not implemented in rev0/1,
- * fallback to usual hibernate process.
- */
- if (board_get_version() <= 1) {
- if (IS_ENABLED(BOARD_ASURADA) ||
- (IS_ENABLED(CONFIG_ZEPHYR) &&
- IS_ENABLED(CONFIG_BOARD_ASURADA)))
- return;
- }
-
- isl9238c_hibernate(CHARGER_SOLO);
-
- gpio_set_level(GPIO_EN_SLP_Z, 1);
-
- /* should not reach here */
- __builtin_unreachable();
-}
diff --git a/baseboard/asurada/it5205_sbu.c b/baseboard/asurada/it5205_sbu.c
deleted file mode 100644
index 9ee59a5cc3..0000000000
--- a/baseboard/asurada/it5205_sbu.c
+++ /dev/null
@@ -1,68 +0,0 @@
-/* Copyright 2020 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.
- *
- * IT5205 Type-C SBU OVP handler
- */
-
-#include "console.h"
-#include "hooks.h"
-#include "it5205.h"
-#include "stdbool.h"
-#include "timer.h"
-#include "usb_mux.h"
-
-#define CPRINTS(format, args...) cprints(CC_USB, format, ## args)
-#define CPRINTF(format, args...) cprintf(CC_USB, format, ## args)
-
-#define OVP_RETRY_DELAY_US_MIN (100 * MSEC)
-
-static unsigned int ovp_retry_delay_us = OVP_RETRY_DELAY_US_MIN;
-
-static void reset_retry_delay(void)
-{
- CPRINTS("IT5205 SBU OVP cleared");
- ovp_retry_delay_us = OVP_RETRY_DELAY_US_MIN;
-}
-DECLARE_DEFERRED(reset_retry_delay);
-
-static void reset_csbu(void)
-{
- /* double the retry time up to 1 minute */
- ovp_retry_delay_us = MIN(ovp_retry_delay_us * 2, MINUTE);
- /* and reset it if interrupt not triggered in a short period */
- hook_call_deferred(&reset_retry_delay_data, 500 * MSEC);
-
- /* re-enable sbu interrupt */
- it5205h_enable_csbu_switch(&usb_muxes[0], false);
- it5205h_enable_csbu_switch(&usb_muxes[0], true);
-}
-DECLARE_DEFERRED(reset_csbu);
-
-static void it5205h_hook_ac_change(void)
-{
- int reg;
-
- /* Check if the board has IT5205H, and read its ovp status */
- if (i2c_read8(I2C_PORT_USB_MUX0, IT5205H_SBU_I2C_ADDR_FLAGS,
- IT5205H_REG_ISR, &reg))
- return;
-
- /*
- * Re-poll ovp status immediately if AC detached, because ovp will
- * likely be recovered.
- *
- * Always perform the re-poll even when this hook is triggered by
- * unrelated events.
- */
- if (reg & IT5205H_ISR_CSBU_OVP)
- hook_call_deferred(&reset_csbu_data, 0);
-}
-DECLARE_HOOK(HOOK_AC_CHANGE, it5205h_hook_ac_change, HOOK_PRIO_DEFAULT);
-
-void it5205h_sbu_interrupt(enum gpio_signal signal)
-{
- CPRINTS("IT5205 SBU OVP triggered");
- hook_call_deferred(&reset_csbu_data, ovp_retry_delay_us);
- hook_call_deferred(&reset_retry_delay_data, -1);
-}
diff --git a/baseboard/asurada/it5205_sbu.h b/baseboard/asurada/it5205_sbu.h
deleted file mode 100644
index 8dc59520dd..0000000000
--- a/baseboard/asurada/it5205_sbu.h
+++ /dev/null
@@ -1,13 +0,0 @@
-/* Copyright 2020 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.
- *
- * IT5205 Type-C SBU OVP handler
- */
-
-#ifndef __CROS_EC_ASURADA_IT5205_SBU_H
-#define __CROS_EC_ASURADA_IT5205_SBU_H
-
-void it5205h_sbu_interrupt(enum gpio_signal signal);
-
-#endif /* __CROS_EC_ASURADA_IT5205_SBU_H */
diff --git a/baseboard/asurada/regulator.c b/baseboard/asurada/regulator.c
deleted file mode 100644
index 35670bda82..0000000000
--- a/baseboard/asurada/regulator.c
+++ /dev/null
@@ -1,46 +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 "common.h"
-#include "bc12/mt6360_public.h"
-
-/* SD Card */
-int board_regulator_get_info(uint32_t index, char *name,
- uint16_t *num_voltages, uint16_t *voltages_mv)
-{
- enum mt6360_regulator_id id = index;
-
- return mt6360_regulator_get_info(id, name, num_voltages,
- voltages_mv);
-}
-
-int board_regulator_enable(uint32_t index, uint8_t enable)
-{
- enum mt6360_regulator_id id = index;
-
- return mt6360_regulator_enable(id, enable);
-}
-
-int board_regulator_is_enabled(uint32_t index, uint8_t *enabled)
-{
- enum mt6360_regulator_id id = index;
-
- return mt6360_regulator_is_enabled(id, enabled);
-}
-
-int board_regulator_set_voltage(uint32_t index, uint32_t min_mv,
- uint32_t max_mv)
-{
- enum mt6360_regulator_id id = index;
-
- return mt6360_regulator_set_voltage(id, min_mv, max_mv);
-}
-
-int board_regulator_get_voltage(uint32_t index, uint32_t *voltage_mv)
-{
- enum mt6360_regulator_id id = index;
-
- return mt6360_regulator_get_voltage(id, voltage_mv);
-}
diff --git a/baseboard/asurada/usb_pd_policy.c b/baseboard/asurada/usb_pd_policy.c
deleted file mode 100644
index f9ba7e5a4d..0000000000
--- a/baseboard/asurada/usb_pd_policy.c
+++ /dev/null
@@ -1,236 +0,0 @@
-/* Copyright 2020 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 "adc.h"
-#include "atomic.h"
-#include "baseboard_common.h"
-#include "charge_manager.h"
-#include "chipset.h"
-#include "timer.h"
-#include "usb_dp_alt_mode.h"
-#include "usb_mux.h"
-#include "usb_pd.h"
-#include "usbc_ppc.h"
-
-#if CONFIG_USB_PD_3A_PORTS != 1
-#error Asurada reference must have at least one 3.0 A port
-#endif
-
-#define CPRINTS(format, args...) cprints(CC_USBPD, format, ## args)
-#define CPRINTF(format, args...) cprintf(CC_USBPD, format, ## args)
-
-int svdm_get_hpd_gpio(int port)
-{
- /* HPD is low active, inverse the result */
- return !gpio_get_level(GPIO_EC_DPBRDG_HPD_ODL);
-}
-
-void svdm_set_hpd_gpio(int port, int en)
-{
- /*
- * HPD is low active, inverse the en
- * TODO: C0&C1 shares the same HPD, implement FCFS policy.
- */
- gpio_set_level(GPIO_EC_DPBRDG_HPD_ODL, !en);
-}
-
-/**
- * Is the port fine to be muxed its DisplayPort lines?
- *
- * Only one port can be muxed to DisplayPort at a time.
- *
- * @param port Port number of TCPC.
- * @return 1 is fine; 0 is bad as other port is already muxed;
- */
-static int is_dp_muxable(int port)
-{
- int i;
-
- for (i = 0; i < board_get_usb_pd_port_count(); i++) {
- if (i != port) {
- if (usb_mux_get(i) & USB_PD_MUX_DP_ENABLED)
- return 0;
- }
- }
-
- return 1;
-}
-
-__override int svdm_dp_attention(int port, uint32_t *payload)
-{
- int lvl = PD_VDO_DPSTS_HPD_LVL(payload[1]);
- int irq = PD_VDO_DPSTS_HPD_IRQ(payload[1]);
-#ifdef CONFIG_USB_PD_DP_HPD_GPIO
- int cur_lvl = svdm_get_hpd_gpio(port);
-#endif /* CONFIG_USB_PD_DP_HPD_GPIO */
- mux_state_t mux_state;
-
- dp_status[port] = payload[1];
-
- if (!is_dp_muxable(port)) {
- /* TODO(waihong): Info user? */
- CPRINTS("p%d: The other port is already muxed.", port);
- return 0; /* nak */
- }
-
- if (lvl)
- gpio_set_level_verbose(CC_USBPD, GPIO_DP_AUX_PATH_SEL, port);
-
- if (chipset_in_state(CHIPSET_STATE_ANY_SUSPEND) &&
- (irq || lvl))
- /*
- * Wake up the AP. IRQ or level high indicates a DP sink is now
- * present.
- */
- if (IS_ENABLED(CONFIG_MKBP_EVENT))
- pd_notify_dp_alt_mode_entry(port);
-
- /* Its initial DP status message prior to config */
- if (!(dp_flags[port] & DP_FLAGS_DP_ON)) {
- if (lvl)
- dp_flags[port] |= DP_FLAGS_HPD_HI_PENDING;
- return 1;
- }
-
-#ifdef CONFIG_USB_PD_DP_HPD_GPIO
- if (irq && !lvl) {
- /*
- * IRQ can only be generated when the level is high, because
- * the IRQ is signaled by a short low pulse from the high level.
- */
- CPRINTF("ERR:HPD:IRQ&LOW\n");
- return 0; /* nak */
- }
-
- if (irq && cur_lvl) {
- uint64_t now = get_time().val;
- /* wait for the minimum spacing between IRQ_HPD if needed */
- if (now < svdm_hpd_deadline[port])
- usleep(svdm_hpd_deadline[port] - now);
-
- /* generate IRQ_HPD pulse */
- svdm_set_hpd_gpio(port, 0);
- /*
- * b/171172053#comment14: since the HPD_DSTREAM_DEBOUNCE_IRQ is
- * very short (500us), we can use udelay instead of usleep for
- * more stable pulse period.
- */
- udelay(HPD_DSTREAM_DEBOUNCE_IRQ);
- svdm_set_hpd_gpio(port, 1);
- } else {
- svdm_set_hpd_gpio(port, lvl);
- }
-
- /* set the minimum time delay (2ms) for the next HPD IRQ */
- svdm_hpd_deadline[port] = get_time().val + HPD_USTREAM_DEBOUNCE_LVL;
-#endif /* CONFIG_USB_PD_DP_HPD_GPIO */
-
- mux_state = (lvl ? USB_PD_MUX_HPD_LVL : USB_PD_MUX_HPD_LVL_DEASSERTED) |
- (irq ? USB_PD_MUX_HPD_IRQ : USB_PD_MUX_HPD_IRQ_DEASSERTED);
- usb_mux_hpd_update(port, mux_state);
-
-#ifdef USB_PD_PORT_TCPC_MST
- if (port == USB_PD_PORT_TCPC_MST)
- baseboard_mst_enable_control(port, lvl);
-#endif
-
- /* ack */
- return 1;
-}
-
-__override void svdm_exit_dp_mode(int port)
-{
-#ifdef CONFIG_USB_PD_DP_HPD_GPIO
- svdm_set_hpd_gpio(port, 0);
-#endif /* CONFIG_USB_PD_DP_HPD_GPIO */
- usb_mux_hpd_update(port, USB_PD_MUX_HPD_LVL_DEASSERTED |
- USB_PD_MUX_HPD_IRQ_DEASSERTED);
-
-#ifdef USB_PD_PORT_TCPC_MST
- if (port == USB_PD_PORT_TCPC_MST)
- baseboard_mst_enable_control(port, 0);
-#endif
-}
-
-int pd_snk_is_vbus_provided(int port)
-{
- static int vbus_prev[CONFIG_USB_PD_PORT_MAX_COUNT];
- int vbus;
-
- if ((IS_ENABLED(BOARD_HAYATO) && board_get_version() < 4) ||
- (IS_ENABLED(BOARD_SPHERION) && board_get_version() < 1))
- return ppc_is_vbus_present(port);
-
- /*
- * (b:181203590#comment20) TODO(yllin): use
- * PD_VSINK_DISCONNECT_PD for non-5V case.
- */
- vbus = adc_read_channel(board_get_vbus_adc(port)) >=
- PD_V_SINK_DISCONNECT_MAX;
-
-#ifdef CONFIG_USB_CHARGER
- /*
- * There's no PPC to inform VBUS change for usb_charger, so inform
- * the usb_charger now.
- */
- if (!!(vbus_prev[port] != vbus))
- usb_charger_vbus_change(port, vbus);
-
- if (vbus)
- atomic_or(&vbus_prev[port], 1);
- else
- atomic_clear(&vbus_prev[port]);
-#endif
- return vbus;
-}
-
-void pd_power_supply_reset(int port)
-{
- int prev_en;
-
- prev_en = ppc_is_sourcing_vbus(port);
-
- /* Disable VBUS. */
- ppc_vbus_source_enable(port, 0);
-
- /* Enable discharge if we were previously sourcing 5V */
- if (prev_en)
- pd_set_vbus_discharge(port, 1);
-
- /* Notify host of power info change. */
- pd_send_host_event(PD_EVENT_POWER_CHANGE);
-}
-
-int pd_check_vconn_swap(int port)
-{
- /* Allow Vconn swap if AP is on. */
- return chipset_in_state(CHIPSET_STATE_SUSPEND | CHIPSET_STATE_ON);
-}
-
-int pd_set_power_supply_ready(int port)
-{
- int rv;
-
- /* Disable charging. */
- rv = ppc_vbus_sink_enable(port, 0);
- if (rv)
- return rv;
-
- pd_set_vbus_discharge(port, 0);
-
- /* Provide Vbus. */
- rv = ppc_vbus_source_enable(port, 1);
- if (rv)
- return rv;
-
- /* Notify host of power info change. */
- pd_send_host_event(PD_EVENT_POWER_CHANGE);
-
- return EC_SUCCESS;
-}
-
-int board_vbus_source_enabled(int port)
-{
- return ppc_is_sourcing_vbus(port);
-}
diff --git a/baseboard/asurada/usbc_config.c b/baseboard/asurada/usbc_config.c
deleted file mode 100644
index e552c97771..0000000000
--- a/baseboard/asurada/usbc_config.c
+++ /dev/null
@@ -1,431 +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.
- */
-
-/* Asurada baseboard-specific USB-C configuration */
-
-#include "adc.h"
-#include "baseboard_common.h"
-#include "bc12/pi3usb9201_public.h"
-#include "bc12/mt6360_public.h"
-#include "button.h"
-#include "charger.h"
-#include "charge_state_v2.h"
-#include "charger/isl923x_public.h"
-#include "console.h"
-#include "ec_commands.h"
-#include "extpower.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "lid_switch.h"
-#include "task.h"
-#include "ppc/syv682x_public.h"
-#include "power.h"
-#include "power_button.h"
-#include "spi.h"
-#include "switch.h"
-#include "tablet_mode.h"
-#include "tcpm/it8xxx2_pd_public.h"
-#include "uart.h"
-#include "usbc_ppc.h"
-#include "usb_charge.h"
-#include "usb_mux.h"
-#include "usb_mux/ps8743_public.h"
-#include "usb_mux/it5205_public.h"
-#include "usb_pd_tcpm.h"
-#include "usbc_ppc.h"
-
-#define CPRINTSUSB(format, args...) cprints(CC_USBCHARGE, format, ## args)
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ## args)
-#define CPRINTF(format, args...) cprintf(CC_SYSTEM, format, ## args)
-
-const struct charger_config_t chg_chips[] = {
- {
- .i2c_port = I2C_PORT_CHARGER,
- .i2c_addr_flags = ISL923X_ADDR_FLAGS,
- .drv = &isl923x_drv,
- },
-};
-
-/* Baseboard */
-
-static void baseboard_init(void)
-{
- gpio_enable_interrupt(GPIO_USB_C0_BC12_INT_ODL);
- gpio_enable_interrupt(GPIO_AP_XHCI_INIT_DONE);
-}
-DECLARE_HOOK(HOOK_INIT, baseboard_init, HOOK_PRIO_DEFAULT-1);
-
-/* Sub-board */
-
-enum board_sub_board board_get_sub_board(void)
-{
- static enum board_sub_board sub = SUB_BOARD_NONE;
-
- if (sub != SUB_BOARD_NONE)
- return sub;
-
- /* HDMI board has external pull high. */
- if (gpio_get_level(GPIO_EC_X_GPIO3)) {
- sub = SUB_BOARD_HDMI;
- /* Only has 1 PPC with HDMI subboard */
- ppc_cnt = 1;
- /* EC_X_GPIO1 */
- gpio_set_flags(GPIO_EN_HDMI_PWR, GPIO_OUT_HIGH);
- /* X_EC_GPIO2 */
- gpio_set_flags(GPIO_PS185_EC_DP_HPD, GPIO_INT_BOTH);
- /* EC_X_GPIO3 */
- gpio_set_flags(GPIO_PS185_PWRDN_ODL, GPIO_ODR_HIGH);
- } else {
- sub = SUB_BOARD_TYPEC;
- /* EC_X_GPIO1 */
- gpio_set_flags(GPIO_USB_C1_FRS_EN, GPIO_OUT_LOW);
- /* X_EC_GPIO2 */
- gpio_set_flags(GPIO_USB_C1_PPC_INT_ODL,
- GPIO_INT_BOTH | GPIO_PULL_UP);
- /* EC_X_GPIO3 */
- gpio_set_flags(GPIO_USB_C1_DP_IN_HPD, GPIO_OUT_LOW);
- }
-
- CPRINTS("Detect %s SUB", sub == SUB_BOARD_HDMI ? "HDMI" : "TYPEC");
- return sub;
-}
-
-static void sub_board_init(void)
-{
- board_get_sub_board();
-}
-DECLARE_HOOK(HOOK_INIT, sub_board_init, HOOK_PRIO_INIT_I2C - 1);
-
-/* Detect subboard */
-static void board_tcpc_init(void)
-{
- gpio_enable_interrupt(GPIO_USB_C0_PPC_INT_ODL);
- /* C1: GPIO_USB_C1_PPC_INT_ODL & HDMI: GPIO_PS185_EC_DP_HPD */
- gpio_enable_interrupt(GPIO_X_EC_GPIO2);
-
- /* If this is not a Type-C subboard, disable the task. */
- if (board_get_sub_board() != SUB_BOARD_TYPEC)
- task_disable_task(TASK_ID_PD_C1);
-}
-/* Must be done after I2C and subboard */
-DECLARE_HOOK(HOOK_INIT, board_tcpc_init, HOOK_PRIO_INIT_I2C + 1);
-
-/* PPC */
-struct ppc_config_t ppc_chips[CONFIG_USB_PD_PORT_MAX_COUNT] = {
- {
- .i2c_port = I2C_PORT_PPC0,
- .i2c_addr_flags = SYV682X_ADDR0_FLAGS,
- .drv = &syv682x_drv,
- .frs_en = GPIO_USB_C0_FRS_EN,
- },
- {
- .i2c_port = I2C_PORT_PPC1,
- .i2c_addr_flags = SYV682X_ADDR0_FLAGS,
- .drv = &syv682x_drv,
- .frs_en = GPIO_USB_C1_FRS_EN,
- },
-};
-unsigned int ppc_cnt = ARRAY_SIZE(ppc_chips);
-
-/* BC12 */
-const struct mt6360_config_t mt6360_config = {
- .i2c_port = I2C_PORT_POWER,
- .i2c_addr_flags = MT6360_PMU_I2C_ADDR_FLAGS,
-};
-
-const struct pi3usb9201_config_t
- pi3usb9201_bc12_chips[CONFIG_USB_PD_PORT_MAX_COUNT] = {
- /* [0]: unused */
- [1] = {
- .i2c_port = I2C_PORT_PPC1,
- .i2c_addr_flags = PI3USB9201_I2C_ADDR_3_FLAGS,
- }
-};
-
-struct bc12_config bc12_ports[CONFIG_USB_PD_PORT_MAX_COUNT] = {
- { .drv = &mt6360_drv },
- { .drv = &pi3usb9201_drv },
-};
-
-void bc12_interrupt(enum gpio_signal signal)
-{
- if (signal == GPIO_USB_C0_BC12_INT_ODL)
- task_set_event(TASK_ID_USB_CHG_P0, USB_CHG_EVENT_BC12);
- else
- task_set_event(TASK_ID_USB_CHG_P1, USB_CHG_EVENT_BC12);
-}
-
-static void board_sub_bc12_init(void)
-{
- if (board_get_sub_board() == SUB_BOARD_TYPEC)
- gpio_enable_interrupt(GPIO_USB_C1_BC12_INT_L);
- else
- /* If this is not a Type-C subboard, disable the task. */
- task_disable_task(TASK_ID_USB_CHG_P1);
-}
-/* Must be done after I2C and subboard */
-DECLARE_HOOK(HOOK_INIT, board_sub_bc12_init, HOOK_PRIO_INIT_I2C + 1);
-
-void ppc_interrupt(enum gpio_signal signal)
-{
- if (signal == GPIO_USB_C0_PPC_INT_ODL)
- /* C0: PPC interrupt */
- syv682x_interrupt(0);
-}
-
-__override uint8_t board_get_usb_pd_port_count(void)
-{
- if (board_get_sub_board() == SUB_BOARD_TYPEC)
- return CONFIG_USB_PD_PORT_MAX_COUNT;
- else
- return CONFIG_USB_PD_PORT_MAX_COUNT - 1;
-}
-
-/* USB-A */
-const int usb_port_enable[] = {
- GPIO_EN_PP5000_USB_A0_VBUS,
-};
-BUILD_ASSERT(ARRAY_SIZE(usb_port_enable) == USB_PORT_COUNT);
-
-void usb_a0_interrupt(enum gpio_signal signal)
-{
- enum usb_charge_mode mode = gpio_get_level(signal) ?
- USB_CHARGE_MODE_ENABLED : USB_CHARGE_MODE_DISABLED;
-
- for (int i = 0; i < USB_PORT_COUNT; i++)
- usb_charge_set_mode(i, mode, USB_ALLOW_SUSPEND_CHARGE);
-}
-
-static int board_ps8743_mux_set(const struct usb_mux *me,
- mux_state_t mux_state)
-{
- int rv = EC_SUCCESS;
- int reg = 0;
-
- rv = ps8743_read(me, PS8743_REG_MODE, &reg);
- if (rv)
- return rv;
-
- /* Disable FLIP pin, enable I2C control. */
- reg |= PS8743_MODE_FLIP_REG_CONTROL;
- /* Disable CE_USB pin, enable I2C control. */
- reg |= PS8743_MODE_USB_REG_CONTROL;
- /* Disable CE_DP pin, enable I2C control. */
- reg |= PS8743_MODE_DP_REG_CONTROL;
-
- /*
- * DP specific config
- *
- * Enable/Disable IN_HPD on the DB.
- */
- gpio_set_level(GPIO_USB_C1_DP_IN_HPD,
- mux_state & USB_PD_MUX_DP_ENABLED);
-
- return ps8743_write(me, PS8743_REG_MODE, reg);
-}
-
-const struct usb_mux usbc0_virtual_mux = {
- .usb_port = 0,
- .driver = &virtual_usb_mux_driver,
- .hpd_update = &virtual_hpd_update,
-};
-
-const struct usb_mux usbc1_virtual_mux = {
- .usb_port = 1,
- .driver = &virtual_usb_mux_driver,
- .hpd_update = &virtual_hpd_update,
-};
-
-const struct usb_mux usb_muxes[CONFIG_USB_PD_PORT_MAX_COUNT] = {
- {
- .usb_port = 0,
- .i2c_port = I2C_PORT_USB_MUX0,
- .i2c_addr_flags = IT5205_I2C_ADDR1_FLAGS,
- .driver = &it5205_usb_mux_driver,
- .next_mux = &usbc0_virtual_mux,
- },
- {
- .usb_port = 1,
- .i2c_port = I2C_PORT_USB_MUX1,
- .i2c_addr_flags = PS8743_I2C_ADDR0_FLAG,
- .driver = &ps8743_usb_mux_driver,
- .next_mux = &usbc1_virtual_mux,
- .board_set = &board_ps8743_mux_set,
- },
-};
-
-void board_overcurrent_event(int port, int is_overcurrented)
-{
- /* TODO: check correct operation for Asurada */
-}
-
-/* TCPC */
-const struct tcpc_config_t tcpc_config[CONFIG_USB_PD_PORT_MAX_COUNT] = {
- {
- .bus_type = EC_BUS_TYPE_EMBEDDED,
- /* TCPC is embedded within EC so no i2c config needed */
- .drv = &it8xxx2_tcpm_drv,
- /* Alert is active-low, push-pull */
- .flags = 0,
- },
- {
- .bus_type = EC_BUS_TYPE_EMBEDDED,
- /* TCPC is embedded within EC so no i2c config needed */
- .drv = &it8xxx2_tcpm_drv,
- /* Alert is active-low, push-pull */
- .flags = 0,
- },
-};
-
-uint16_t tcpc_get_alert_status(void)
-{
- /*
- * C0 & C1: TCPC is embedded in the EC and processes interrupts in the
- * chip code (it83xx/intc.c)
- */
- return 0;
-}
-
-void board_reset_pd_mcu(void)
-{
- /*
- * C0 & C1: TCPC is embedded in the EC and processes interrupts in the
- * chip code (it83xx/intc.c)
- */
-}
-
-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);
-}
-
-void board_pd_vconn_ctrl(int port, enum usbpd_cc_pin cc_pin, int enabled)
-{
- /*
- * We ignore the cc_pin and PPC vconn because polarity and PPC vconn
- * should already be set correctly in the PPC driver via the pd
- * state machine.
- */
-}
-
-int board_set_active_charge_port(int port)
-{
- int i;
- int is_valid_port = port == 0 || (port == 1 && board_get_sub_board() ==
- SUB_BOARD_TYPEC);
-
- if (!is_valid_port && port != CHARGE_PORT_NONE)
- return EC_ERROR_INVAL;
-
- if (port == CHARGE_PORT_NONE) {
- CPRINTS("Disabling all charger ports");
-
- /* Disable all ports. */
- for (i = 0; i < ppc_cnt; i++) {
- /*
- * Do not return early if one fails otherwise we can
- * get into a boot loop assertion failure.
- */
- if (ppc_vbus_sink_enable(i, 0))
- CPRINTS("Disabling C%d as sink failed.", i);
- }
-
- return EC_SUCCESS;
- }
-
- /* Check if the port is sourcing VBUS. */
- if (ppc_is_sourcing_vbus(port)) {
- CPRINTS("Skip enable C%d", port);
- return EC_ERROR_INVAL;
- }
-
- CPRINTS("New charge port: C%d", port);
-
- /*
- * Turn off the other ports' sink path FETs, before enabling the
- * requested charge port.
- */
- for (i = 0; i < ppc_cnt; i++) {
- if (i == port)
- continue;
-
- if (ppc_vbus_sink_enable(i, 0))
- CPRINTS("C%d: sink path disable failed.", i);
- }
-
- /* Enable requested charge port. */
- if (ppc_vbus_sink_enable(port, 1)) {
- CPRINTS("C%d: sink path enable failed.", port);
- return EC_ERROR_UNKNOWN;
- }
-
- return EC_SUCCESS;
-}
-
-/**
- * Handle PS185 HPD changing state.
- */
-int debounced_hpd;
-
-static void ps185_hdmi_hpd_deferred(void)
-{
- const int new_hpd = gpio_get_level(GPIO_PS185_EC_DP_HPD);
-
- /* HPD status not changed, probably a glitch, just return. */
- if (debounced_hpd == new_hpd)
- return;
-
- debounced_hpd = new_hpd;
-
- gpio_set_level(GPIO_EC_DPBRDG_HPD_ODL, !debounced_hpd);
- CPRINTS(debounced_hpd ? "HDMI plug" : "HDMI unplug");
-}
-DECLARE_DEFERRED(ps185_hdmi_hpd_deferred);
-
-#define PS185_HPD_DEBOUCE 250
-
-static void hdmi_hpd_interrupt(enum gpio_signal signal)
-{
- hook_call_deferred(&ps185_hdmi_hpd_deferred_data, PS185_HPD_DEBOUCE);
-}
-
-/* HDMI/TYPE-C function shared subboard interrupt */
-void x_ec_interrupt(enum gpio_signal signal)
-{
- int sub = board_get_sub_board();
-
- if (sub == SUB_BOARD_TYPEC)
- /* C1: PPC interrupt */
- syv682x_interrupt(1);
- else if (sub == SUB_BOARD_HDMI)
- hdmi_hpd_interrupt(signal);
- else
- CPRINTS("Undetected subboard interrupt.");
-}
-
-int ppc_get_alert_status(int port)
-{
- if (port == 0)
- return gpio_get_level(GPIO_USB_C0_PPC_INT_ODL) == 0;
- if (port == 1 && board_get_sub_board() == SUB_BOARD_TYPEC)
- return gpio_get_level(GPIO_USB_C1_PPC_INT_ODL) == 0;
-
- return 0;
-}
-
-#ifdef CONFIG_USB_PD_VBUS_MEASURE_ADC_EACH_PORT
-enum adc_channel board_get_vbus_adc(int port)
-{
- if (port == 0)
- return ADC_VBUS_C0;
- if (port == 1)
- return ADC_VBUS_C1;
- CPRINTSUSB("Unknown vbus adc port id: %d", port);
- return ADC_VBUS_C0;
-}
-#endif /* CONFIG_USB_PD_VBUS_MEASURE_ADC_EACH_PORT */