summaryrefslogtreecommitdiff
path: root/board
diff options
context:
space:
mode:
authorDiana Z <dzigterman@chromium.org>2020-01-02 09:34:34 -0700
committerCommit Bot <commit-bot@chromium.org>2020-02-11 01:16:38 +0000
commite18f1e42127a856ea6591e13ee6c26fe5781848d (patch)
tree6fc5fe37cef132217c7b131d2afbafd1aab83a6e /board
parentef859d1c129174161c4d187c3d8b8c65b17fd9db (diff)
downloadchrome-ec-e18f1e42127a856ea6591e13ee6c26fe5781848d.tar.gz
Waddledee: Initial board file
This commit contains the initial code for waddledee, the ITE reference board for dedede. All of the GPIOs are defined, and any tasks that can be enabled to begin with are. Since the charger driver is still in progress, this commit undefs any charger related baseboard features, and they will be re-enabled once the driver is ready. BUG=b:146557556 BRANCH=None TEST=builds Change-Id: Ie5901304f92bf9040f1c883fb738c9f3bda0e95e Signed-off-by: Diana Z <dzigterman@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/2044359 Reviewed-by: Aseda Aboagye <aaboagye@chromium.org>
Diffstat (limited to 'board')
-rw-r--r--board/waddledee/battery.c39
-rw-r--r--board/waddledee/board.c202
-rw-r--r--board/waddledee/board.h112
-rw-r--r--board/waddledee/build.mk15
-rw-r--r--board/waddledee/ec.tasklist19
-rw-r--r--board/waddledee/gpio.inc138
6 files changed, 525 insertions, 0 deletions
diff --git a/board/waddledee/battery.c b/board/waddledee/battery.c
new file mode 100644
index 0000000000..6ed506dbcb
--- /dev/null
+++ b/board/waddledee/battery.c
@@ -0,0 +1,39 @@
+/* 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.
+ *
+ * Battery pack vendor provided charging profile
+ */
+
+#include "battery_fuel_gauge.h"
+#include "charge_state.h"
+#include "common.h"
+
+/*
+ * Battery info for all waddledee 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[] = {
+ /* TODO(b/146557556): get battery spec(s) */
+};
+BUILD_ASSERT(ARRAY_SIZE(board_battery_info) == BATTERY_TYPE_COUNT);
+
+const enum battery_type DEFAULT_BATTERY_TYPE = BATTERY_TYPE_COUNT;
diff --git a/board/waddledee/board.c b/board/waddledee/board.c
new file mode 100644
index 0000000000..61ca552a9c
--- /dev/null
+++ b/board/waddledee/board.c
@@ -0,0 +1,202 @@
+/* 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.
+ */
+
+/* Waddledee board-specific configuration */
+
+#include "button.h"
+#include "driver/accel_lis2dh.h"
+#include "driver/accelgyro_lsm6dsm.h"
+#include "driver/sync.h"
+#include "gpio.h"
+#include "intc.h"
+#include "keyboard_scan.h"
+#include "lid_switch.h"
+#include "power.h"
+#include "power_button.h"
+#include "pwm.h"
+#include "pwm_chip.h"
+#include "switch.h"
+#include "tablet_mode.h"
+#include "task.h"
+#include "temp_sensor.h"
+#include "thermistor.h"
+#include "uart.h"
+
+static void filler_interrupt_handler(enum gpio_signal s)
+{
+ /* TODO(b/146557556): placeholder for TCPC, charger, fault protector */
+}
+
+/* Must come after other header files and interrupt handler declarations */
+#include "gpio_list.h"
+
+int extpower_is_present(void)
+{
+ /* TODO(b/146651778): retrieve from chargers */
+ return 0;
+}
+
+void board_reset_pd_mcu(void)
+{
+ /*
+ * Nothing to do. TCPC C0 is internal, TCPC C1 reset pin is not
+ * connected to the EC.
+ */
+}
+
+/* PWM channels. Must be in the exactly same order as in enum pwm_channel. */
+const struct pwm_t pwm_channels[] = {
+ [PWM_CH_KBLIGHT] = {
+ .channel = 0,
+ .flags = PWM_CONFIG_DSLEEP,
+ .freq_hz = 10000,
+ },
+
+ [PWM_CH_LED_RED] = {
+ .channel = 1,
+ .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
+ .freq_hz = 2400,
+ },
+
+ [PWM_CH_LED_GREEN] = {
+ .channel = 2,
+ .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
+ .freq_hz = 2400,
+ },
+
+ [PWM_CH_LED_BLUE] = {
+ .channel = 3,
+ .flags = PWM_CONFIG_DSLEEP | PWM_CONFIG_ACTIVE_LOW,
+ .freq_hz = 2400,
+ }
+
+};
+BUILD_ASSERT(ARRAY_SIZE(pwm_channels) == PWM_CH_COUNT);
+
+/* Sensor Mutexes */
+static struct mutex g_lid_mutex;
+static struct mutex g_base_mutex;
+
+/* Sensor Data */
+static struct stprivate_data g_lis2dh_data;
+static struct lsm6dsm_data lsm6dsm_data = LSM6DSM_DATA;
+
+/* Drivers */
+struct motion_sensor_t motion_sensors[] = {
+ [LID_ACCEL] = {
+ .name = "Lid Accel",
+ .active_mask = SENSOR_ACTIVE_S0_S3,
+ .chip = MOTIONSENSE_CHIP_LIS2DE,
+ .type = MOTIONSENSE_TYPE_ACCEL,
+ .location = MOTIONSENSE_LOC_LID,
+ .drv = &lis2dh_drv,
+ .mutex = &g_lid_mutex,
+ .drv_data = &g_lis2dh_data,
+ .port = I2C_PORT_SENSOR,
+ .i2c_spi_addr_flags = LIS2DH_ADDR1_FLAGS,
+ .rot_standard_ref = NULL,
+ .default_range = 2, /* g */
+ /* We only use 2g because its resolution is only 8-bits */
+ .min_frequency = LIS2DH_ODR_MIN_VAL,
+ .max_frequency = LIS2DH_ODR_MAX_VAL,
+ .config = {
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ },
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ },
+ },
+ },
+ [BASE_ACCEL] = {
+ .name = "Base Accel",
+ .active_mask = SENSOR_ACTIVE_S0_S3,
+ .chip = MOTIONSENSE_CHIP_LSM6DSM,
+ .type = MOTIONSENSE_TYPE_ACCEL,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &lsm6dsm_drv,
+ .mutex = &g_base_mutex,
+ .drv_data = LSM6DSM_ST_DATA(lsm6dsm_data,
+ MOTIONSENSE_TYPE_ACCEL),
+ .int_signal = GPIO_BASE_SIXAXIS_INT_L,
+ .flags = MOTIONSENSE_FLAG_INT_SIGNAL,
+ .port = I2C_PORT_SENSOR,
+ .i2c_spi_addr_flags = LSM6DSM_ADDR0_FLAGS,
+ .rot_standard_ref = NULL,
+ .default_range = 4, /* g */
+ .min_frequency = LSM6DSM_ODR_MIN_VAL,
+ .max_frequency = LSM6DSM_ODR_MAX_VAL,
+ .config = {
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 13000 | ROUND_UP_FLAG,
+ .ec_rate = 100 * MSEC,
+ },
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 100 * MSEC,
+ },
+ },
+ },
+ [BASE_GYRO] = {
+ .name = "Base Gyro",
+ .active_mask = SENSOR_ACTIVE_S0_S3,
+ .chip = MOTIONSENSE_CHIP_LSM6DSM,
+ .type = MOTIONSENSE_TYPE_GYRO,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &lsm6dsm_drv,
+ .mutex = &g_base_mutex,
+ .drv_data = LSM6DSM_ST_DATA(lsm6dsm_data,
+ MOTIONSENSE_TYPE_GYRO),
+ .int_signal = GPIO_BASE_SIXAXIS_INT_L,
+ .flags = MOTIONSENSE_FLAG_INT_SIGNAL,
+ .port = I2C_PORT_SENSOR,
+ .i2c_spi_addr_flags = LSM6DSM_ADDR0_FLAGS,
+ .default_range = 1000 | ROUND_UP_FLAG, /* dps */
+ .rot_standard_ref = NULL,
+ .min_frequency = LSM6DSM_ODR_MIN_VAL,
+ .max_frequency = LSM6DSM_ODR_MAX_VAL,
+ },
+ [VSYNC] = {
+ .name = "Camera VSYNC",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_GPIO,
+ .type = MOTIONSENSE_TYPE_SYNC,
+ .location = MOTIONSENSE_LOC_CAMERA,
+ .drv = &sync_drv,
+ .default_range = 0,
+ .min_frequency = 0,
+ .max_frequency = 1,
+ },
+};
+
+const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
+
+#ifndef TEST_BUILD
+/* This callback disables keyboard when convertibles are fully open */
+void lid_angle_peripheral_enable(int enable)
+{
+ int chipset_in_s0 = chipset_in_state(CHIPSET_STATE_ON);
+
+ /*
+ * If the lid is in tablet position via other sensors,
+ * ignore the lid angle, which might be faulty then
+ * disable keyboard.
+ */
+ if (tablet_get_mode())
+ enable = 0;
+
+ if (enable) {
+ keyboard_scan_enable(1, KB_SCAN_DISABLE_LID_ANGLE);
+ } else {
+ /*
+ * Ensure that the chipset is off before disabling the keyboard.
+ * When the chipset is on, the EC keeps the keyboard enabled and
+ * the AP decides whether to ignore input devices or not.
+ */
+ if (!chipset_in_s0)
+ keyboard_scan_enable(0, KB_SCAN_DISABLE_LID_ANGLE);
+ }
+}
+#endif
diff --git a/board/waddledee/board.h b/board/waddledee/board.h
new file mode 100644
index 0000000000..448dd4f236
--- /dev/null
+++ b/board/waddledee/board.h
@@ -0,0 +1,112 @@
+/* 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.
+ */
+
+/* Waddledee board configuration */
+
+#ifndef __CROS_EC_BOARD_H
+#define __CROS_EC_BOARD_H
+
+/* Select Baseboard features */
+#define VARIANT_DEDEDE_EC_IT8320
+#include "baseboard.h"
+
+/* Undef battery, charger, LED, PD functions until charger is in */
+#undef CONFIG_BATTERY_CUT_OFF
+#undef CONFIG_BATTERY_PRESENT_GPIO
+#undef CONFIG_BATTERY_REVIVE_DISCONNECT
+#undef CONFIG_BATTERY_SMART
+#undef CONFIG_CHARGE_MANAGER
+#undef CONFIG_CHARGER
+#undef CONFIG_CHARGER_INPUT_CURRENT
+#undef CONFIG_LED_COMMON
+#undef CONFIG_LED_PWM
+#undef CONFIG_USB_MUX_PI3USB31532
+#undef CONFIG_USBC_SS_MUX
+#undef CONFIG_USBC_SS_MUX_DFP_ONLY
+#undef CONFIG_USBC_VCONN
+#undef CONFIG_USBC_VCONN_SWAP
+#undef CONFIG_USB_CHARGER
+#undef CONFIG_USB_PD_5V_EN_CUSTOM
+#undef CONFIG_TRICKLE_CHARGING
+#undef CONFIG_USB_PD_ALT_MODE
+#undef CONFIG_USB_PD_ALT_MODE_DFP
+#undef CONFIG_USB_PD_DISCHARGE_TCPC
+#undef CONFIG_USB_PD_DP_HPD_GPIO
+#undef CONFIG_USB_PD_DUAL_ROLE
+#undef CONFIG_USB_PD_DUAL_ROLE_AUTO_TOGGLE
+#undef CONFIG_USB_PD_LOGGING
+#undef CONFIG_USB_PD_PORT_MAX_COUNT
+#undef CONFIG_USB_PD_TCPM_MUX
+#undef CONFIG_USB_PD_TCPM_TCPCI
+#undef CONFIG_USB_PD_TRY_SRC
+#undef CONFIG_USB_PD_VBUS_DETECT_TCPC
+#undef CONFIG_USB_PD_VBUS_MEASURE_CHARGER
+#undef CONFIG_USB_PD_DECODE_SOP
+#undef CONFIG_USB_PID
+#undef CONFIG_USB_POWER_DELIVERY
+#undef CONFIG_USB_SM_FRAMEWORK
+#undef CONFIG_USB_TYPEC_DRP_ACC_TRYSRC
+
+/* System unlocked in early development */
+#define CONFIG_SYSTEM_UNLOCKED
+
+/* Sensors */
+#define CONFIG_ACCEL_LIS2DE /* Lid accel */
+#define CONFIG_ACCELGYRO_LSM6DSM /* Base accel */
+#define CONFIG_SYNC /* Camera VSYNC */
+/* Sensors without hardware FIFO are in forced mode */
+#define CONFIG_ACCEL_FORCE_MODE_MASK BIT(LID_ACCEL)
+
+#define CONFIG_ACCEL_INTERRUPTS
+/* Enable sensor fifo, must also define the _SIZE and _THRES */
+#define CONFIG_ACCEL_FIFO
+/* Power of 2 - Too large of a fifo causes too much timestamp jitter */
+#define CONFIG_ACCEL_FIFO_SIZE 256
+#define CONFIG_ACCEL_FIFO_THRES (CONFIG_ACCEL_FIFO_SIZE / 3)
+
+#define CONFIG_LID_ANGLE
+#define CONFIG_LID_ANGLE_UPDATE
+#define CONFIG_LID_ANGLE_SENSOR_BASE BASE_ACCEL
+#define CONFIG_LID_ANGLE_SENSOR_LID LID_ACCEL
+
+#define CONFIG_SYNC_INT_EVENT \
+ TASK_EVENT_MOTION_SENSOR_INTERRUPT(VSYNC)
+
+#define CONFIG_TABLET_MODE
+#define CONFIG_TABLET_MODE_SWITCH
+#define CONFIG_GMR_TABLET_MODE
+
+#ifndef __ASSEMBLER__
+
+#include "gpio_signal.h"
+#include "registers.h"
+
+enum pwm_channel {
+ PWM_CH_KBLIGHT,
+ PWM_CH_LED_RED,
+ PWM_CH_LED_GREEN,
+ PWM_CH_LED_BLUE,
+ PWM_CH_COUNT,
+};
+
+/* Motion sensors */
+enum sensor_id {
+ LID_ACCEL,
+ BASE_ACCEL,
+ BASE_GYRO,
+ VSYNC,
+ SENSOR_COUNT
+};
+
+
+/* List of possible batteries */
+enum battery_type {
+ /* TODO(b/146557556): get battery spec(s) */
+ BATTERY_TYPE_COUNT,
+};
+
+#endif /* !__ASSEMBLER__ */
+
+#endif /* __CROS_EC_BOARD_H */
diff --git a/board/waddledee/build.mk b/board/waddledee/build.mk
new file mode 100644
index 0000000000..382ec57971
--- /dev/null
+++ b/board/waddledee/build.mk
@@ -0,0 +1,15 @@
+# -*- makefile -*-
+# 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.
+#
+# Board specific files build
+#
+
+CHIP:=it83xx
+CHIP_FAMILY:=it8320
+CHIP_VARIANT:=it8320dx
+BASEBOARD:=dedede
+
+board-y=board.o
+board-$(CONFIG_BATTERY_SMART)+=battery.o
diff --git a/board/waddledee/ec.tasklist b/board/waddledee/ec.tasklist
new file mode 100644
index 0000000000..bf1b5b19c3
--- /dev/null
+++ b/board/waddledee/ec.tasklist
@@ -0,0 +1,19 @@
+/* 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.
+ */
+
+/*
+ * See CONFIG_TASK_LIST in config.h for details.
+ */
+
+#define CONFIG_TASK_LIST \
+ TASK_ALWAYS(HOOKS, hook_task, NULL, VENTI_TASK_STACK_SIZE) \
+ TASK_ALWAYS(MOTIONSENSE, motion_sense_task, NULL, VENTI_TASK_STACK_SIZE) \
+ TASK_NOTEST(CHIPSET, chipset_task, NULL, VENTI_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, VENTI_TASK_STACK_SIZE) \
+ TASK_ALWAYS(CONSOLE, console_task, NULL, VENTI_TASK_STACK_SIZE) \
+ TASK_ALWAYS(POWERBTN, power_button_task, NULL, VENTI_TASK_STACK_SIZE) \
+ TASK_NOTEST(KEYSCAN, keyboard_scan_task, NULL, TASK_STACK_SIZE)
diff --git a/board/waddledee/gpio.inc b/board/waddledee/gpio.inc
new file mode 100644
index 0000000000..24c3fae63b
--- /dev/null
+++ b/board/waddledee/gpio.inc
@@ -0,0 +1,138 @@
+/* -*- mode:c -*-
+ *
+ * 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.
+ */
+
+/* Declare symbolic names for all the GPIOs that we care about.
+ * Note: Those with interrupt handlers must be declared first. */
+
+/* Power State interrupts */
+GPIO_INT(SLP_S4_L, PIN(I, 5), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(SLP_S3_L, PIN(H, 3), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(SLP_S0_L, PIN(E, 4), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(SLP_SUS_L, PIN(G, 2), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(VCCIN_AUX_VID0, PIN(D, 0), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(RSMRST_PWRGD_L, PIN(E, 1), GPIO_INT_BOTH | GPIO_PULL_UP, power_signal_interrupt)
+GPIO_INT(CPU_C10_GATE_L, PIN(G, 1), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(PG_DRAM_OD, PIN(D, 3), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(PG_PP1050_ST_OD, PIN(L, 1), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(VCCIN_AUX_VID1, PIN(K, 1), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(PG_VCCIO_EXT_OD, PIN(D, 7), GPIO_INT_BOTH, power_signal_interrupt)
+GPIO_INT(ESPI_RESET_L, PIN(D, 2), GPIO_INT_FALLING | GPIO_SEL_1P8V, espi_reset_pin_asserted_interrupt)
+
+GPIO_INT(H1_EC_PWR_BTN_ODL, PIN(E, 2), GPIO_INT_BOTH | GPIO_PULL_UP, power_button_interrupt)
+#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_DBG_TX_EC_RX */
+#endif
+
+/* USB-C interrupts */
+GPIO_INT(USB_C0_INT_ODL, PIN(K, 0), GPIO_INT_FALLING, filler_interrupt_handler) /* BC12 and charger */
+GPIO_INT(USB_C1_INT_ODL, PIN(B, 5), GPIO_INT_FALLING, filler_interrupt_handler) /* TCPC, charger, BC12 */
+GPIO_INT(USB_C0_CCSBU_OVP_ODL, PIN(K, 6), GPIO_INT_FALLING, filler_interrupt_handler) /* Fault protection */
+
+/* Other interrupts */
+GPIO_INT(LID_OPEN, PIN(F, 3), GPIO_INT_BOTH, lid_interrupt)
+GPIO_INT(LID_360_L, PIN(A, 7), GPIO_INT_BOTH, gmr_tablet_switch_isr)
+GPIO_INT(VOLDN_BTN_ODL, PIN(I, 6), GPIO_INT_BOTH, button_interrupt)
+GPIO_INT(VOLUP_BTN_ODL, PIN(I, 7), GPIO_INT_BOTH, button_interrupt)
+GPIO_INT(BASE_SIXAXIS_INT_L, PIN(J, 0), GPIO_INT_FALLING | GPIO_SEL_1P8V, lsm6dsm_interrupt)
+GPIO_INT(CAM_EC_VSYNC, PIN(C, 7), GPIO_INT_RISING, sync_interrupt)
+GPIO_INT(EC_WP_OD, PIN(A, 6), GPIO_INT_BOTH, switch_interrupt)
+
+/* Power sequence GPIOs */
+GPIO(EC_AP_RTCRST, PIN(K, 2), GPIO_OUT_LOW)
+GPIO(EC_AP_PWR_BTN_ODL, PIN(B, 6), GPIO_ODR_HIGH)
+GPIO(EC_AP_DPWROK, PIN(L, 7), GPIO_OUT_LOW)
+GPIO(EC_AP_RSMRST_L, PIN(H, 0), GPIO_OUT_LOW)
+GPIO(EC_AP_WAKE_ODL, PIN(D, 5), GPIO_ODR_HIGH)
+GPIO(SYS_RST_ODL, PIN(D, 1), GPIO_ODR_HIGH)
+GPIO(EC_AP_SYS_PWROK, PIN(F, 2), GPIO_OUT_LOW)
+GPIO(PG_PP5000_U_OD, PIN(E, 3), GPIO_INPUT)
+GPIO(EN_PP3300_PEN, PIN(E, 6), GPIO_OUT_LOW)
+GPIO(EN_PP3300_A, PIN(C, 5), GPIO_OUT_LOW)
+GPIO(EC_AP_PCH_PWROK_OD, PIN(D, 6), GPIO_ODR_LOW)
+GPIO(EN_PP5000_U, PIN(K, 5), GPIO_OUT_LOW)
+GPIO(EN_VCCST, PIN(D, 4), GPIO_OUT_LOW)
+GPIO(EN_VCCIO_EXT, PIN(B, 2), GPIO_OUT_LOW)
+GPIO(EC_PROCHOT_ODL, PIN(I, 1), GPIO_ODR_HIGH | GPIO_SEL_1P8V)
+GPIO(EC_AP_VCCST_PWRGD_OD, PIN(E, 5), GPIO_ODR_LOW)
+GPIO(ALL_SYS_PWRGD, PIN(B, 7), GPIO_OUT_LOW)
+GPIO(EN_SLP_Z, PIN(K, 3), GPIO_OUT_LOW)
+
+/* Required for icelake chipset code, but implemented through other means for dedede */
+UNIMPLEMENTED(PG_EC_DSW_PWROK)
+UNIMPLEMENTED(PG_EC_ALL_SYS_PWRGD)
+
+/* I2C pins - Alternate function below configures I2C module on these pins */
+GPIO(EC_I2C_EEPROM_SCL, PIN(B, 3), GPIO_INPUT)
+GPIO(EC_I2C_EEPROM_SDA, PIN(B, 4), GPIO_INPUT)
+GPIO(EC_I2C_BATTERY_SCL, PIN(C, 1), GPIO_INPUT)
+GPIO(EC_I2C_BATTERY_SDA, PIN(C, 2), GPIO_INPUT)
+GPIO(EC_I2C_SENSOR_SCL, PIN(F, 6), GPIO_INPUT | GPIO_SEL_1P8V)
+GPIO(EC_I2C_SENSOR_SDA, PIN(F, 7), GPIO_INPUT | GPIO_SEL_1P8V)
+GPIO(EC_I2C_SUB_USB_C1_SCL, PIN(E, 0), GPIO_INPUT)
+GPIO(EC_I2C_SUB_USB_C1_SDA, PIN(E, 7), GPIO_INPUT)
+GPIO(EC_I2C_USB_C0_SCL, PIN(A, 4), GPIO_INPUT)
+GPIO(EC_I2C_USB_C0_SDA, PIN(A, 5), GPIO_INPUT)
+
+/* USB pins */
+GPIO(EN_USB_C0_CC1_VCONN, PIN(H, 4), GPIO_OUT_LOW)
+GPIO(EN_USB_C0_CC2_VCONN, PIN(H, 6), GPIO_OUT_LOW)
+GPIO(EC_AP_USB_C0_HPD, PIN(L, 4), GPIO_OUT_LOW)
+GPIO(EC_AP_USB_C1_HDMI_HPD, PIN(K, 7), GPIO_OUT_LOW)
+GPIO(USB_C0_FRS, PIN(C, 4), GPIO_OUT_LOW)
+GPIO(HDMI_SEL_L, PIN(C, 6), GPIO_OUT_HIGH)
+
+/* MKBP event synchronization */
+GPIO(EC_AP_MKBP_INT_L, PIN(L, 5), GPIO_OUT_HIGH)
+
+/* Misc pins which will run to the I/O board */
+GPIO(EC_SUB_IO_1_1, PIN(L, 3), GPIO_INPUT)
+GPIO(EC_SUB_IO_1_2, PIN(F, 0), GPIO_INPUT)
+GPIO(EC_SUB_IO_2_1, PIN(F, 1), GPIO_INPUT)
+GPIO(EC_SUB_IO_2_2, PIN(L, 2), GPIO_INPUT)
+
+/* Misc */
+GPIO(EN_BL_OD, PIN(K, 4), GPIO_OUT_LOW)
+GPIO(EC_ENTERING_RW, PIN(G, 0), GPIO_OUT_LOW)
+GPIO(CCD_MODE_ODL, PIN(H, 5), GPIO_INPUT)
+GPIO(EC_BATTERY_PRES_ODL, PIN(I, 4), GPIO_INPUT)
+GPIO(PEN_DET_ODL, PIN(J, 1), GPIO_INPUT | GPIO_PULL_UP)
+GPIO(EN_KB_BL, PIN(J, 3), GPIO_OUT_LOW) /* Currently unused */
+
+/* NC pins, enable internal pull-down to avoid floating state. */
+GPIO(GPIOC0_NC, PIN(C, 0), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOC3_NC, PIN(C, 3), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOG3_NC, PIN(G, 3), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOG4_NC, PIN(G, 4), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOG5_NC, PIN(G, 5), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOG6_NC, PIN(G, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOG7_NC, PIN(G, 7), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOJ4_NC, PIN(J, 4), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOJ5_NC, PIN(J, 5), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOJ6_NC, PIN(J, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOL6_NC, PIN(L, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOM6_NC, PIN(M, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+
+/* Alternate functions GPIO definitions */
+/* UART */
+ALTERNATE(PIN_MASK(B, BIT(0) | BIT(1)), 0, MODULE_UART, 0) /* UART for debug */
+
+/* I2C */
+ALTERNATE(PIN_MASK(B, BIT(3) | BIT(4)), 0, MODULE_I2C, 0) /* I2C0 */
+ALTERNATE(PIN_MASK(C, BIT(1) | BIT(2)), 0, MODULE_I2C, 0) /* I2C1 */
+ALTERNATE(PIN_MASK(F, BIT(6) | BIT(7)), 0, MODULE_I2C, GPIO_SEL_1P8V) /* I2C2 - 1.8V */
+ALTERNATE(PIN_MASK(E, BIT(0) | BIT(7)), 0, MODULE_I2C, 0) /* I2C4 */
+ALTERNATE(PIN_MASK(A, BIT(4) | BIT(5)), 0, MODULE_I2C, 0) /* I2C5 */
+
+/* ADC */
+ALTERNATE(PIN_MASK(L, BIT(0)), 0, MODULE_ADC, 0) /* ADC13: EC_SUB_ANALOG */
+ALTERNATE(PIN_MASK(I, BIT(0) | BIT(2) | BIT(3)), 0, MODULE_ADC, 0) /* ADC0: EC_VSNS_PP3300_A, ADC2: TEMP_SENSOR_1, ADC3: TEMP_SENSOR_2 */
+
+/* TODO(b/149094279): DAC module for PSYS */
+
+/* PWM */
+ALTERNATE(PIN_MASK(A, BIT(0) | BIT(1) | BIT(2) | BIT(3)), 0, MODULE_PWM, 0) /* KB_BL_PWM, LED_[R,G,B]_ODL */