summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDino Li <Dino.Li@ite.com.tw>2017-05-16 11:11:25 +0800
committerchrome-bot <chrome-bot@chromium.org>2017-05-18 02:26:10 -0700
commit59c04665c6f48366f06543883baf7ff7c5251f0e (patch)
treea10650f0a053121f67691cd6908ed5667ddac655
parent9774484d298c5d91795637a953624d7579d1ac85 (diff)
downloadchrome-ec-59c04665c6f48366f06543883baf7ff7c5251f0e.tar.gz
reef_it8320: initial reef_it8320 board
This change is based on reef's board code and modified for it8320. BUG=none BRANCH=none TEST=Run the entire faft_ec suite and passed. Change-Id: I8977d7431eb0a97ceb4ee1dfd11a2c4433687db0 Signed-off-by: Dino Li <Dino.Li@ite.com.tw> Reviewed-on: https://chromium-review.googlesource.com/487792 Reviewed-by: Randall Spangler <rspangler@chromium.org> Reviewed-by: Daisuke Nojiri <dnojiri@chromium.org>
-rw-r--r--Makefile.rules2
-rw-r--r--board/reef_it8320/battery.c2
-rw-r--r--board/reef_it8320/board.c795
-rw-r--r--board/reef_it8320/board.h209
-rw-r--r--board/reef_it8320/build.mk7
-rw-r--r--board/reef_it8320/ec.tasklist5
-rw-r--r--board/reef_it8320/gpio.inc232
-rw-r--r--board/reef_it8320/led.c2
-rw-r--r--board/reef_it8320/usb_pd_policy.c15
-rw-r--r--chip/it83xx/config_chip.h3
-rwxr-xr-xutil/flash_ec1
11 files changed, 367 insertions, 906 deletions
diff --git a/Makefile.rules b/Makefile.rules
index d8ec80736b..e1606496c7 100644
--- a/Makefile.rules
+++ b/Makefile.rules
@@ -17,7 +17,7 @@ build-srcs := $(foreach u,$(build-util-bin),$(sort $($(u)-objs:%.o=util/%.c) uti
host-srcs := $(foreach u,$(host-util-bin),$(sort $($(u)-objs:%.o=util/%.c) util/$(u).c))
# Don't do a build test on the following boards:
-skip_boards = OWNERS host it83xx_evb
+skip_boards = OWNERS host it83xx_evb reef_it8320
boards := $(filter-out $(skip_boards),$(notdir $(wildcard board/* private*/board/*)))
# Create output directories if necessary
diff --git a/board/reef_it8320/battery.c b/board/reef_it8320/battery.c
index ff916822ec..1745bf736b 100644
--- a/board/reef_it8320/battery.c
+++ b/board/reef_it8320/battery.c
@@ -1,4 +1,4 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*
diff --git a/board/reef_it8320/board.c b/board/reef_it8320/board.c
index a203938b24..06259c0c6a 100644
--- a/board/reef_it8320/board.c
+++ b/board/reef_it8320/board.c
@@ -1,9 +1,9 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*/
-/* Reef board-specific configuration */
+/* reef_it8320 board-specific configuration */
#include "adc.h"
#include "adc_chip.h"
@@ -14,21 +14,16 @@
#include "charger.h"
#include "chipset.h"
#include "console.h"
-#include "driver/als_opt3001.h"
-#include "driver/accel_kionix.h"
-#include "driver/accel_kx022.h"
-#include "driver/accelgyro_bmi160.h"
-#include "driver/baro_bmp280.h"
#include "driver/charger/bd9995x.h"
-#include "driver/tcpm/anx74xx.h"
-#include "driver/tcpm/ps8751.h"
-#include "driver/tcpm/tcpci.h"
+#include "driver/tcpm/it83xx_pd.h"
#include "driver/tcpm/tcpm.h"
#include "extpower.h"
+#include "ec2i_chip.h"
#include "gpio.h"
#include "hooks.h"
#include "host_command.h"
#include "i2c.h"
+#include "intc.h"
#include "keyboard_scan.h"
#include "lid_angle.h"
#include "lid_switch.h"
@@ -61,66 +56,6 @@
#define IN_PGOOD_PP3300 POWER_SIGNAL_MASK(X86_PGOOD_PP3300)
#define IN_PGOOD_PP5000 POWER_SIGNAL_MASK(X86_PGOOD_PP5000)
-#define USB_PD_PORT_ANX74XX 0
-#define USB_PD_PORT_PS8751 1
-
-static void tcpc_alert_event(enum gpio_signal signal)
-{
- if ((signal == GPIO_USB_C0_PD_INT_ODL) &&
- !gpio_get_level(GPIO_USB_C0_PD_RST_L))
- return;
-
- if ((signal == GPIO_USB_C1_PD_INT_ODL) &&
- !gpio_get_level(GPIO_USB_C1_PD_RST_ODL))
- return;
-
-#ifdef HAS_TASK_PDCMD
- /* Exchange status with TCPCs */
- host_command_pd_send_status(PD_CHARGE_NO_CHANGE);
-#endif
-}
-
-#ifdef CONFIG_USB_PD_TCPC_LOW_POWER
-static void anx74xx_cable_det_handler(void)
-{
- int cable_det = gpio_get_level(GPIO_USB_C0_CABLE_DET);
- int reset_n = gpio_get_level(GPIO_USB_C0_PD_RST_L);
-
- /*
- * A cable_det low->high transition was detected. If following the
- * debounce time, cable_det is high, and reset_n is low, then ANX3429 is
- * currently in standby mode and needs to be woken up. Set the
- * TCPC_RESET event which will bring the ANX3429 out of standby
- * mode. Setting this event is gated on reset_n being low because the
- * ANX3429 will always set cable_det when transitioning to normal mode
- * and if in normal mode, then there is no need to trigger a tcpc reset.
- */
- if (cable_det && !reset_n)
- task_set_event(TASK_ID_PD_C0, PD_EVENT_TCPC_RESET, 0);
-}
-DECLARE_DEFERRED(anx74xx_cable_det_handler);
-
-void anx74xx_cable_det_interrupt(enum gpio_signal signal)
-{
- /* debounce for 2 msec */
- hook_call_deferred(&anx74xx_cable_det_handler_data, (2 * MSEC));
-}
-#endif
-
-/*
- * enable_input_devices() is called by the tablet_mode ISR, but changes the
- * state of GPIOs, so its definition must reside after including gpio_list.
- * Use DECLARE_DEFERRED to generate enable_input_devices_data.
- */
-static void enable_input_devices(void);
-DECLARE_DEFERRED(enable_input_devices);
-
-#define LID_DEBOUNCE_US (30 * MSEC) /* Debounce time for lid switch */
-void tablet_mode_interrupt(enum gpio_signal signal)
-{
- hook_call_deferred(&enable_input_devices_data, LID_DEBOUNCE_US);
-}
-
#include "gpio_list.h"
/* power signal list. Must match order of enum power_signal. */
@@ -138,135 +73,74 @@ BUILD_ASSERT(ARRAY_SIZE(power_signal_list) == POWER_SIGNAL_COUNT);
/* ADC channels */
const struct adc_t adc_channels[] = {
- /* Vfs = Vref = 2.816V, 10-bit unsigned reading */
- [ADC_TEMP_SENSOR_CHARGER] = {
- "CHARGER", NPCX_ADC_CH0, ADC_MAX_VOLT, ADC_READ_MAX + 1, 0
- },
- [ADC_TEMP_SENSOR_AMB] = {
- "AMBIENT", NPCX_ADC_CH1, ADC_MAX_VOLT, ADC_READ_MAX + 1, 0
- },
- [ADC_BOARD_ID] = {
- "BRD_ID", NPCX_ADC_CH2, ADC_MAX_VOLT, ADC_READ_MAX + 1, 0
- },
+ /* Convert to mV (3000mV/1024). */
+ {"CHARGER", 3000, 1024, 0, 1}, /* GPI1 */
+ {"AMBIENT", 3000, 1024, 0, 2}, /* GPI2 */
+ {"BRD_ID", 3000, 1024, 0, 3}, /* GPI3 */
};
BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
-/* PWM channels. Must be in the exactly same order as in enum pwm_channel. */
-const struct pwm_t pwm_channels[] = {
- [PWM_CH_LED_GREEN] = { 2, PWM_CONFIG_DSLEEP, 100 },
- [PWM_CH_LED_RED] = { 3, PWM_CONFIG_DSLEEP, 100 },
-};
-BUILD_ASSERT(ARRAY_SIZE(pwm_channels) == PWM_CH_COUNT);
-
const struct i2c_port_t i2c_ports[] = {
- {"tcpc0", NPCX_I2C_PORT0_0, 400,
- GPIO_EC_I2C_USB_C0_PD_SCL, GPIO_EC_I2C_USB_C0_PD_SDA},
- {"tcpc1", NPCX_I2C_PORT0_1, 400,
- GPIO_EC_I2C_USB_C1_PD_SCL, GPIO_EC_I2C_USB_C1_PD_SDA},
- {"accelgyro", I2C_PORT_GYRO, 400,
- GPIO_EC_I2C_GYRO_SCL, GPIO_EC_I2C_GYRO_SDA},
- {"sensors", NPCX_I2C_PORT2, 400,
- GPIO_EC_I2C_SENSOR_SCL, GPIO_EC_I2C_SENSOR_SDA},
- {"batt", NPCX_I2C_PORT3, 100,
- GPIO_EC_I2C_POWER_SCL, GPIO_EC_I2C_POWER_SDA},
+ {"mux", IT83XX_I2C_CH_C, 400,
+ GPIO_EC_I2C_C_SCL, GPIO_EC_I2C_C_SDA},
+ {"batt", IT83XX_I2C_CH_E, 100,
+ GPIO_EC_I2C_E_SCL, GPIO_EC_I2C_E_SDA},
};
const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
-#ifdef CONFIG_CMD_I2C_STRESS_TEST
-struct i2c_stress_test i2c_stress_tests[] = {
-/* NPCX_I2C_PORT0_0 */
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_TCPC
- {
- .port = NPCX_I2C_PORT0_0,
- .addr = 0x50,
- .i2c_test = &anx74xx_i2c_stress_test_dev,
- },
-#endif
-
-/* NPCX_I2C_PORT0_1 */
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_TCPC
- {
- .port = NPCX_I2C_PORT0_1,
- .addr = 0x16,
- .i2c_test = &ps8751_i2c_stress_test_dev,
- },
-#endif
-
-/* NPCX_I2C_PORT1 */
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_ACCEL
- {
- .port = I2C_PORT_GYRO,
- .addr = BMI160_ADDR0,
- .i2c_test = &bmi160_i2c_stress_test_dev,
- },
-#endif
-
-/* NPCX_I2C_PORT2 */
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_ACCEL
- {
- .port = I2C_PORT_BARO,
- .addr = BMP280_I2C_ADDRESS1,
- .i2c_test = &bmp280_i2c_stress_test_dev,
- },
- {
- .port = I2C_PORT_LID_ACCEL,
- .addr = KX022_ADDR1,
- .i2c_test = &kionix_i2c_stress_test_dev,
- },
-#endif
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_ALS
- {
- .port = I2C_PORT_ALS,
- .addr = OPT3001_I2C_ADDR1,
- .i2c_test = &opt3001_i2c_stress_test_dev,
- },
-#endif
-
-/* NPCX_I2C_PORT3 */
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_BATTERY
- {
- .i2c_test = &battery_i2c_stress_test_dev,
- },
-#endif
-#ifdef CONFIG_CMD_I2C_STRESS_TEST_CHARGER
- {
- .i2c_test = &bd9995x_i2c_stress_test_dev,
- },
-#endif
-};
-const int i2c_test_dev_used = ARRAY_SIZE(i2c_stress_tests);
-#endif /* CONFIG_CMD_I2C_STRESS_TEST */
-
const struct tcpc_config_t tcpc_config[CONFIG_USB_PD_PORT_COUNT] = {
- [USB_PD_PORT_ANX74XX] = {
- .i2c_host_port = NPCX_I2C_PORT0_0,
- .i2c_slave_addr = 0x50,
- .drv = &anx74xx_tcpm_drv,
- .pol = TCPC_ALERT_ACTIVE_LOW,
- },
- [USB_PD_PORT_PS8751] = {
- .i2c_host_port = NPCX_I2C_PORT0_1,
- .i2c_slave_addr = 0x16,
- .drv = &tcpci_tcpm_drv,
- .pol = TCPC_ALERT_ACTIVE_LOW,
- },
+ {-1, -1, &it83xx_tcpm_drv, 0},
+ {-1, -1, &it83xx_tcpm_drv, 0},
};
-uint16_t tcpc_get_alert_status(void)
+void board_pd_vconn_ctrl(int port, int cc_pin, int enabled)
{
- uint16_t status = 0;
+ int cc1_enabled = 0, cc2_enabled = 0;
- if (!gpio_get_level(GPIO_USB_C0_PD_INT_ODL)) {
- if (gpio_get_level(GPIO_USB_C0_PD_RST_L))
- status |= PD_STATUS_TCPC_ALERT_0;
+ if (cc_pin)
+ cc2_enabled = enabled;
+ else
+ cc1_enabled = enabled;
+
+ if (port) {
+ gpio_set_level(GPIO_USB_C1_CC2_VCONN_EN, cc2_enabled);
+ gpio_set_level(GPIO_USB_C1_CC1_VCONN_EN, cc1_enabled);
+ } else {
+ gpio_set_level(GPIO_USB_C0_CC2_VCONN_EN, !cc2_enabled);
+ gpio_set_level(GPIO_USB_C0_CC1_VCONN_EN, !cc1_enabled);
}
+}
- if (!gpio_get_level(GPIO_USB_C1_PD_INT_ODL)) {
- if (gpio_get_level(GPIO_USB_C1_PD_RST_ODL))
- status |= PD_STATUS_TCPC_ALERT_1;
- }
+/*
+ * PD host event status for host command
+ * Note: this variable must be aligned on 4-byte boundary because we pass the
+ * address to atomic_ functions which use assembly to access them.
+ */
+static uint32_t pd_host_event_status __aligned(4);
+
+static int hc_pd_host_event_status(struct host_cmd_handler_args *args)
+{
+ struct ec_response_host_event_status *r = args->response;
+
+ /* Read and clear the host event status to return to AP */
+ r->status = atomic_read_clear(&pd_host_event_status);
- return status;
+ args->response_size = sizeof(*r);
+ return EC_RES_SUCCESS;
+}
+DECLARE_HOST_COMMAND(EC_CMD_PD_HOST_EVENT_STATUS, hc_pd_host_event_status,
+ EC_VER_MASK(0));
+
+/* Send host event up to AP */
+void pd_send_host_event(int mask)
+{
+ /* mask must be set */
+ if (!mask)
+ return;
+
+ atomic_or(&pd_host_event_status, mask);
+ /* interrupt the AP */
+ host_set_single_event(EC_HOST_EVENT_PD_MCU);
}
const enum gpio_signal hibernate_wake_pins[] = {
@@ -277,118 +151,38 @@ const enum gpio_signal hibernate_wake_pins[] = {
const int hibernate_wake_pins_used = ARRAY_SIZE(hibernate_wake_pins);
-static int ps8751_tune_mux(const struct usb_mux *mux)
+static void it83xx_tcpc_update_hpd_status(int port, int hpd_lvl, int hpd_irq)
{
- /* 0x98 sets lower EQ of DP port (4.5db) */
- i2c_write8(NPCX_I2C_PORT0_1, 0x16, PS8751_REG_MUX_DP_EQ_CONFIGURATION,
- 0x98);
- return EC_SUCCESS;
+ enum gpio_signal gpio =
+ port ? GPIO_USB_C1_HPD_1P8_ODL : GPIO_USB_C0_HPD_1P8_ODL;
+
+ hpd_lvl = !hpd_lvl;
+
+ gpio_set_level(gpio, hpd_lvl);
+ if (hpd_irq) {
+ gpio_set_level(gpio, 1);
+ msleep(1);
+ gpio_set_level(gpio, hpd_lvl);
+ }
}
struct usb_mux usb_muxes[CONFIG_USB_PD_PORT_COUNT] = {
{
- .port_addr = USB_PD_PORT_ANX74XX, /* don't care / unused */
- .driver = &anx74xx_tcpm_usb_mux_driver,
- .hpd_update = &anx74xx_tcpc_update_hpd_status,
+ .port_addr = 0xa8,
+ .driver = &pi3usb30532_usb_mux_driver,
+ .hpd_update = &it83xx_tcpc_update_hpd_status,
},
{
- .port_addr = USB_PD_PORT_PS8751,
- .driver = &tcpci_tcpm_usb_mux_driver,
- .hpd_update = &ps8751_tcpc_update_hpd_status,
- .board_init = &ps8751_tune_mux,
- }
+ .port_addr = 0x20,
+ .driver = &ps8740_usb_mux_driver,
+ .hpd_update = &it83xx_tcpc_update_hpd_status,
+ },
};
const int usb_port_enable[CONFIG_USB_PORT_POWER_SMART_PORT_COUNT] = {
GPIO_USB1_ENABLE,
};
-/* called from anx74xx_set_power_mode() */
-void board_set_tcpc_power_mode(int port, int mode)
-{
- if (port != USB_PD_PORT_ANX74XX)
- return;
-
- switch (mode) {
- case ANX74XX_NORMAL_MODE:
- gpio_set_level(GPIO_EN_USB_TCPC_PWR, 1);
- msleep(10);
- gpio_set_level(GPIO_USB_C0_PD_RST_L, 1);
- break;
- case ANX74XX_STANDBY_MODE:
- gpio_set_level(GPIO_USB_C0_PD_RST_L, 0);
- msleep(1);
- gpio_set_level(GPIO_EN_USB_TCPC_PWR, 0);
- break;
- default:
- break;
- }
-}
-
-/**
- * Reset PD MCU -- currently only called from handle_pending_reboot() in
- * common/power.c just before hard resetting the system. This logic is likely
- * not needed as the PP3300_A rail should be dropped on EC reset.
- */
-void board_reset_pd_mcu(void)
-{
- /* Assert reset to TCPC1 */
- gpio_set_level(GPIO_USB_C1_PD_RST_ODL, 0);
-
- /* Assert reset to TCPC0 */
- board_set_tcpc_power_mode(0, 0);
-
- /* Deassert reset to TCPC1 */
- gpio_set_level(GPIO_USB_C1_PD_RST_ODL, 1);
-
- /* TCPC0 requires 10ms reset/power down assertion */
- msleep(10);
-
- /* Deassert reset to TCPC0 */
- board_set_tcpc_power_mode(0, 1);
-}
-
-void board_tcpc_init(void)
-{
- int port, reg;
-
- /* Only reset TCPC if not sysjump */
- if (!system_jumped_to_this_image())
- board_reset_pd_mcu();
-
- /*
- * TODO: Remove when Reef is updated with PS8751 A3.
- *
- * Force PS8751 A2 to wake from low power mode.
- * If PS8751 remains in low power mode after sysjump,
- * TCPM_INIT will fail due to not able to access PS8751.
- *
- * NOTE: PS8751 A3 will wake on any I2C access.
- */
- i2c_read8(NPCX_I2C_PORT0_1, 0x10, 0xA0, &reg);
-
- /* Enable TCPC0 interrupt */
- gpio_enable_interrupt(GPIO_USB_C0_PD_INT_ODL);
-
- /* Enable TCPC1 interrupt */
- gpio_enable_interrupt(GPIO_USB_C1_PD_INT_ODL);
-
-#ifdef CONFIG_USB_PD_TCPC_LOW_POWER
- /* Enable CABLE_DET interrupt for ANX3429 wake from standby */
- gpio_enable_interrupt(GPIO_USB_C0_CABLE_DET);
-#endif
- /*
- * Initialize HPD to low; after sysjump SOC needs to see
- * HPD pulse to enable video path
- */
- for (port = 0; port < CONFIG_USB_PD_PORT_COUNT; port++) {
- const struct usb_mux *mux = &usb_muxes[port];
-
- mux->hpd_update(port, 0, 0);
- }
-}
-DECLARE_HOOK(HOOK_INIT, board_tcpc_init, HOOK_PRIO_INIT_I2C+1);
-
/*
* Data derived from Seinhart-Hart equation in a resistor divider circuit with
* Vdd=3300mV, R = 13.7Kohm, and Murata NCP15WB-series thermistor (B = 4050,
@@ -419,7 +213,7 @@ static const struct thermistor_info charger_thermistor_info = {
int board_get_charger_temp(int idx, int *temp_ptr)
{
- int mv = adc_read_channel(NPCX_ADC_CH0);
+ int mv = adc_read_channel(ADC_TEMP_SENSOR_CHARGER);
if (mv < 0)
return -1;
@@ -459,7 +253,7 @@ static const struct thermistor_info amb_thermistor_info = {
int board_get_ambient_temp(int idx, int *temp_ptr)
{
- int mv = adc_read_channel(NPCX_ADC_CH1);
+ int mv = adc_read_channel(ADC_TEMP_SENSOR_AMB);
if (mv < 0)
return -1;
@@ -469,7 +263,6 @@ int board_get_ambient_temp(int idx, int *temp_ptr)
return 0;
}
-
const struct temp_sensor_t temp_sensors[] = {
/* FIXME(dhendrix): tweak action_delay_sec */
{"Battery", TEMP_SENSOR_TYPE_BATTERY, charge_get_battery_temp, 0, 1},
@@ -515,37 +308,30 @@ static void chipset_pre_init(void)
}
DECLARE_HOOK(HOOK_CHIPSET_PRE_INIT, chipset_pre_init, HOOK_PRIO_DEFAULT);
-static void board_set_tablet_mode(void)
-{
- tablet_set_mode(!gpio_get_level(GPIO_TABLET_MODE_L));
-}
-
/* Initialize board. */
static void board_init(void)
{
- /* Ensure tablet mode is initialized according to the hardware state
- * so that the cached state reflects reality.
- */
- board_set_tablet_mode();
-
- gpio_enable_interrupt(GPIO_TABLET_MODE_L);
+ int port;
/* Enable charger interrupts */
gpio_enable_interrupt(GPIO_CHARGER_INT_L);
- /* Enable Gyro interrupts */
- gpio_enable_interrupt(GPIO_BASE_SIXAXIS_INT_L);
+ /*
+ * Initialize HPD to low; after sysjump SOC needs to see
+ * HPD pulse to enable video path
+ */
+ for (port = 0; port < CONFIG_USB_PD_PORT_COUNT; port++)
+ usb_muxes[port].hpd_update(port, 0, 0);
}
-/* PP3300 needs to be enabled before TCPC init hooks */
-DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_FIRST);
+DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_INIT_I2C + 1);
int pd_snk_is_vbus_provided(int port)
{
- enum bd9995x_charge_port bd9995x_port;
+ enum bd9995x_charge_port bd9995x_port = 0;
switch (port) {
- case USB_PD_PORT_ANX74XX:
- case USB_PD_PORT_PS8751:
+ case 0:
+ case 1:
bd9995x_port = bd9995x_pd_port_to_chg_port(port);
break;
default:
@@ -566,7 +352,7 @@ int pd_snk_is_vbus_provided(int port)
*/
int board_set_active_charge_port(int charge_port)
{
- enum bd9995x_charge_port bd9995x_port;
+ enum bd9995x_charge_port bd9995x_port = 0;
int bd9995x_port_select = 1;
static int initialized;
@@ -581,8 +367,8 @@ int board_set_active_charge_port(int charge_port)
return -1;
switch (charge_port) {
- case USB_PD_PORT_ANX74XX:
- case USB_PD_PORT_PS8751:
+ case 0:
+ case 1:
/* Don't charge from a source port */
if (board_vbus_source_enabled(charge_port))
return -1;
@@ -679,34 +465,6 @@ int board_is_vbus_too_low(int port, enum chg_ramp_vbus_state ramp_state)
return charger_get_vbus_voltage(port) < BD9995X_BC12_MIN_VOLTAGE;
}
-static void enable_input_devices(void)
-{
- /* We need to turn on tablet mode for motion sense */
- board_set_tablet_mode();
-
- /* Then, we disable peripherals only when the lid reaches 360 position.
- * (It's probably already disabled by motion_sense_task.)
- * We deliberately do not enable peripherals when the lid is leaving
- * 360 position. Instead, we let motion_sense_task enable it once it
- * reaches laptop zone (180 or less).
- */
- if (tablet_get_mode())
- lid_angle_peripheral_enable(0);
-}
-
-/* Enable or disable input devices, based on chipset state and tablet mode */
-#ifndef TEST_BUILD
-void lid_angle_peripheral_enable(int enable)
-{
- /* If the lid is in 360 position, ignore the lid angle,
- * which might be faulty. Disable keyboard and touchpad.
- */
- if (tablet_get_mode() || chipset_in_state(CHIPSET_STATE_ANY_OFF))
- enable = 0;
- keyboard_scan_enable(enable, KB_SCAN_DISABLE_LID_ANGLE);
-}
-#endif
-
/* Called on AP S5 -> S3 transition */
static void board_chipset_startup(void)
{
@@ -715,8 +473,6 @@ static void board_chipset_startup(void)
/* Enable Trackpad */
gpio_set_level(GPIO_EN_P3300_TRACKPAD_ODL, 0);
-
- hook_call_deferred(&enable_input_devices_data, 0);
}
DECLARE_HOOK(HOOK_CHIPSET_STARTUP, board_chipset_startup, HOOK_PRIO_DEFAULT);
@@ -729,7 +485,6 @@ static void board_chipset_shutdown(void)
/* Disable Trackpad */
gpio_set_level(GPIO_EN_P3300_TRACKPAD_ODL, 1);
- hook_call_deferred(&enable_input_devices_data, 0);
/* FIXME(dhendrix): Drive USB_PD_RST_ODL low to prevent
* leakage? (see comment in schematic)
*/
@@ -794,273 +549,8 @@ void board_hibernate_late(void)
/* Change GPIOs' state in hibernate for better power consumption */
for (i = 0; i < ARRAY_SIZE(hibernate_pins); ++i)
gpio_set_flags(hibernate_pins[i][0], hibernate_pins[i][1]);
-
- gpio_config_module(MODULE_KEYBOARD_SCAN, 0);
-
- /*
- * Calling gpio_config_module sets disabled alternate function pins to
- * GPIO_INPUT. But to prevent keypresses causing leakage currents
- * while hibernating we want to enable GPIO_PULL_UP as well.
- */
- gpio_set_flags_by_mask(0x2, 0x03, GPIO_INPUT | GPIO_PULL_UP);
- gpio_set_flags_by_mask(0x1, 0x7F, GPIO_INPUT | GPIO_PULL_UP);
- gpio_set_flags_by_mask(0x0, 0xE0, GPIO_INPUT | GPIO_PULL_UP);
- /* KBD_KSO2 needs to have a pull-down enabled instead of pull-up */
- gpio_set_flags_by_mask(0x1, 0x80, GPIO_INPUT | GPIO_PULL_DOWN);
}
-/* Motion sensors */
-/* Mutexes */
-static struct mutex g_lid_mutex;
-static struct mutex g_base_mutex;
-
-/* Matrix to rotate accelrator into standard reference frame */
-const matrix_3x3_t base_standard_ref = {
- { 0, FLOAT_TO_FP(-1), 0},
- { FLOAT_TO_FP(1), 0, 0},
- { 0, 0, FLOAT_TO_FP(1)}
-};
-
-const matrix_3x3_t mag_standard_ref = {
- { FLOAT_TO_FP(-1), 0, 0},
- { 0, FLOAT_TO_FP(1), 0},
- { 0, 0, FLOAT_TO_FP(-1)}
-};
-
-/* sensor private data */
-struct kionix_accel_data g_kx022_data;
-struct bmi160_drv_data_t g_bmi160_data;
-struct bmp280_drv_data_t bmp280_drv_data;
-struct opt3001_drv_data_t g_opt3001_data = {
- .attenuation = 5,
-};
-
-/* FIXME(dhendrix): Copied from Amenia, probably need to tweak for Reef */
-struct motion_sensor_t motion_sensors[] = {
- [LID_ACCEL] = {
- .name = "Lid Accel",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_KX022,
- .type = MOTIONSENSE_TYPE_ACCEL,
- .location = MOTIONSENSE_LOC_LID,
- .drv = &kionix_accel_drv,
- .mutex = &g_lid_mutex,
- .drv_data = &g_kx022_data,
- .port = I2C_PORT_LID_ACCEL,
- .addr = KX022_ADDR1,
- .rot_standard_ref = NULL, /* Identity matrix. */
- .default_range = 2, /* g, enough for laptop. */
- .config = {
- /* AP: by default use EC settings */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* EC use accel for angle detection */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 10000 | ROUND_UP_FLAG,
- .ec_rate = 0,
- },
- /* Sensor on for lid angle detection */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 10000 | ROUND_UP_FLAG,
- .ec_rate = 0,
- },
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0,
- },
- },
- },
-
- [BASE_ACCEL] = {
- .name = "Base Accel",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_BMI160,
- .type = MOTIONSENSE_TYPE_ACCEL,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &bmi160_drv,
- .mutex = &g_base_mutex,
- .drv_data = &g_bmi160_data,
- .port = I2C_PORT_GYRO,
- .addr = BMI160_ADDR0,
- .rot_standard_ref = &base_standard_ref,
- .default_range = 2, /* g, enough for laptop. */
- .config = {
- /* AP: by default use EC settings */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* EC use accel for angle detection */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 10000 | ROUND_UP_FLAG,
- .ec_rate = 100 * MSEC,
- },
- /* Sensor on for lid angle detection */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 10000 | ROUND_UP_FLAG,
- .ec_rate = 100 * MSEC,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0
- },
- },
- },
-
- [BASE_GYRO] = {
- .name = "Base Gyro",
- .active_mask = SENSOR_ACTIVE_S0,
- .chip = MOTIONSENSE_CHIP_BMI160,
- .type = MOTIONSENSE_TYPE_GYRO,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &bmi160_drv,
- .mutex = &g_base_mutex,
- .drv_data = &g_bmi160_data,
- .port = I2C_PORT_GYRO,
- .addr = BMI160_ADDR0,
- .default_range = 1000, /* dps */
- .rot_standard_ref = &base_standard_ref,
- .config = {
- /* AP: by default shutdown all sensors */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* EC does not need in S0 */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0,
- },
- },
- },
-
- [BASE_MAG] = {
- .name = "Base Mag",
- .active_mask = SENSOR_ACTIVE_S0,
- .chip = MOTIONSENSE_CHIP_BMI160,
- .type = MOTIONSENSE_TYPE_MAG,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &bmi160_drv,
- .mutex = &g_base_mutex,
- .drv_data = &g_bmi160_data,
- .port = I2C_PORT_GYRO,
- .addr = BMI160_ADDR0,
- .default_range = 1 << 11, /* 16LSB / uT, fixed */
- .rot_standard_ref = &mag_standard_ref,
- .config = {
- /* AP: by default shutdown all sensors */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* EC does not need in S0 */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0,
- },
- },
- },
-
- [BASE_BARO] = {
- .name = "Base Baro",
- .active_mask = SENSOR_ACTIVE_S0,
- .chip = MOTIONSENSE_CHIP_BMP280,
- .type = MOTIONSENSE_TYPE_BARO,
- .location = MOTIONSENSE_LOC_BASE,
- .drv = &bmp280_drv,
- .drv_data = &bmp280_drv_data,
- .port = I2C_PORT_BARO,
- .addr = BMP280_I2C_ADDRESS1,
- .default_range = 1 << 18, /* 1bit = 4 Pa, 16bit ~= 2600 hPa */
- .config = {
- /* AP: by default shutdown all sensors */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* EC does not need in S0 */
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0,
- },
- },
- },
- [LID_ALS] = {
- .name = "Light",
- .active_mask = SENSOR_ACTIVE_S0_S3,
- .chip = MOTIONSENSE_CHIP_OPT3001,
- .type = MOTIONSENSE_TYPE_LIGHT,
- .location = MOTIONSENSE_LOC_LID,
- .drv = &opt3001_drv,
- .drv_data = &g_opt3001_data,
- .port = I2C_PORT_ALS,
- .addr = OPT3001_I2C_ADDR1,
- .rot_standard_ref = NULL,
- .default_range = OPT3001_RANGE_AUTOMATIC_FULL_SCALE,
- .config = {
- /* AP: by default shutdown all sensors */
- [SENSOR_CONFIG_AP] = {
- .odr = 0,
- .ec_rate = 0,
- },
- [SENSOR_CONFIG_EC_S0] = {
- .odr = 1000,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S3] = {
- .odr = 0,
- .ec_rate = 0,
- },
- /* Sensor off in S3/S5 */
- [SENSOR_CONFIG_EC_S5] = {
- .odr = 0,
- .ec_rate = 0,
- },
- },
- },
-};
-const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
-
-/* ALS instances when LPC mapping is needed. Each entry directs to a sensor. */
-const struct motion_sensor_t *motion_als_sensors[] = {
- &motion_sensors[LID_ALS],
-};
-BUILD_ASSERT(ARRAY_SIZE(motion_als_sensors) == ALS_COUNT);
-
void board_hibernate(void)
{
/*
@@ -1080,9 +570,9 @@ void board_hibernate(void)
}
struct {
- enum reef_board_version version;
+ enum reef_it8320_board_version version;
int thresh_mv;
-} const reef_board_versions[] = {
+} const reef_it8320_board_versions[] = {
/* Vin = 3.3V, R1 = 46.4K, R2 values listed below */
{ BOARD_VERSION_1, 328 * 1.03 }, /* 5.11 Kohm */
{ BOARD_VERSION_2, 670 * 1.03 }, /* 11.8 Kohm */
@@ -1093,7 +583,7 @@ struct {
{ BOARD_VERSION_7, 2352 * 1.03 }, /* 115 Kohm */
{ BOARD_VERSION_8, 2802 * 1.03 }, /* 261 Kohm */
};
-BUILD_ASSERT(ARRAY_SIZE(reef_board_versions) == BOARD_VERSION_COUNT);
+BUILD_ASSERT(ARRAY_SIZE(reef_it8320_board_versions) == BOARD_VERSION_COUNT);
int board_get_version(void)
{
@@ -1119,8 +609,8 @@ int board_get_version(void)
}
for (i = 0; i < BOARD_VERSION_COUNT; i++) {
- if (mv < reef_board_versions[i].thresh_mv) {
- version = reef_board_versions[i].version;
+ if (mv < reef_it8320_board_versions[i].thresh_mv) {
+ version = reef_it8320_board_versions[i].version;
break;
}
}
@@ -1148,3 +638,92 @@ struct keyboard_scan_config keyscan_config = {
0xa4, 0xff, 0xfe, 0x55, 0xfa, 0xca /* full set */
},
};
+
+/* PNPCFG settings */
+const struct ec2i_t pnpcfg_settings[] = {
+ /* Select logical device 06h(keyboard) */
+ {HOST_INDEX_LDN, LDN_KBC_KEYBOARD},
+ /* Set IRQ=01h for logical device */
+ {HOST_INDEX_IRQNUMX, 0x01},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+
+ /* Select logical device 05h(mouse) */
+ {HOST_INDEX_LDN, LDN_KBC_MOUSE},
+ /* Set IRQ=0Ch for logical device */
+ {HOST_INDEX_IRQNUMX, 0x0C},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+
+ /* Select logical device 11h(PM1 ACPI) */
+ {HOST_INDEX_LDN, LDN_PMC1},
+ /* Set IRQ=00h for logical device */
+ {HOST_INDEX_IRQNUMX, 0x00},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+
+ /* Select logical device 12h(PM2) */
+ {HOST_INDEX_LDN, LDN_PMC2},
+ /* I/O Port Base Address 200h/204h */
+ {HOST_INDEX_IOBAD0_MSB, 0x02},
+ {HOST_INDEX_IOBAD0_LSB, 0x00},
+ {HOST_INDEX_IOBAD1_MSB, 0x02},
+ {HOST_INDEX_IOBAD1_LSB, 0x04},
+ /* Set IRQ=00h for logical device */
+ {HOST_INDEX_IRQNUMX, 0x00},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+
+ /* Select logical device 0Fh(SMFI) */
+ {HOST_INDEX_LDN, LDN_SMFI},
+ /* H2RAM LPC I/O cycle Dxxx */
+ {HOST_INDEX_DSLDC6, 0x00},
+ /* Enable H2RAM LPC I/O cycle */
+ {HOST_INDEX_DSLDC7, 0x01},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+
+ /* Select logical device 17h(PM3) */
+ {HOST_INDEX_LDN, LDN_PMC3},
+ /* I/O Port Base Address 80h */
+ {HOST_INDEX_IOBAD0_MSB, 0x00},
+ {HOST_INDEX_IOBAD0_LSB, 0x80},
+ {HOST_INDEX_IOBAD1_MSB, 0x00},
+ {HOST_INDEX_IOBAD1_LSB, 0x00},
+ /* Set IRQ=00h for logical device */
+ {HOST_INDEX_IRQNUMX, 0x00},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+ /* Select logical device 10h(RTCT) */
+ {HOST_INDEX_LDN, LDN_RTCT},
+ /* P80L Begin Index */
+ {HOST_INDEX_DSLDC4, P80L_P80LB},
+ /* P80L End Index */
+ {HOST_INDEX_DSLDC5, P80L_P80LE},
+ /* P80L Current Index */
+ {HOST_INDEX_DSLDC6, P80L_P80LC},
+#ifdef CONFIG_UART_HOST
+ /* Select logical device 2h(UART2) */
+ {HOST_INDEX_LDN, LDN_UART2},
+ /*
+ * I/O port base address is 2F8h.
+ * Host can use LPC I/O port 0x2F8 ~ 0x2FF to access UART2.
+ * See specification 7.24.4 for more detial.
+ */
+ {HOST_INDEX_IOBAD0_MSB, 0x02},
+ {HOST_INDEX_IOBAD0_LSB, 0xF8},
+ /* IRQ number is 3 */
+ {HOST_INDEX_IRQNUMX, 0x03},
+ /*
+ * Interrupt Request Type Select
+ * bit1, 0: IRQ request is buffered and applied to SERIRQ.
+ * 1: IRQ request is inverted before being applied to SERIRQ.
+ * bit0, 0: Edge triggered mode.
+ * 1: Level triggered mode.
+ */
+ {HOST_INDEX_IRQTP, 0x02},
+ /* Enable logical device */
+ {HOST_INDEX_LDA, 0x01},
+#endif
+};
+BUILD_ASSERT(ARRAY_SIZE(pnpcfg_settings) == EC2I_SETTING_COUNT);
diff --git a/board/reef_it8320/board.h b/board/reef_it8320/board.h
index dd3a16d776..c4198e4e8a 100644
--- a/board/reef_it8320/board.h
+++ b/board/reef_it8320/board.h
@@ -1,9 +1,9 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*/
-/* Reef board configuration */
+/* reef_it8320 board configuration */
#ifndef __CROS_EC_BOARD_H
#define __CROS_EC_BOARD_H
@@ -16,10 +16,7 @@
#undef CONFIG_HOSTCMD_DEBUG_MODE
#define CONFIG_HOSTCMD_DEBUG_MODE HCDEBUG_OFF
-
/* EC console commands */
-#define CONFIG_CMD_ACCELS
-#define CONFIG_CMD_ACCEL_INFO
#define CONFIG_CMD_BATT_MFG_ACCESS
#define CONFIG_CMD_CHARGER_ADC_AMON_BMON
#define CONFIG_CHARGER_SENSE_RESISTOR 10
@@ -31,13 +28,6 @@
#define BD9995X_PSYS_GAIN_SELECT \
BD9995X_CMD_PMON_IOUT_CTRL_SET_PMON_GAIN_SET_02UAW
-#define CONFIG_CMD_I2C_STRESS_TEST
-#define CONFIG_CMD_I2C_STRESS_TEST_ACCEL
-#define CONFIG_CMD_I2C_STRESS_TEST_ALS
-#define CONFIG_CMD_I2C_STRESS_TEST_BATTERY
-#define CONFIG_CMD_I2C_STRESS_TEST_CHARGER
-#define CONFIG_CMD_I2C_STRESS_TEST_TCPC
-
/* Battery */
#define CONFIG_BATTERY_DEVICE_CHEMISTRY "LION"
#define CONFIG_BATTERY_CUT_OFF
@@ -73,29 +63,24 @@
#define GPIO_USB_ILIM_SEL GPIO_USB_A_CHARGE_EN_L
#define GPIO_USB_CTL1 GPIO_EN_PP5000
-#define CONFIG_TABLET_MODE
-
/* USB PD config */
#define CONFIG_CASE_CLOSED_DEBUG_EXTERNAL
+#define CONFIG_USB_MUX_PI3USB30532
+#define CONFIG_USB_MUX_PS8740
#define CONFIG_CMD_PD_CONTROL
#define CONFIG_USB_PD_ALT_MODE
#define CONFIG_USB_PD_ALT_MODE_DFP
#define CONFIG_USB_PD_CUSTOM_VDM
#define CONFIG_USB_PD_DUAL_ROLE
-#define CONFIG_USB_PD_DUAL_ROLE_AUTO_TOGGLE
#define CONFIG_USB_PD_DISCHARGE
-#define CONFIG_USB_PD_DISCHARGE_TCPC
+#define CONFIG_USB_PD_DISCHARGE_GPIO
#define CONFIG_USB_PD_LOGGING
#define CONFIG_USB_PD_LOG_SIZE 512
#define CONFIG_USB_PD_MAX_SINGLE_SOURCE_CURRENT TYPEC_RP_3A0
#define CONFIG_USB_PD_PORT_COUNT 2
#define CONFIG_USB_PD_QUIRK_SLOW_CC_STATUS
#define CONFIG_USB_PD_VBUS_DETECT_CHARGER
-#define CONFIG_USB_PD_TCPC_LOW_POWER
-#define CONFIG_USB_PD_TCPM_MUX /* for both PS8751 and ANX3429 */
-#define CONFIG_USB_PD_TCPM_ANX74XX
-#define CONFIG_USB_PD_TCPM_PS8751
-#define CONFIG_USB_PD_TCPM_TCPCI
+#define CONFIG_USB_PD_TCPM_ITE83XX
#define CONFIG_USB_PD_TRY_SRC
#define CONFIG_USB_POWER_DELIVERY
#define CONFIG_USB_PD_COMM_LOCKED
@@ -109,7 +94,6 @@
#define CONFIG_LPC
#define CONFIG_CHIPSET_APOLLOLAKE
#define CONFIG_CHIPSET_RESET_HOOK
-#undef CONFIG_PECI
#define CONFIG_POWER_BUTTON
#define CONFIG_POWER_BUTTON_X86
#define CONFIG_POWER_COMMON
@@ -122,124 +106,71 @@
#define CONFIG_BOARD_SPECIFIC_VERSION
#define CONFIG_BUTTON_COUNT 2
#define CONFIG_EXTPOWER_GPIO
-#undef CONFIG_EXTPOWER_DEBOUNCE_MS
-#define CONFIG_EXTPOWER_DEBOUNCE_MS 1000
-#define CONFIG_FPU
-/* Region sizes are not a power of 2 so we can't use MPU */
-#undef CONFIG_MPU
-#define CONFIG_HOSTCMD_FLASH_SPI_INFO
+#undef CONFIG_EXTPOWER_DEBOUNCE_MS
+#define CONFIG_EXTPOWER_DEBOUNCE_MS 1000
#define CONFIG_I2C
#define CONFIG_I2C_MASTER
#define CONFIG_KEYBOARD_BOARD_CONFIG
#define CONFIG_KEYBOARD_PROTOCOL_8042
#define CONFIG_KEYBOARD_COL2_INVERTED
-#define CONFIG_KEYBOARD_PWRBTN_ASSERTS_KSI2
#define CONFIG_LED_COMMON
#define CONFIG_LID_SWITCH
#define CONFIG_LOW_POWER_IDLE
-#define CONFIG_LTO
#define CONFIG_POWER_SIGNAL_INTERRUPT_STORM_DETECT_THRESHOLD 30
-#define CONFIG_PWM
#define CONFIG_TEMP_SENSOR
#define CONFIG_THERMISTOR_NCP15WB
#define CONFIG_DPTF
-#define CONFIG_DPTF_DEVICE_ORIENTATION
#define CONFIG_SCI_GPIO GPIO_PCH_SCI_L
-#define CONFIG_UART_HOST 0
#define CONFIG_VBOOT_HASH
#define CONFIG_BACKLIGHT_LID
#define CONFIG_WIRELESS
#define CONFIG_WIRELESS_SUSPEND EC_WIRELESS_SWITCH_WLAN_POWER
#define CONFIG_WLAN_POWER_ACTIVE_LOW
-#define WIRELESS_GPIO_WLAN_POWER GPIO_WIRELESS_GPIO_WLAN_POWER
+#define WIRELESS_GPIO_WLAN_POWER GPIO_WIRELESS_GPIO_WLAN_POWER
#define CONFIG_PWR_STATE_DISCHARGE_FULL
/*
- * During shutdown sequence TPS65094x PMIC turns off the sensor rails
- * asynchronously to the EC. If we access the sensors when the sensor power
- * rails are off we get I2C errors. To avoid this issue, defer switching
- * the sensors rate if in S3. By the time deferred function is serviced if
- * the chipset is in S5 we can back out from switching the sensor rate.
- *
- * Time taken by V1P8U rail to go down from S3 is 30ms to 60ms hence defer
- * the sensor switching after 60ms.
- */
-#undef CONFIG_MOTION_SENSE_SUSPEND_DELAY_US
-#define CONFIG_MOTION_SENSE_SUSPEND_DELAY_US (MSEC * 60)
-
-#define CONFIG_FLASH_SIZE 524288
-#define CONFIG_SPI_FLASH_REGS
-#define CONFIG_SPI_FLASH_W25Q40 /* FIXME: Should be GD25LQ40? */
-
-/*
* Enable 1 slot of secure temporary storage to support
* suspend/resume with read/write memory training.
*/
#define CONFIG_VSTORE
#define CONFIG_VSTORE_SLOT_COUNT 1
-/* Optional feature - used by nuvoton */
-#define NPCX_UART_MODULE2 1 /* 0:GPIO10/11 1:GPIO64/65 as UART */
-#define NPCX_JTAG_MODULE2 0 /* 0:GPIO21/17/16/20 1:GPIOD5/E2/D4/E5 as JTAG*/
-/* FIXME(dhendrix): these pins are just normal GPIOs on Reef. Do we need
- * to change some other setting to put them in GPIO mode?
- */
-#define NPCX_TACH_SEL2 0 /* 0:GPIO40/73 1:GPIO93/A6 as TACH */
+/* modules we want to exclude */
+#undef CONFIG_PECI
+#undef CONFIG_PWM
+#undef CONFIG_SPI
+#undef CONFIG_UART_HOST
-/* I2C ports */
-#define I2C_PORT_GYRO NPCX_I2C_PORT1
-#define I2C_PORT_LID_ACCEL NPCX_I2C_PORT2
-#define I2C_PORT_ALS NPCX_I2C_PORT2
-#define I2C_PORT_BARO NPCX_I2C_PORT2
-#define I2C_PORT_BATTERY NPCX_I2C_PORT3
-#define I2C_PORT_CHARGER NPCX_I2C_PORT3
-/* Accelerometer and Gyroscope are the same device. */
-#define I2C_PORT_ACCEL I2C_PORT_GYRO
-
-/* Sensors */
-#define CONFIG_MKBP_EVENT
-#define CONFIG_MKBP_USE_HOST_EVENT
-#define CONFIG_ACCELGYRO_BMI160
-#define CONFIG_ACCEL_INTERRUPTS
-#define CONFIG_ACCELGYRO_BMI160_INT_EVENT TASK_EVENT_CUSTOM(4)
-#define CONFIG_MAG_BMI160_BMM150
-#define BMM150_I2C_ADDRESS BMM150_ADDR0 /* 8-bit address */
-#define CONFIG_MAG_CALIBRATE
-#define CONFIG_ACCEL_KX022
-#define CONFIG_ALS_OPT3001
-#define CONFIG_BARO_BMP280
-#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
-
-/* FIFO size is in power of 2. */
-#define CONFIG_ACCEL_FIFO 1024
-
-/* Depends on how fast the AP boots and typical ODRs */
-#define CONFIG_ACCEL_FIFO_THRES (CONFIG_ACCEL_FIFO / 3)
+/* TODO: There isn't enough space on flash before nds32 toolchain is updated */
+#undef CONFIG_CMD_HASH
+#undef CONFIG_CMD_IDLE_STATS
+#undef CONFIG_CMD_SLEEPMASK
+#undef CONFIG_CMD_TIMERINFO
+#undef CONFIG_UART_TX_BUF_SIZE
+#define CONFIG_UART_TX_BUF_SIZE 4096
+#undef CONFIG_UART_RX_BUF_SIZE
+#define CONFIG_UART_RX_BUF_SIZE 512
#ifndef __ASSEMBLER__
#include "gpio_signal.h"
#include "registers.h"
+/* I2C ports */
+#define I2C_PORT_USB_MUX IT83XX_I2C_CH_C
+#define I2C_PORT_BATTERY IT83XX_I2C_CH_E
+#define I2C_PORT_CHARGER IT83XX_I2C_CH_E
+
/* ADC signal */
enum adc_channel {
- ADC_TEMP_SENSOR_CHARGER, /* ADC0 */
- ADC_TEMP_SENSOR_AMB, /* ADC1 */
- ADC_BOARD_ID, /* ADC2 */
+ ADC_TEMP_SENSOR_CHARGER, /* ADC CH1 */
+ ADC_TEMP_SENSOR_AMB, /* ADC CH2 */
+ ADC_BOARD_ID, /* ADC CH3 */
ADC_CH_COUNT
};
-enum pwm_channel {
- PWM_CH_LED_GREEN = 0,
- PWM_CH_LED_RED,
- /* Number of PWM channels */
- PWM_CH_COUNT
-};
-
enum power_signal {
X86_RSMRST_N = 0,
X86_SLP_S3_N,
@@ -261,30 +192,7 @@ enum temp_sensor_id {
TEMP_SENSOR_COUNT
};
-/*
- * For backward compatibility, to report ALS via ACPI,
- * Define the number of ALS sensors: motion_sensor copy the data to the ALS
- * memmap region.
- */
-#define CONFIG_ALS
-#define ALS_COUNT 1
-
-/*
- * Motion sensors:
- * When reading through IO memory is set up for sensors (LPC is used),
- * the first 2 entries must be accelerometers, then gyroscope.
- * For BMI160, accel, gyro and compass sensors must be next to each other.
- */
-enum sensor_id {
- LID_ACCEL = 0,
- BASE_ACCEL,
- BASE_GYRO,
- BASE_MAG,
- BASE_BARO,
- LID_ALS,
-};
-
-enum reef_board_version {
+enum reef_it8320_board_version {
BOARD_VERSION_UNKNOWN = -1,
BOARD_VERSION_1,
BOARD_VERSION_2,
@@ -297,6 +205,50 @@ enum reef_board_version {
BOARD_VERSION_COUNT,
};
+enum ec2i_setting {
+ EC2I_SET_KB_LDN,
+ EC2I_SET_KB_IRQ,
+ EC2I_SET_KB_ENABLE,
+ EC2I_SET_MOUSE_LDN,
+ EC2I_SET_MOUSE_IRQ,
+ EC2I_SET_MOUSE_ENABLE,
+ EC2I_SET_PMC1_LDN,
+ EC2I_SET_PMC1_IRQ,
+ EC2I_SET_PMC1_ENABLE,
+ EC2I_SET_PMC2_LDN,
+ EC2I_SET_PMC2_BASE0_MSB,
+ EC2I_SET_PMC2_BASE0_LSB,
+ EC2I_SET_PMC2_BASE1_MSB,
+ EC2I_SET_PMC2_BASE1_LSB,
+ EC2I_SET_PMC2_IRQ,
+ EC2I_SET_PMC2_ENABLE,
+ EC2I_SET_SMFI_LDN,
+ EC2I_SET_SMFI_H2RAM_IO_BASE,
+ EC2I_SET_SMFI_H2RAM_MAP_LPC_IO,
+ EC2I_SET_SMFI_ENABLE,
+ EC2I_SET_PMC3_LDN,
+ EC2I_SET_PMC3_BASE0_MSB,
+ EC2I_SET_PMC3_BASE0_LSB,
+ EC2I_SET_PMC3_BASE1_MSB,
+ EC2I_SET_PMC3_BASE1_LSB,
+ EC2I_SET_PMC3_IRQ,
+ EC2I_SET_PMC3_ENABLE,
+ EC2I_SET_RTCT_LDN,
+ EC2I_SET_RTCT_P80LB,
+ EC2I_SET_RTCT_P80LE,
+ EC2I_SET_RTCT_P80LC,
+#ifdef CONFIG_UART_HOST
+ EC2I_SET_UART2_LDN,
+ EC2I_SET_UART2_IO_BASE_MSB,
+ EC2I_SET_UART2_IO_BASE_LSB,
+ EC2I_SET_UART2_IRQ,
+ EC2I_SET_UART2_IRQ_TYPE,
+ EC2I_SET_UART2_ENABLE,
+#endif
+ /* Number of EC2I settings */
+ EC2I_SETTING_COUNT
+};
+
/* TODO: determine the following board specific type-C power constants */
/* FIXME(dhendrix): verify all of the below PD_* numbers */
/*
@@ -317,14 +269,9 @@ enum reef_board_version {
/* Reset PD MCU */
void board_reset_pd_mcu(void);
-
int board_get_version(void);
-
-void board_set_tcpc_power_mode(int port, int mode);
-
-/* Sensors without hardware FIFO are in forced mode */
-#define CONFIG_ACCEL_FORCE_MODE_MASK \
- ((1 << LID_ACCEL) | (1 << BASE_BARO) | (1 << LID_ALS))
+/* Turn on/off vconn power switch. */
+void board_pd_vconn_ctrl(int port, int cc_pin, int enabled);
#endif /* !__ASSEMBLER__ */
diff --git a/board/reef_it8320/build.mk b/board/reef_it8320/build.mk
index 728d027803..328afdc8f5 100644
--- a/board/reef_it8320/build.mk
+++ b/board/reef_it8320/build.mk
@@ -1,13 +1,12 @@
# -*- makefile -*-
-# Copyright 2015 The Chromium OS Authors. All rights reserved.
+# Copyright 2017 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:=npcx
-CHIP_VARIANT:=npcx5m6g
+# the IC is ITE IT8320
+CHIP:=it83xx
board-y=board.o led.o
board-$(CONFIG_BATTERY_SMART)+=battery.o
diff --git a/board/reef_it8320/ec.tasklist b/board/reef_it8320/ec.tasklist
index e153496b43..12d940e81c 100644
--- a/board/reef_it8320/ec.tasklist
+++ b/board/reef_it8320/ec.tasklist
@@ -1,4 +1,4 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*/
@@ -25,14 +25,11 @@
TASK_ALWAYS(CHG_RAMP, chg_ramp_task, NULL, TASK_STACK_SIZE) \
TASK_ALWAYS(USB_CHG, usb_charger_task, NULL, TASK_STACK_SIZE) \
TASK_ALWAYS(CHARGER, charger_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(MOTIONSENSE, motion_sense_task, NULL, VENTI_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/reef_it8320/gpio.inc b/board/reef_it8320/gpio.inc
index fb45f2336b..4c6d81b98e 100644
--- a/board/reef_it8320/gpio.inc
+++ b/board/reef_it8320/gpio.inc
@@ -1,172 +1,116 @@
/* -*- mode:c -*-
*
- * Copyright 2016 The Chromium OS Authors. All rights reserved.
+ * Copyright 2017 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. */
-
-GPIO_INT(CHARGER_INT_L, PIN(3, 3), GPIO_INT_FALLING, bd9995x_vbus_interrupt) /* CHARGER_EC_INT_ODL from BD99956 */
-/*
- * TODO: The pull ups for Parade TCPC interrupt line can be removed in versions
- * of board following EVT in which daughter card (which has an external pull up)
- * will always be inserted.
- */
-GPIO_INT(USB_C0_PD_INT_ODL, PIN(3, 7), GPIO_INT_FALLING, tcpc_alert_event) /* from Analogix TCPC */
-GPIO_INT(USB_C1_PD_INT_ODL, PIN(B, 1), GPIO_INT_FALLING | GPIO_PULL_UP, tcpc_alert_event) /* from Parade TCPC */
-
-GPIO_INT(USB_C0_CABLE_DET, PIN(C, 5), GPIO_INT_RISING, anx74xx_cable_det_interrupt) /* CABLE_DET from ANX3429 */
-
-GPIO_INT(PCH_SLP_S4_L, PIN(8, 6), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S4_L */
-GPIO_INT(PCH_SLP_S3_L, PIN(7, 3), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S3_L */
-GPIO_INT(SUSPWRNACK, PIN(7, 2), GPIO_INT_BOTH, power_signal_interrupt)
-GPIO_INT(RSMRST_L_PGOOD, PIN(6, 0), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_RSMRST_ODL */
-GPIO_INT(ALL_SYS_PGOOD, PIN(5, 0), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_PWROK_OD */
-
-GPIO_INT(AC_PRESENT, PIN(C, 1), GPIO_INT_BOTH, extpower_interrupt) /* ACOK_OD from BD99956 */
-/* TODO: We might remove external pull-up for POWER_BUTTON_L in EVT */
-GPIO_INT(POWER_BUTTON_L, PIN(0, 4), GPIO_INT_BOTH, power_button_interrupt) /* MECH_PWR_BTN_ODL */
-GPIO_INT(LID_OPEN, PIN(6, 7), GPIO_INT_BOTH, lid_interrupt)
-/* Volume up and down buttons need to be swapped. The one closer to the hinge
- * should be volume up and the one closer to the user should be volume down.
- * (cros.bug/p/60057) */
-GPIO_INT(EC_VOLDN_BTN_ODL_SWAPPED, PIN(8, 3), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt)
-GPIO_INT(EC_VOLUP_BTN_ODL_SWAPPED, PIN(8, 2), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt)
-#define GPIO_EC_VOLDN_BTN_ODL GPIO_EC_VOLUP_BTN_ODL_SWAPPED
-#define GPIO_EC_VOLUP_BTN_ODL GPIO_EC_VOLDN_BTN_ODL_SWAPPED
-/* Tablet switch is active-low. L: lid is attached (360 position) H: detached */
-GPIO_INT(TABLET_MODE_L, PIN(3, 6), GPIO_INT_BOTH, tablet_mode_interrupt)
-
-GPIO_INT(WP_L, PIN(4, 0), GPIO_INT_BOTH | GPIO_SEL_1P8V, switch_interrupt) /* EC_WP_ODL */
-
-GPIO_INT(BASE_SIXAXIS_INT_L, PIN(9, 3), GPIO_INT_FALLING | GPIO_SEL_1P8V,
- bmi160_interrupt)
-GPIO(LID_ACCEL_INT_L, PIN(C, 7), GPIO_INPUT | GPIO_SEL_1P8V)
-
-/* I2C GPIOs will be set to alt. function later. */
-GPIO(EC_I2C_GYRO_SDA, PIN(8, 7), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(EC_I2C_GYRO_SCL, PIN(9, 0), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(EC_I2C_SENSOR_SDA, PIN(9, 1), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(EC_I2C_SENSOR_SCL, PIN(9, 2), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(EC_I2C_USB_C0_PD_SDA, PIN(B, 4), GPIO_INPUT)
-GPIO(EC_I2C_USB_C0_PD_SCL, PIN(B, 5), GPIO_INPUT)
-GPIO(EC_I2C_USB_C1_PD_SDA, PIN(B, 2), GPIO_INPUT)
-GPIO(EC_I2C_USB_C1_PD_SCL, PIN(B, 3), GPIO_INPUT)
-GPIO(EC_I2C_POWER_SDA, PIN(D, 0), GPIO_INPUT)
-GPIO(EC_I2C_POWER_SCL, PIN(D, 1), GPIO_INPUT)
-
-/*
- * LPC:
- * Pins 46, 47, 51, 52, 53, 54, 55, default to LPC mode.
- * Pin 56 (CLKRUN#) defaults to GPIO mode.
- * Pin 57 (SER_IRQ) defaults to LPC mode, but we also have EC_PCH_KB_INT_ODL
- * (Pin B0) in case it doesn't work (Set CONFIG_KEYBOARD_IRQ_GPIO in this case).
- *
- * See also the NO_LPC_ESPI bit in DEVALT1 and the CONFIG_HOSTCMD_SPS option.
+ * Note: Those with interrupt handlers must be declared first.
*/
-
-GPIO(PCH_SMI_L, PIN(A, 6), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_SMI_ODL */
-GPIO(PCH_SCI_L, PIN(A, 7), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_SCI_ODL */
-GPIO(PCH_SLP_S0_L, PIN(7, 5), GPIO_INPUT) /* SLP_S0_L */
-
+GPIO_INT(CHARGER_INT_L, PIN(A, 6), GPIO_INT_FALLING, bd9995x_vbus_interrupt) /* CHARGER_EC_INT_ODL from BD99956 */
+GPIO_INT(AC_PRESENT, PIN(A, 7), GPIO_INT_BOTH, extpower_interrupt) /* ACOK_OD from BD99956 */
+#ifdef CONFIG_LOW_POWER_IDLE
+GPIO_INT(UART1_RX, PIN(B, 0), GPIO_INT_FALLING, uart_deepsleep_interrupt) /* UART_SERVO_TX_EC_RX */
+#endif
+GPIO_INT(EC_VOLUP_BTN_ODL, PIN(D, 5), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt) /* EC_VOLUP_BTN_ODL */
+GPIO_INT(EC_VOLDN_BTN_ODL, PIN(D, 6), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt) /* EC_VOLDN_BTN_ODL */
+GPIO_INT(SUSPWRNACK, PIN(E, 1), GPIO_INT_BOTH, power_signal_interrupt) /* SUSPWRNACK */
+GPIO_INT(LID_OPEN, PIN(E, 2), GPIO_INT_BOTH, lid_interrupt) /* LID_OPEN */
+GPIO_INT(PCH_PLTRST_L, PIN(E, 3), GPIO_INT_BOTH | GPIO_PULL_UP, lpcrst_interrupt) /* PLT_RST_L */
+GPIO_INT(POWER_BUTTON_L, PIN(E, 4), GPIO_INT_BOTH, power_button_interrupt) /* MECH_PWR_BTN_ODL */
+GPIO_INT(ALL_SYS_PGOOD, PIN(F, 0), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_PWROK_OD */
+GPIO_INT(RSMRST_L_PGOOD, PIN(F, 1), GPIO_INT_BOTH, power_signal_interrupt) /* PMIC_EC_RSMRST_ODL */
+GPIO_INT(PCH_SLP_S3_L, PIN(F, 2), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S3_L */
+GPIO_INT(PCH_SLP_S4_L, PIN(F, 3), GPIO_INT_BOTH, power_signal_interrupt) /* SLP_S4_L */
+GPIO_INT(WP_L, PIN(I, 4), GPIO_INT_BOTH | GPIO_SEL_1P8V, switch_interrupt) /* EC_WP_ODL_R */
+
+GPIO(EN_USB_C0_3A, PIN(A, 0), GPIO_OUT_LOW) /* 1.5/3.0 C0 current limit selection */
+GPIO(EN_USB_C1_3A, PIN(A, 1), GPIO_OUT_LOW) /* 1.5/3.0 C1 current limit selection */
+GPIO(EN_P3300_TRACKPAD_ODL, PIN(A, 2), GPIO_ODR_HIGH) /* EN_PP3300_TRACKPAD_ODL */
+GPIO(EC_HAVEN_RESET_ODL, PIN(A, 3), GPIO_ODR_HIGH) /* EC_HAVEN_RST_ODL */
+/* Pin A.4 A.5 (I2C) for iteflash (servo board) */
+GPIO(WIRELESS_GPIO_WLAN_POWER, PIN(B, 2), GPIO_ODR_HIGH) /* EN_PP3300_WLAN_ODL */
+/* I2C GPIOs will be set to ALT function later. */
+GPIO(EC_I2C_A_SCL, PIN(B, 3), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C_GYRO_SCL */
+GPIO(EC_I2C_A_SDA, PIN(B, 4), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C_GYRO_SDA */
+GPIO(ENABLE_BACKLIGHT, PIN(B, 5), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_BL_EN_OD */
+GPIO(PCH_RCIN_L, PIN(B, 6), GPIO_ODR_HIGH) /* SYS_RST_ODL */
+GPIO(PCH_SLP_S0_L, PIN(B, 7), GPIO_INPUT) /* SLP_S0_L */
+GPIO(EC_BATT_PRES_L, PIN(C, 0), GPIO_INPUT) /* EC_BATT_PRES_L */
+GPIO(EC_I2C_B_SCL, PIN(C, 1), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C_SENSOR_U_SCL */
+GPIO(EC_I2C_B_SDA, PIN(C, 2), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C_SENSOR_U_SDA */
/*
* BRD_ID1 is a an ADC pin which will be used to measure multiple values.
* Assert EC_BRD_ID_EN_ODL and then read BRD_ID1.
*/
-ALTERNATE(PIN_MASK(4, 0x08), 1, MODULE_ADC, 0)
-GPIO(EC_BRD_ID_EN_ODL, PIN(3, 5), GPIO_INPUT)
-
-GPIO(CCD_MODE_ODL, PIN(6, 3), GPIO_INPUT)
-GPIO(EC_HAVEN_RESET_ODL, PIN(0, 2), GPIO_ODR_HIGH)
-GPIO(ENTERING_RW, PIN(7, 6), GPIO_OUTPUT) /* EC_ENTERING_RW */
-
-GPIO(PCH_RSMRST_L, PIN(7, 0), GPIO_OUT_LOW)
-GPIO(EC_BATT_PRES_L, PIN(3, 4), GPIO_INPUT)
-GPIO(PMIC_EN, PIN(8, 5), GPIO_OUT_LOW)
-GPIO(EN_PP3300, PIN(C, 2), GPIO_OUT_LOW)
-GPIO(PP3300_PG, PIN(6, 2), GPIO_INPUT)
-GPIO(EN_PP5000, PIN(C, 6), GPIO_OUT_LOW)
-GPIO(PP5000_PG, PIN(7, 1), GPIO_INPUT)
-GPIO(EN_P3300_TRACKPAD_ODL, PIN(3, 2), GPIO_ODR_LOW)
-/* Control the gate for trackpad IRQ. High closes the gate.
- * This is always set low so that the OS can manage the trackpad. */
-GPIO(TRACKPAD_INT_GATE, PIN(A, 1), GPIO_OUT_LOW)
-GPIO(PCH_SYS_PWROK, PIN(E, 7), GPIO_OUT_LOW) /* EC_PCH_PWROK */
-GPIO(ENABLE_BACKLIGHT, PIN(9, 7), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_BL_EN_OD */
-
-GPIO(WIRELESS_GPIO_WLAN_POWER, PIN(6, 6), GPIO_ODR_HIGH) /* EN_PP3300_WLAN_ODL */
-
+GPIO(EC_BRD_ID_EN_ODL, PIN(C, 3), GPIO_INPUT) /* EC_BRD_ID_EN_ODL */
+GPIO(CCD_MODE_ODL, PIN(C, 4), GPIO_INPUT) /* CCD_MODE_ODL */
+GPIO(ENTERING_RW, PIN(C, 5), GPIO_OUTPUT) /* EC_ENTERING_RW */
+GPIO(PCH_RSMRST_L, PIN(C, 6), GPIO_OUT_LOW) /* PCH_RSMRST_L */
/*
* 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(A, 3), GPIO_INPUT | GPIO_SEL_1P8V) /* PCH_PROCHOT_ODL */
-
-GPIO(PCH_PWRBTN_L, PIN(0, 1), GPIO_ODR_HIGH) /* EC_PCH_PWR_BTN_ODL */
-GPIO(PCH_WAKE_L, PIN(8, 1), GPIO_ODR_HIGH) /* EC_PCH_WAKE_ODL */
-GPIO(USB_C0_HPD_1P8_ODL, PIN(9, 4), GPIO_INPUT | GPIO_SEL_1P8V)
-GPIO(USB_C1_HPD_1P8_ODL, PIN(A, 5), GPIO_INPUT | GPIO_SEL_1P8V)
-
-GPIO(USB2_OTG_VBUSSENSE, PIN(9, 5), GPIO_OUTPUT)
-
+GPIO(CPU_PROCHOT, PIN(C, 7), GPIO_INPUT | GPIO_SEL_1P8V) /* PCH_PROCHOT_ODL */
+GPIO(PCH_PWRBTN_L, PIN(D, 0), GPIO_ODR_HIGH) /* EC_PCH_PWR_BTN_ODL */
+GPIO(PCH_WAKE_L, PIN(D, 1), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_PCH_WAKE_ODL */
+GPIO(DP_MUX_EN, PIN(D, 2), GPIO_OUT_HIGH) /* DB_MUX_EN */
+GPIO(PCH_SCI_L, PIN(D, 3), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_SCI_ODL */
+GPIO(PCH_SMI_L, PIN(D, 4), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* EC_SMI_ODL */
+GPIO(PMIC_EN, PIN(D, 7), GPIO_OUT_LOW) /* PMIC_A_RAILS_EN */
+GPIO(EC_I2C_E_SCL, PIN(E, 0), GPIO_INPUT) /* EC_I2C_POWER_3V3_SCL */
+/* FIXME: this pin doesn't support 1.8v */
+#if 0
+GPIO(KBD_IRQ_L, PIN(E, 5), GPIO_ODR_HIGH) /* EC_PCH_KB_INT_ODL */
+#endif
+GPIO(CHARGER_RST_ODL, PIN(E, 6), GPIO_ODR_HIGH) /* CHARGER_RST_ODL */
+GPIO(EC_I2C_E_SDA, PIN(E, 7), GPIO_INPUT) /* EC_I2C_POWER_3V3_SDA */
+/* F.5 F.4 are cc pins of PD0 */
+GPIO(EC_I2C_C_SCL, PIN(F, 6), GPIO_INPUT) /* EC_I2C_USBC_MUX_SCL */
+GPIO(EC_I2C_C_SDA, PIN(F, 7), GPIO_INPUT) /* EC_I2C_USBC_MUX_SDA */
+GPIO(LPC_CLKRUN_L, PIN(H, 0), GPIO_OUT_LOW) /* LPC_CLKRUN_L */
+/* H.1 H.2 are cc pins of PD1 */
+GPIO(TRACKPAD_INT_GATE, PIN(H, 3), GPIO_OUT_LOW)
+GPIO(USB2_OTG_VBUSSENSE, PIN(H, 4), GPIO_OUTPUT)
+GPIO(USB_C0_HPD_1P8_ODL, PIN(J, 0), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* USB_C0_HPD_1V8_ODL */
+GPIO(USB_C1_HPD_1P8_ODL, PIN(J, 1), GPIO_ODR_HIGH | GPIO_SEL_1P8V) /* USB_C1_HPD_1V8_ODL */
+GPIO(LID_ACCEL_INT_L, PIN(J, 3), GPIO_INPUT | GPIO_SEL_1P8V) /* LID_ACCEL_INT_L */
+/* NOTE: Active low */
+GPIO(USB_C0_CC1_VCONN_EN, PIN(J, 4), GPIO_OUT_HIGH) /* USB_C0_CC1_VCONN_EN_ODL */
+GPIO(USB_C0_CC2_VCONN_EN, PIN(J, 5), GPIO_OUT_HIGH) /* USB_C0_CC2_VCONN_EN_ODL */
+
+GPIO(EN_PP3300, PIN(K, 0), GPIO_OUT_LOW) /* EN_PP3300 */
+GPIO(PP3300_PG, PIN(K, 1), GPIO_INPUT) /* PP3300_PG_OD */
+GPIO(EN_PP5000, PIN(K, 2), GPIO_OUT_LOW) /* EN_PP5000 */
+GPIO(PP5000_PG, PIN(K, 3), GPIO_INPUT) /* PP5000_PG_OD */
+GPIO(PCH_SYS_PWROK, PIN(K, 4), GPIO_OUT_LOW) /* EC_PCH_PWROK */
+/* NOTE: These two pins are reserved on this test board. */
+GPIO(USB_C1_CC1_VCONN_EN, PIN(K, 5), GPIO_INPUT | GPIO_PULL_DOWN) /* USB_C1_CC1_VCONN_EN */
+GPIO(USB_C1_CC2_VCONN_EN, PIN(K, 6), GPIO_INPUT | GPIO_PULL_DOWN) /* USB_C1_CC2_VCONN_EN */
/* EC_PCH_RTCRST is a sledgehammer for resetting SoC state and should rarely
* be used. Set as input for now, we'll set it as an output when we want to use
* it. Has external pull-down resistor. */
-GPIO(EC_PCH_RTCRST, PIN(B, 7), GPIO_INPUT)
-GPIO(PCH_RCIN_L, PIN(6, 1), GPIO_ODR_HIGH) /* SYS_RST_ODL */
-
-/* FIXME: What, if anything, to do about EC_RST_ODL on VCC1_RST#? */
-
-GPIO(CHARGER_RST_ODL, PIN(C, 0), GPIO_ODR_HIGH)
-GPIO(USB_A_CHARGE_EN_L, PIN(4, 2), GPIO_OUT_LOW)
-GPIO(EN_USB_TCPC_PWR, PIN(C, 3), GPIO_OUT_LOW)
-GPIO(USB1_ENABLE, PIN(4, 1), GPIO_OUT_LOW)
-
-GPIO(USB_C0_PD_RST_L, PIN(0, 3), GPIO_OUT_LOW) /* USB_C0_PD_RST_L */
-GPIO(USB_C1_PD_RST_ODL, PIN(7, 4), GPIO_ODR_LOW)
-
+GPIO(EC_PCH_RTCRST, PIN(K, 7), GPIO_INPUT) /* EC_PCH_RTCRST */
+GPIO(USB_A_CHARGE_EN_L, PIN(L, 0), GPIO_OUT_LOW) /* USB_A_CHARGE_EN_L */
+GPIO(USB1_ENABLE, PIN(L, 1), GPIO_OUT_LOW) /* EN_USB_A_5V */
/*
* Configure as input to enable @ 1.5A, output-low to turn off, or output-high
* to enable @ 3A.
*/
-GPIO(USB_C0_5V_EN, PIN(D, 3), GPIO_OUT_LOW | GPIO_PULL_UP) /* EN_USB_C0_5V_OUT, Enable C0 */
-GPIO(USB_C1_5V_EN, PIN(D, 2), GPIO_OUT_LOW | GPIO_PULL_UP) /* EN_USB_C1_5V_OUT, Enable C1 */
-
-/* Clear for non-HDI breakout, must be pulled high */
-GPIO(NC1, PIN(0, 0), GPIO_INPUT | GPIO_PULL_UP | GPIO_SEL_1P8V)
-GPIO(NC2, PIN(8, 4), GPIO_INPUT | GPIO_PULL_UP | GPIO_SEL_1P8V)
-
-GPIO(ENG_STRAP, PIN(B, 6), GPIO_INPUT)
-
-GPIO(BAT_LED_BLUE, PIN(8, 0), GPIO_OUT_HIGH)
-GPIO(BAT_LED_AMBER, PIN(C, 4), GPIO_OUT_HIGH)
+GPIO(USB_C0_5V_EN, PIN(L, 2), GPIO_OUT_LOW | GPIO_PULL_UP) /* EN_USB_C0_5V_OUT, Enable C0 */
+GPIO(USB_C1_5V_EN, PIN(L, 3), GPIO_OUT_LOW | GPIO_PULL_UP) /* EN_USB_C1_5V_OUT, Enable C1 */
+GPIO(BAT_LED_BLUE, PIN(L, 4), GPIO_OUT_HIGH) /* BLUE_PWR_LED */
+GPIO(BAT_LED_AMBER, PIN(L, 5), GPIO_OUT_HIGH) /* ORANGE_CHG_LED */
+GPIO(USB_C0_DISCHARGE, PIN(L, 6), GPIO_OUT_LOW) /* USB_C0_DISCHARGE */
+GPIO(USB_C1_DISCHARGE, PIN(L, 7), GPIO_OUT_LOW) /* USB_C1_DISCHARGE */
/*
* Alternate function pins
*/
-/* Keyboard pins */
-#define GPIO_KB_INPUT (GPIO_INPUT | GPIO_PULL_UP)
-#define GPIO_KB_OUTPUT (GPIO_ODR_HIGH)
-#define GPIO_KB_OUTPUT_COL2 (GPIO_OUT_LOW)
-ALTERNATE(PIN_MASK(3, 0x03), 0, MODULE_KEYBOARD_SCAN, GPIO_KB_INPUT)
-ALTERNATE(PIN_MASK(2, 0xfc), 0, MODULE_KEYBOARD_SCAN, GPIO_KB_INPUT)
-ALTERNATE(PIN_MASK(2, 0x03), 0, MODULE_KEYBOARD_SCAN, GPIO_KB_OUTPUT)
-ALTERNATE(PIN_MASK(0, 0xe0), 0, MODULE_KEYBOARD_SCAN, GPIO_KB_OUTPUT)
-ALTERNATE(PIN_MASK(1, 0x7f), 0, MODULE_KEYBOARD_SCAN, GPIO_KB_OUTPUT)
-GPIO(KBD_KSO2, PIN(1, 7), GPIO_KB_OUTPUT_COL2)
-
-ALTERNATE(PIN(4, 4), 6, MODULE_ADC, 0) /* TEMP_SENSOR_AMB (FIXME: alt function 6?) */
-ALTERNATE(PIN(4, 5), 6, MODULE_ADC, 0) /* TEMP_SENSOR_CHARGER (FIXME: alt function?) */
-
-ALTERNATE(PIN_MASK(8, 0x80), 1, MODULE_I2C, 0) /* GPIO87 for EC_I2C_GYRO_SDA */
-ALTERNATE(PIN_MASK(9, 0x01), 1, MODULE_I2C, 0) /* GPIO90 for EC_I2C_GYRO_SCL */
-ALTERNATE(PIN_MASK(9, 0x06), 1, MODULE_I2C, 0) /* GPIO92-91 for EC_I2C_SENSOR_SDA/SCL */
-ALTERNATE(PIN_MASK(B, 0x30), 1, MODULE_I2C, 0) /* GPIOB5-B4 for EC_I2C_USB_C0_PD_SDA/SCL */
-ALTERNATE(PIN_MASK(B, 0x0C), 1, MODULE_I2C, 0) /* GPOPB3-B2 for EC_I2C_USB_C1_PD_SDA/SCL */
-ALTERNATE(PIN_MASK(D, 0x03), 1, MODULE_I2C, 0) /* GPIOD1-D0 for EC_I2C_POWER_SDA/SCL */
-
-/* FIXME: Make UART RX an interrupt? */
-ALTERNATE(PIN_MASK(6, 0x30), 0, MODULE_UART, 0) /* UART from EC to Servo */
+ALTERNATE(PIN_MASK(B, 0x03), 1, MODULE_UART, GPIO_PULL_UP) /* UART1 */
+ALTERNATE(PIN_MASK(B, 0x18), 1, MODULE_I2C, 0) /* I2C A SCL/SDA */
+ALTERNATE(PIN_MASK(C, 0x06), 1, MODULE_I2C, 0) /* I2C B SCL/SDA */
+ALTERNATE(PIN_MASK(E, 0x81), 1, MODULE_I2C, 0) /* I2C E SCL/SDA */
+ALTERNATE(PIN_MASK(F, 0xC0), 1, MODULE_I2C, 0) /* I2C C SCL/SDA */
diff --git a/board/reef_it8320/led.c b/board/reef_it8320/led.c
index c25445afde..5c2c15482d 100644
--- a/board/reef_it8320/led.c
+++ b/board/reef_it8320/led.c
@@ -1,4 +1,4 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*
diff --git a/board/reef_it8320/usb_pd_policy.c b/board/reef_it8320/usb_pd_policy.c
index 0a22e0c36e..7985ed4176 100644
--- a/board/reef_it8320/usb_pd_policy.c
+++ b/board/reef_it8320/usb_pd_policy.c
@@ -1,4 +1,4 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
+/* Copyright 2017 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.
*/
@@ -67,18 +67,11 @@ int board_vbus_source_enabled(int port)
static void board_vbus_update_source_current(int port)
{
enum gpio_signal gpio = port ? GPIO_USB_C1_5V_EN : GPIO_USB_C0_5V_EN;
- int flags = (vbus_rp[port] == TYPEC_RP_1A5 && vbus_en[port]) ?
- (GPIO_INPUT | GPIO_PULL_UP) : (GPIO_OUTPUT | GPIO_PULL_UP);
+ enum gpio_signal gpio_3a_en = port ? GPIO_EN_USB_C1_3A :
+ GPIO_EN_USB_C0_3A;
- /*
- * Driving USB_Cx_5V_EN high, actually put a 16.5k resistance
- * (2x 33k in parallel) on the NX5P3290 load switch ILIM pin,
- * setting a minimum OCP current of 3186 mA.
- * Putting an internal pull-up on USB_Cx_5V_EN, effectively put a 33k
- * resistor on ILIM, setting a minimum OCP current of 1505 mA.
- */
+ gpio_set_level(gpio_3a_en, vbus_rp[port] == TYPEC_RP_3A0 ? 1 : 0);
gpio_set_level(gpio, vbus_en[port]);
- gpio_set_flags(gpio, flags);
}
void typec_set_source_current_limit(int port, int rp)
diff --git a/chip/it83xx/config_chip.h b/chip/it83xx/config_chip.h
index 6571d4fefe..58cfe37541 100644
--- a/chip/it83xx/config_chip.h
+++ b/chip/it83xx/config_chip.h
@@ -38,9 +38,10 @@
#define CONFIG_STACK_SIZE 1024
/* non-standard task stack sizes */
+#define SMALLER_TASK_STACK_SIZE 384
#define IDLE_TASK_STACK_SIZE 512
#define LARGER_TASK_STACK_SIZE 768
-#define SMALLER_TASK_STACK_SIZE 384
+#define VENTI_TASK_STACK_SIZE 896
/* Default task stack size */
#define TASK_STACK_SIZE 512
diff --git a/util/flash_ec b/util/flash_ec
index 93750aee1a..b8b3470e19 100755
--- a/util/flash_ec
+++ b/util/flash_ec
@@ -47,6 +47,7 @@ die() {
BOARDS_IT83XX=(
it83xx_evb
+ reef_it8320
)
BOARDS_LM4=(