summaryrefslogtreecommitdiff
path: root/zephyr/program/nissa/src
diff options
context:
space:
mode:
Diffstat (limited to 'zephyr/program/nissa/src')
-rw-r--r--zephyr/program/nissa/src/board_power.c169
-rw-r--r--zephyr/program/nissa/src/common.c199
-rw-r--r--zephyr/program/nissa/src/led.c52
-rw-r--r--zephyr/program/nissa/src/sub_board.c288
4 files changed, 0 insertions, 708 deletions
diff --git a/zephyr/program/nissa/src/board_power.c b/zephyr/program/nissa/src/board_power.c
deleted file mode 100644
index 858076686b..0000000000
--- a/zephyr/program/nissa/src/board_power.c
+++ /dev/null
@@ -1,169 +0,0 @@
-/* Copyright 2022 The ChromiumOS Authors
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "gpio/gpio.h"
-#include "gpio_signal.h"
-
-#include <zephyr/drivers/gpio.h>
-#include <zephyr/logging/log.h>
-#include <zephyr/sys/atomic.h>
-
-#include <ap_power/ap_power.h>
-#include <ap_power/ap_power_events.h>
-#include <ap_power/ap_power_interface.h>
-#include <ap_power_override_functions.h>
-#include <power_signals.h>
-#include <x86_power_signals.h>
-
-LOG_MODULE_DECLARE(ap_pwrseq, LOG_LEVEL_INF);
-
-#define X86_NON_DSX_ADLP_NONPWRSEQ_FORCE_SHUTDOWN_TO_MS 5
-
-static bool s0_stable;
-
-static void generate_ec_soc_dsw_pwrok_handler(int delay)
-{
- int in_sig_val = power_signal_get(PWR_DSW_PWROK);
-
- if (in_sig_val != power_signal_get(PWR_EC_SOC_DSW_PWROK)) {
- if (in_sig_val)
- k_msleep(delay);
- power_signal_set(PWR_EC_SOC_DSW_PWROK, 1);
- }
-}
-
-void board_ap_power_force_shutdown(void)
-{
- int timeout_ms = X86_NON_DSX_ADLP_NONPWRSEQ_FORCE_SHUTDOWN_TO_MS;
-
- if (s0_stable) {
- /* Enable these power signals in case of sudden shutdown */
- power_signal_enable(PWR_DSW_PWROK);
- power_signal_enable(PWR_PG_PP1P05);
- }
-
- power_signal_set(PWR_EC_SOC_DSW_PWROK, 0);
- power_signal_set(PWR_EC_PCH_RSMRST, 0);
-
- while (power_signal_get(PWR_RSMRST) == 0 &&
- power_signal_get(PWR_SLP_SUS) == 0 && timeout_ms > 0) {
- k_msleep(1);
- timeout_ms--;
- }
- if (power_signal_get(PWR_SLP_SUS) == 0) {
- LOG_WRN("SLP_SUS is not deasserted! Assuming G3");
- }
-
- if (power_signal_get(PWR_RSMRST) == 1) {
- LOG_WRN("RSMRST is not deasserted! Assuming G3");
- }
-
- power_signal_set(PWR_EN_PP3300_A, 0);
-
- power_signal_set(PWR_EN_PP5000_A, 0);
-
- timeout_ms = X86_NON_DSX_ADLP_NONPWRSEQ_FORCE_SHUTDOWN_TO_MS;
- while (power_signal_get(PWR_DSW_PWROK) && timeout_ms > 0) {
- k_msleep(1);
- timeout_ms--;
- };
-
- if (power_signal_get(PWR_DSW_PWROK))
- LOG_WRN("DSW_PWROK didn't go low! Assuming G3.");
-
- power_signal_disable(PWR_DSW_PWROK);
- power_signal_disable(PWR_PG_PP1P05);
- s0_stable = false;
-}
-
-void board_ap_power_action_g3_s5(void)
-{
- power_signal_enable(PWR_DSW_PWROK);
- power_signal_enable(PWR_PG_PP1P05);
-
- LOG_DBG("Turning on PWR_EN_PP5000_A and PWR_EN_PP3300_A");
- power_signal_set(PWR_EN_PP5000_A, 1);
- power_signal_set(PWR_EN_PP3300_A, 1);
-
- power_wait_signals_timeout(IN_PGOOD_ALL_CORE,
- AP_PWRSEQ_DT_VALUE(wait_signal_timeout));
-
- generate_ec_soc_dsw_pwrok_handler(AP_PWRSEQ_DT_VALUE(dsw_pwrok_delay));
- s0_stable = false;
-}
-
-void board_ap_power_action_s3_s0(void)
-{
- s0_stable = false;
-}
-
-void board_ap_power_action_s0_s3(void)
-{
- power_signal_enable(PWR_DSW_PWROK);
- power_signal_enable(PWR_PG_PP1P05);
- s0_stable = false;
-}
-
-void board_ap_power_action_s0(void)
-{
- if (s0_stable) {
- return;
- }
- LOG_INF("Reaching S0");
- power_signal_disable(PWR_DSW_PWROK);
- power_signal_disable(PWR_PG_PP1P05);
- s0_stable = true;
-}
-
-int board_ap_power_assert_pch_power_ok(void)
-{
- /* Pass though PCH_PWROK */
- if (power_signal_get(PWR_PCH_PWROK) == 0) {
- k_msleep(AP_PWRSEQ_DT_VALUE(pch_pwrok_delay));
- power_signal_set(PWR_PCH_PWROK, 1);
- }
-
- return 0;
-}
-
-bool board_ap_power_check_power_rails_enabled(void)
-{
- return power_signal_get(PWR_EN_PP3300_A) &&
- power_signal_get(PWR_EN_PP5000_A) &&
- power_signal_get(PWR_EC_SOC_DSW_PWROK);
-}
-
-int board_power_signal_get(enum power_signal signal)
-{
- switch (signal) {
- default:
- LOG_ERR("Unknown signal for board get: %d", signal);
- return -EINVAL;
-
- case PWR_ALL_SYS_PWRGD:
- /*
- * All system power is good.
- * Checks that PWR_SLP_S3 is off, and
- * the GPIO signal for all power good is set,
- * and that the 1.05 volt line is ready.
- */
- if (power_signal_get(PWR_SLP_S3)) {
- return 0;
- }
- if (!gpio_pin_get_dt(
- GPIO_DT_FROM_NODELABEL(gpio_all_sys_pwrgd))) {
- return 0;
- }
- if (!power_signal_get(PWR_PG_PP1P05)) {
- return 0;
- }
- return 1;
- }
-}
-
-int board_power_signal_set(enum power_signal signal, int value)
-{
- return -EINVAL;
-}
diff --git a/zephyr/program/nissa/src/common.c b/zephyr/program/nissa/src/common.c
deleted file mode 100644
index d437bfca47..0000000000
--- a/zephyr/program/nissa/src/common.c
+++ /dev/null
@@ -1,199 +0,0 @@
-/* Copyright 2022 The ChromiumOS Authors
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "battery.h"
-#include "charge_state_v2.h"
-#include "charger.h"
-#include "chipset.h"
-#include "cros_cbi.h"
-#include "hooks.h"
-#include "nissa_common.h"
-#include "system.h"
-#include "usb_mux.h"
-
-#include <zephyr/device.h>
-#include <zephyr/logging/log.h>
-
-#include <ap_power/ap_power.h>
-LOG_MODULE_REGISTER(nissa, CONFIG_NISSA_LOG_LEVEL);
-
-static uint8_t cached_usb_pd_port_count;
-
-__override uint8_t board_get_usb_pd_port_count(void)
-{
- __ASSERT(cached_usb_pd_port_count != 0,
- "sub-board detection did not run before a port count request");
- if (cached_usb_pd_port_count == 0)
- LOG_WRN("USB PD Port count not initialized!");
- return cached_usb_pd_port_count;
-}
-
-static void board_power_change(struct ap_power_ev_callback *cb,
- struct ap_power_ev_data data)
-{
- /*
- * Enable power to pen garage when system is active (safe even if no
- * pen is present).
- */
- const struct gpio_dt_spec *const pen_power_gpio =
- GPIO_DT_FROM_NODELABEL(gpio_en_pp5000_pen_x);
-
- switch (data.event) {
- case AP_POWER_STARTUP:
- gpio_pin_set_dt(pen_power_gpio, 1);
- break;
- case AP_POWER_SHUTDOWN:
- gpio_pin_set_dt(pen_power_gpio, 0);
- break;
- default:
- break;
- }
-}
-
-/*
- * Initialise the USB PD port count, which
- * depends on which sub-board is attached.
- */
-static void board_setup_init(void)
-{
- static struct ap_power_ev_callback cb;
-
- ap_power_ev_init_callback(&cb, board_power_change,
- AP_POWER_STARTUP | AP_POWER_SHUTDOWN);
- ap_power_ev_add_callback(&cb);
-
- switch (nissa_get_sb_type()) {
- default:
- cached_usb_pd_port_count = 1;
- break;
-
- case NISSA_SB_C_A:
- case NISSA_SB_C_LTE:
- cached_usb_pd_port_count = 2;
- break;
- }
-}
-/*
- * Make sure setup is done after EEPROM is readable.
- */
-DECLARE_HOOK(HOOK_INIT, board_setup_init, HOOK_PRIO_INIT_I2C);
-
-int pd_check_vconn_swap(int port)
-{
- /* Allow VCONN swaps if the AP is on. */
- return chipset_in_state(CHIPSET_STATE_ANY_SUSPEND | CHIPSET_STATE_ON);
-}
-
-/*
- * Count of chargers depends on sub board presence.
- */
-__override uint8_t board_get_charger_chip_count(void)
-{
- return board_get_usb_pd_port_count();
-}
-
-/*
- * Retrieve sub-board type from FW_CONFIG.
- */
-enum nissa_sub_board_type nissa_get_sb_type(void)
-{
- static enum nissa_sub_board_type sb = NISSA_SB_UNKNOWN;
- int ret;
- uint32_t val;
-
- /*
- * Return cached value.
- */
- if (sb != NISSA_SB_UNKNOWN)
- return sb;
-
- sb = NISSA_SB_NONE; /* Defaults to none */
- ret = cros_cbi_get_fw_config(FW_SUB_BOARD, &val);
- if (ret != 0) {
- LOG_WRN("Error retrieving CBI FW_CONFIG field %d",
- FW_SUB_BOARD);
- return sb;
- }
- switch (val) {
- default:
- LOG_WRN("No sub-board defined");
- break;
- case FW_SUB_BOARD_1:
- sb = NISSA_SB_C_A;
- LOG_INF("SB: USB type C, USB type A");
- break;
-
- case FW_SUB_BOARD_2:
- sb = NISSA_SB_C_LTE;
- LOG_INF("SB: USB type C, WWAN LTE");
- break;
-
- case FW_SUB_BOARD_3:
- sb = NISSA_SB_HDMI_A;
- LOG_INF("SB: HDMI, USB type A");
- break;
- }
- return sb;
-}
-
-__override void ocpc_get_pid_constants(int *kp, int *kp_div, int *ki,
- int *ki_div, int *kd, int *kd_div)
-{
- *kp = 1;
- *kp_div = 32;
- *ki = 0;
- *ki_div = 1;
- *kd = 0;
- *kd_div = 1;
-}
-
-#ifdef CONFIG_PLATFORM_EC_CHARGER_SM5803
-/*
- * Called by USB-PD code to determine whether a given input voltage is
- * acceptable.
- */
-__override int pd_is_valid_input_voltage(int mv)
-{
- int battery_voltage, rv;
-
- rv = battery_design_voltage(&battery_voltage);
- if (rv) {
- LOG_ERR("Unable to get battery design voltage: %d", rv);
- return true;
- }
-
- /*
- * SM5803 is extremely inefficient in buck-boost mode, when
- * VBUS ~= VSYS: very high temperatures on the chip and associated
- * inductor have been observed when sinking normal charge current in
- * buck-boost mode (but not in buck or boost mode) so we choose to
- * completely exclude some voltages that are likely to be problematic.
- *
- * Nissa devices use either 2S or 3S batteries, for which VBUS will
- * usually only be near VSYS with a 3S battery and 12V input (picked
- * from among common supported PD voltages)- 2S can get close to
- * 9V, but we expect charge current to be low when a 2S battery is
- * charged to that voltage (because it will be nearly full).
- *
- * We assume that any battery with a design voltage above 9V is 3S, and
- * that other problematic PD voltages (near to, but not exactly 12V)
- * will rarely occur.
- */
- if (battery_voltage > 9000 && mv == 12000) {
- return false;
- }
- return true;
-}
-#endif
-
-/* Trigger shutdown by enabling the Z-sleep circuit */
-__override void board_hibernate_late(void)
-{
- gpio_pin_set_dt(GPIO_DT_FROM_NODELABEL(gpio_en_slp_z), 1);
- /*
- * The system should hibernate, but there may be
- * a small delay, so return.
- */
-}
diff --git a/zephyr/program/nissa/src/led.c b/zephyr/program/nissa/src/led.c
deleted file mode 100644
index 2617d0092d..0000000000
--- a/zephyr/program/nissa/src/led.c
+++ /dev/null
@@ -1,52 +0,0 @@
-/* Copyright 2022 The ChromiumOS Authors
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- *
- * Battery LED control for nissa
- */
-#include "common.h"
-#include "ec_commands.h"
-#include "led_common.h"
-#include "led_onoff_states.h"
-#include "led_pwm.h"
-
-__override const int led_charge_lvl_1 = 5;
-__override const int led_charge_lvl_2 = 97;
-__override struct led_descriptor
- led_bat_state_table[LED_NUM_STATES][LED_NUM_PHASES] = {
- [STATE_CHARGING_LVL_1] = { { EC_LED_COLOR_RED,
- LED_INDEFINITE } },
- [STATE_CHARGING_LVL_2] = { { EC_LED_COLOR_AMBER,
- LED_INDEFINITE } },
- [STATE_CHARGING_FULL_CHARGE] = { { EC_LED_COLOR_GREEN,
- 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_RED, 1 * LED_ONE_SEC },
- { LED_OFF, 1 * LED_ONE_SEC } },
- [STATE_FACTORY_TEST] = { { EC_LED_COLOR_RED, 2 * LED_ONE_SEC },
- { EC_LED_COLOR_GREEN,
- 2 * LED_ONE_SEC } },
- };
-
-__override void led_set_color_battery(enum ec_led_colors color)
-{
- switch (color) {
- case EC_LED_COLOR_RED:
- set_pwm_led_color(EC_LED_ID_BATTERY_LED, EC_LED_COLOR_RED);
- break;
- case EC_LED_COLOR_GREEN:
- set_pwm_led_color(EC_LED_ID_BATTERY_LED, EC_LED_COLOR_GREEN);
- break;
- case EC_LED_COLOR_AMBER:
- set_pwm_led_color(EC_LED_ID_BATTERY_LED, EC_LED_COLOR_AMBER);
- break;
- default: /* LED_OFF and other unsupported colors */
- set_pwm_led_color(EC_LED_ID_BATTERY_LED, -1);
- break;
- }
-}
diff --git a/zephyr/program/nissa/src/sub_board.c b/zephyr/program/nissa/src/sub_board.c
deleted file mode 100644
index e8e9648ba6..0000000000
--- a/zephyr/program/nissa/src/sub_board.c
+++ /dev/null
@@ -1,288 +0,0 @@
-/* Copyright 2022 The ChromiumOS Authors
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* Nissa sub-board hardware configuration */
-
-#include "cros_board_info.h"
-#include "driver/tcpm/tcpci.h"
-#include "gpio/gpio_int.h"
-#include "hooks.h"
-#include "nissa_common.h"
-#include "nissa_hdmi.h"
-#include "task.h"
-#include "usb_charge.h"
-#include "usb_pd.h"
-#include "usbc/usb_muxes.h"
-
-#include <zephyr/drivers/gpio.h>
-#include <zephyr/drivers/pinctrl.h>
-#include <zephyr/init.h>
-#include <zephyr/kernel.h>
-#include <zephyr/sys/printk.h>
-
-#include <ap_power/ap_power.h>
-
-LOG_MODULE_DECLARE(nissa, CONFIG_NISSA_LOG_LEVEL);
-
-#if NISSA_BOARD_HAS_HDMI_SUPPORT
-static void hdmi_power_handler(struct ap_power_ev_callback *cb,
- struct ap_power_ev_data data)
-{
- /* Enable VCC on the HDMI port. */
- const struct gpio_dt_spec *s3_rail =
- GPIO_DT_FROM_ALIAS(gpio_hdmi_en_odl);
- /* Connect AP's DDC to sub-board (default is USB-C aux) */
- const struct gpio_dt_spec *ddc_select =
- GPIO_DT_FROM_NODELABEL(gpio_hdmi_sel);
-
- switch (data.event) {
- case AP_POWER_PRE_INIT:
- LOG_DBG("Connecting HDMI DDC to sub-board");
- gpio_pin_set_dt(ddc_select, 1);
- break;
- case AP_POWER_STARTUP:
- LOG_DBG("Enabling HDMI VCC");
- gpio_pin_set_dt(s3_rail, 1);
- break;
- case AP_POWER_SHUTDOWN:
- LOG_DBG("Disabling HDMI VCC");
- gpio_pin_set_dt(s3_rail, 0);
- break;
- case AP_POWER_HARD_OFF:
- LOG_DBG("Disconnecting HDMI sub-board DDC");
- gpio_pin_set_dt(ddc_select, 0);
- break;
- default:
- LOG_ERR("Unhandled HDMI power event %d", data.event);
- break;
- }
-}
-
-static void hdmi_hpd_interrupt(const struct device *device,
- struct gpio_callback *callback,
- gpio_port_pins_t pins)
-{
- int state = gpio_pin_get_dt(GPIO_DT_FROM_ALIAS(gpio_hpd_odl));
-
- gpio_pin_set_dt(GPIO_DT_FROM_NODELABEL(gpio_ec_soc_hdmi_hpd), state);
- LOG_DBG("HDMI HPD changed state to %d", state);
-}
-
-void nissa_configure_hdmi_rails(void)
-{
-#if DT_NODE_EXISTS(GPIO_DT_FROM_ALIAS(gpio_en_rails_odl))
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_en_rails_odl),
- GPIO_OUTPUT_INACTIVE | GPIO_OPEN_DRAIN |
- GPIO_PULL_UP | GPIO_ACTIVE_LOW);
-#endif
-}
-
-void nissa_configure_hdmi_vcc(void)
-{
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_hdmi_en_odl),
- GPIO_OUTPUT_INACTIVE | GPIO_OPEN_DRAIN |
- GPIO_ACTIVE_LOW);
-}
-
-__overridable void nissa_configure_hdmi_power_gpios(void)
-{
- nissa_configure_hdmi_rails();
-}
-
-#ifdef CONFIG_SOC_IT8XXX2
-/*
- * On it8xxx2, the below condition will break the EC to enter deep doze mode
- * (b:237717730):
- * Enhance i2c (GPE0/E7, GPH1/GPH2 or GPA4/GPA5) is enabled and its clock and
- * data pins aren't both at high level.
- *
- * Since HDMI+type A SKU doesn't use i2c4, disable it for better power number.
- */
-#define I2C4_NODE DT_NODELABEL(i2c4)
-#if DT_NODE_EXISTS(I2C4_NODE)
-PINCTRL_DT_DEFINE(I2C4_NODE);
-
-/* disable i2c4 alternate function */
-static void soc_it8xxx2_disable_i2c4_alt(void)
-{
- const struct pinctrl_dev_config *pcfg =
- PINCTRL_DT_DEV_CONFIG_GET(I2C4_NODE);
-
- pinctrl_apply_state(pcfg, PINCTRL_STATE_SLEEP);
-}
-#endif /* DT_NODE_EXISTS(I2C4_NODE) */
-#endif /* CONFIG_SOC_IT8XXX2 */
-#endif /* NISSA_BOARD_HAS_HDMI_SUPPORT */
-
-static void lte_power_handler(struct ap_power_ev_callback *cb,
- struct ap_power_ev_data data)
-{
- /* Enable rails for S5 */
- const struct gpio_dt_spec *s5_rail =
- GPIO_DT_FROM_ALIAS(gpio_en_sub_s5_rails);
- switch (data.event) {
- case AP_POWER_PRE_INIT:
- LOG_DBG("Enabling LTE sub-board power rails");
- gpio_pin_set_dt(s5_rail, 1);
- break;
- case AP_POWER_HARD_OFF:
- LOG_DBG("Disabling LTE sub-board power rails");
- gpio_pin_set_dt(s5_rail, 0);
- break;
- default:
- LOG_ERR("Unhandled LTE power event %d", data.event);
- break;
- }
-}
-
-/**
- * Configure GPIOs (and other pin functions) that vary with present sub-board.
- *
- * The functions of some pins vary according to which sub-board is present
- * (indicated by CBI fw_config); this function configures them according to the
- * needs of the present sub-board.
- */
-static void nereid_subboard_config(void)
-{
- enum nissa_sub_board_type sb = nissa_get_sb_type();
- static struct ap_power_ev_callback power_cb;
-
- /*
- * USB-A port: current limit output is configured by default and unused
- * if this port is not present. VBUS enable must be configured if
- * needed and is controlled by the usba-port-enable-pins driver.
- */
- if (sb == NISSA_SB_C_A || sb == NISSA_SB_HDMI_A ||
- sb == NISSA_SB_NONE) {
- /*
- * Configure VBUS enable, retaining current value.
- * SB_NONE indicates missing fw_config; it's safe to enable VBUS
- * control in this case since all that will happen is we turn
- * off power to LTE, and it's useful to allow USB-A to work in
- * such a configuration.
- */
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_en_usb_a1_vbus),
- GPIO_OUTPUT);
- } else {
- /* Turn off unused pins */
- gpio_pin_configure_dt(
- GPIO_DT_FROM_NODELABEL(gpio_sub_usb_a1_ilimit_sdp),
- GPIO_DISCONNECTED);
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_en_usb_a1_vbus),
- GPIO_DISCONNECTED);
- /* Disable second USB-A port enable GPIO */
- __ASSERT(USB_PORT_ENABLE_COUNT == 2,
- "USB A port count != 2 (%d)", USB_PORT_ENABLE_COUNT);
- usb_port_enable[1] = -1;
- }
- /*
- * USB-C port: the default configuration has I2C on the I2C pins,
- * but the interrupt line needs to be configured.
- */
-#if CONFIG_USB_PD_PORT_MAX_COUNT > 1
- if (sb == NISSA_SB_C_A || sb == NISSA_SB_C_LTE) {
- /* Configure interrupt input */
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_usb_c1_int_odl),
- GPIO_INPUT | GPIO_PULL_UP);
- } else {
- /* Port doesn't exist, doesn't need muxing */
- USB_MUX_ENABLE_ALTERNATIVE(usb_mux_chain_1_no_mux);
- }
-#endif
-
- switch (sb) {
-#if NISSA_BOARD_HAS_HDMI_SUPPORT
- case NISSA_SB_HDMI_A: {
- /*
- * HDMI: two outputs control power which must be configured to
- * non-default settings, and HPD must be forwarded to the AP
- * on another output pin.
- */
- const struct gpio_dt_spec *hpd_gpio =
- GPIO_DT_FROM_ALIAS(gpio_hpd_odl);
- static struct gpio_callback hdmi_hpd_cb;
- int rv, irq_key;
-
- nissa_configure_hdmi_power_gpios();
-
-#if CONFIG_SOC_IT8XXX2 && DT_NODE_EXISTS(I2C4_NODE)
- /* disable i2c4 alternate function for better power number */
- soc_it8xxx2_disable_i2c4_alt();
-#endif
-
- /*
- * Control HDMI power according to AP power state. Some events
- * won't do anything if the corresponding pin isn't configured,
- * but that's okay.
- */
- ap_power_ev_init_callback(
- &power_cb, hdmi_power_handler,
- AP_POWER_PRE_INIT | AP_POWER_HARD_OFF |
- AP_POWER_STARTUP | AP_POWER_SHUTDOWN);
- ap_power_ev_add_callback(&power_cb);
-
- /*
- * Configure HPD input from sub-board; it's inverted by a buffer
- * on the sub-board.
- */
- gpio_pin_configure_dt(hpd_gpio, GPIO_INPUT | GPIO_ACTIVE_LOW);
- /* Register interrupt handler for HPD changes */
- gpio_init_callback(&hdmi_hpd_cb, hdmi_hpd_interrupt,
- BIT(hpd_gpio->pin));
- gpio_add_callback(hpd_gpio->port, &hdmi_hpd_cb);
- rv = gpio_pin_interrupt_configure_dt(hpd_gpio,
- GPIO_INT_EDGE_BOTH);
- __ASSERT(rv == 0,
- "HPD interrupt configuration returned error %d", rv);
- /*
- * Run the HPD handler once to ensure output is in sync.
- * Lock interrupts to ensure that we don't cause desync if an
- * HPD interrupt comes in between the internal read of the input
- * and write to the output.
- */
- irq_key = irq_lock();
- hdmi_hpd_interrupt(hpd_gpio->port, &hdmi_hpd_cb,
- BIT(hpd_gpio->pin));
- irq_unlock(irq_key);
- break;
- }
-#endif
- case NISSA_SB_C_LTE:
- /*
- * LTE: Set up callbacks for enabling/disabling
- * sub-board power on S5 state.
- */
- gpio_pin_configure_dt(GPIO_DT_FROM_ALIAS(gpio_en_sub_s5_rails),
- GPIO_OUTPUT_INACTIVE);
- /* Control LTE power when CPU entering or
- * exiting S5 state.
- */
- ap_power_ev_init_callback(&power_cb, lte_power_handler,
- AP_POWER_HARD_OFF |
- AP_POWER_PRE_INIT);
- ap_power_ev_add_callback(&power_cb);
- break;
-
- default:
- break;
- }
-}
-DECLARE_HOOK(HOOK_INIT, nereid_subboard_config, HOOK_PRIO_POST_FIRST);
-
-/*
- * Enable interrupts
- */
-static void board_init(void)
-{
- /*
- * Enable USB-C interrupts.
- */
- gpio_enable_dt_interrupt(GPIO_INT_FROM_NODELABEL(int_usb_c0));
-#if CONFIG_USB_PD_PORT_MAX_COUNT > 1
- if (board_get_usb_pd_port_count() == 2)
- gpio_enable_dt_interrupt(GPIO_INT_FROM_NODELABEL(int_usb_c1));
-#endif
-}
-DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);