summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--board/ampton/battery.c39
-rw-r--r--board/ampton/board.c122
-rw-r--r--board/ampton/board.h65
-rw-r--r--board/ampton/build.mk15
-rw-r--r--board/ampton/ec.tasklist36
-rw-r--r--board/ampton/gpio.inc140
6 files changed, 417 insertions, 0 deletions
diff --git a/board/ampton/battery.c b/board/ampton/battery.c
new file mode 100644
index 0000000000..552649b6b7
--- /dev/null
+++ b/board/ampton/battery.c
@@ -0,0 +1,39 @@
+/* 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 ampton/apel 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/115502621): Ampton/Apel: need battery datasheets and specs */
+};
+BUILD_ASSERT(ARRAY_SIZE(board_battery_info) == BATTERY_TYPE_COUNT);
+
+const enum battery_type DEFAULT_BATTERY_TYPE = BATTERY_TYPE_COUNT;
diff --git a/board/ampton/board.c b/board/ampton/board.c
new file mode 100644
index 0000000000..0552be05a6
--- /dev/null
+++ b/board/ampton/board.c
@@ -0,0 +1,122 @@
+/* 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.
+ */
+
+/* Ampton/Apel board-specific configuration */
+
+#include "adc.h"
+#include "adc_chip.h"
+#include "button.h"
+#include "charge_state.h"
+#include "common.h"
+#include "driver/bc12/bq24392.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);
+}
+
+#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). SUB_EC_ADC */
+ [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_3v3_13k7_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);
+}
+
+/* TODO(b/115501243): Ampton/Apel: implement motion sensors in EC code */
+
+void board_overcurrent_event(int port)
+{
+ /* TODO(b/78344554): pass this signal upstream once hardware reworked */
+ cprints(CC_USBPD, "p%d: overcurrent!", port);
+}
diff --git a/board/ampton/board.h b/board/ampton/board.h
new file mode 100644
index 0000000000..a6132291a6
--- /dev/null
+++ b/board/ampton/board.h
@@ -0,0 +1,65 @@
+/* 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.
+ */
+
+/* Ampton/Apel 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"
+
+#define CONFIG_VOLUME_BUTTONS
+#define GPIO_VOLUME_UP_L GPIO_EC_VOLUP_BTN_ODL
+#define GPIO_VOLUME_DOWN_L GPIO_EC_VOLDN_BTN_ODL
+
+/* Optional features */
+#define CONFIG_SYSTEM_UNLOCKED /* Allow dangerous commands while in dev. */
+
+/* Sensors */
+/* TODO(b/115502220): Ampton/Apel: confirm thermistor parts */
+#define CONFIG_TEMP_SENSOR
+#define CONFIG_THERMISTOR
+#define CONFIG_STEINHART_HART_3V3_51K1_47K_4050B
+#define CONFIG_STEINHART_HART_3V3_13K7_47K_4050B
+
+#undef CONFIG_UART_TX_BUF_SIZE
+#define CONFIG_UART_TX_BUF_SIZE 4096
+
+/* Keyboard backlight is unimplemented in hardware */
+#undef CONFIG_PWM
+#undef CONFIG_PWM_KBLIGHT
+
+#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 */
+/* TODO(b/115502621): Ampton/Apel: need battery datasheets and specs */
+enum battery_type {
+ BATTERY_TYPE_COUNT,
+};
+
+#endif /* !__ASSEMBLER__ */
+
+#endif /* __CROS_EC_BOARD_H */
diff --git a/board/ampton/build.mk b/board/ampton/build.mk
new file mode 100644
index 0000000000..ad22f71678
--- /dev/null
+++ b/board/ampton/build.mk
@@ -0,0 +1,15 @@
+# -*- 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:=it8320dx
+BASEBOARD:=octopus
+
+board-y=board.o
+board-$(CONFIG_BATTERY_SMART)+=battery.o
diff --git a/board/ampton/ec.tasklist b/board/ampton/ec.tasklist
new file mode 100644
index 0000000000..75447efa1f
--- /dev/null
+++ b/board/ampton/ec.tasklist
@@ -0,0 +1,36 @@
+/* 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/ampton/gpio.inc b/board/ampton/gpio.inc
new file mode 100644
index 0000000000..6734174c54
--- /dev/null
+++ b/board/ampton/gpio.inc
@@ -0,0 +1,140 @@
+/* -*- 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, tablet_mode_isr)
+GPIO_INT(EC_VOLDN_BTN_ODL, PIN(D, 6), GPIO_INT_BOTH, button_interrupt)
+GPIO_INT(EC_VOLUP_BTN_ODL, PIN(D, 5), GPIO_INT_BOTH, button_interrupt)
+GPIO(LID_ACCEL_INT_L, PIN(J, 3), GPIO_INPUT | GPIO_SEL_1P8V)
+
+
+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(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. */
+GPIO(PCH_RTCRST, PIN(K, 7), GPIO_OUT_LOW) /* EC_PCH_RTCRST */
+
+/* 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(I, 0), 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_C1_PD_RST_ODL, PIN(L, 7), GPIO_ODR_HIGH) /* C1 PD Reset */
+
+GPIO(CCD_MODE_ODL, PIN(C, 4), GPIO_INPUT)
+
+/* LED */
+GPIO(BAT_LED_AMBER, PIN(A, 6), GPIO_OUT_LOW) /* LED_1_EC */
+GPIO(BAT_LED_WHITE, PIN(A, 3), GPIO_OUT_LOW) /* LED_2_EC */
+
+/* Camera */
+GPIO(WFCAM_VSYNC, PIN(D, 4), GPIO_INPUT)
+GPIO(CAM_SOC_EC_SYNC, PIN(E, 6), GPIO_INPUT)
+
+UNIMPLEMENTED(KB_BL_PWR_EN)
+
+/* NC pins, enable internal pull-down to avoid floating state. */
+GPIO(GPIOB2_NC, PIN(B, 2), 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(GPIOL6_NC, PIN(L, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOM6_NC, PIN(M, 6), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOD3_NC, PIN(D, 3), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIOI1_NC, PIN(I, 1), GPIO_INPUT | GPIO_PULL_DOWN)
+GPIO(GPIO12_NC, PIN(I, 2), GPIO_INPUT | GPIO_PULL_DOWN)
+
+/* 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: TEMP_SENSOR_AMB & TEMP_SENSOR_CHARGER */