summaryrefslogtreecommitdiff
path: root/board
diff options
context:
space:
mode:
Diffstat (limited to 'board')
-rw-r--r--board/nami/battery.c177
-rw-r--r--board/nami/board.c855
-rw-r--r--board/nami/board.h216
-rw-r--r--board/nami/build.mk3
-rw-r--r--board/nami/ec.tasklist14
-rw-r--r--board/nami/gpio.inc134
-rw-r--r--board/nami/led.c273
-rw-r--r--board/nami/usb_pd_policy.c202
8 files changed, 1056 insertions, 818 deletions
diff --git a/board/nami/battery.c b/board/nami/battery.c
new file mode 100644
index 0000000000..19a803af6d
--- /dev/null
+++ b/board/nami/battery.c
@@ -0,0 +1,177 @@
+/* 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.
+ *
+ * Placeholder values for temporary battery pack.
+ */
+
+#include "battery.h"
+#include "battery_smart.h"
+#include "charge_state.h"
+#include "console.h"
+#include "ec_commands.h"
+#include "extpower.h"
+#include "gpio.h"
+#include "util.h"
+
+static enum battery_present batt_pres_prev = BP_NOT_SURE;
+
+/*
+ * TODO(philipchen): Check if these parameters are valid for Nautilus battery.
+ *
+ * Shutdown mode parameter to write to manufacturer access register
+ */
+#define SB_SHIP_MODE_REG SB_MANUFACTURER_ACCESS
+#define SB_SHUTDOWN_DATA 0x0010
+
+static const struct battery_info info = {
+ .voltage_max = 8700,
+ .voltage_normal = 7700,
+ .voltage_min = 6000,
+ /* Pre-charge values. */
+ .precharge_current = 152, /* mA */
+
+ .start_charging_min_c = 0,
+ .start_charging_max_c = 45,
+ .charging_min_c = 0,
+ .charging_max_c = 50,
+ .discharging_min_c = -20,
+ .discharging_max_c = 60,
+};
+
+const struct battery_info *battery_get_info(void)
+{
+ return &info;
+}
+
+int board_cut_off_battery(void)
+{
+ int rv;
+
+ /* Ship mode command must be sent twice to take effect */
+ rv = sb_write(SB_SHIP_MODE_REG, SB_SHUTDOWN_DATA);
+
+ if (rv != EC_SUCCESS)
+ return rv;
+
+ return sb_write(SB_SHIP_MODE_REG, SB_SHUTDOWN_DATA);
+}
+
+int charger_profile_override(struct charge_state_data *curr)
+{
+ const struct battery_info *batt_info;
+ int bat_temp_c;
+
+ batt_info = battery_get_info();
+
+ if ((curr->batt.flags & BATT_FLAG_BAD_ANY) == BATT_FLAG_BAD_ANY) {
+ curr->requested_current = batt_info->precharge_current;
+ curr->requested_voltage = batt_info->voltage_max;
+ return 1000;
+ }
+
+ /* battery temp in 0.1 deg C */
+ bat_temp_c = curr->batt.temperature - 2731;
+
+ /* Don't charge if outside of allowable temperature range */
+ if (bat_temp_c >= batt_info->charging_max_c * 10 ||
+ bat_temp_c < batt_info->charging_min_c * 10) {
+ curr->requested_current = 0;
+ curr->requested_voltage = 0;
+ curr->batt.flags &= ~BATT_FLAG_WANT_CHARGE;
+ curr->state = ST_IDLE;
+ }
+ return 0;
+}
+
+/* Customs options controllable by host command. */
+#define PARAM_FASTCHARGE (CS_PARAM_CUSTOM_PROFILE_MIN + 0)
+
+enum ec_status charger_profile_override_get_param(uint32_t param,
+ uint32_t *value)
+{
+ return EC_RES_INVALID_PARAM;
+}
+
+enum ec_status charger_profile_override_set_param(uint32_t param,
+ uint32_t value)
+{
+ return EC_RES_INVALID_PARAM;
+}
+
+enum battery_present battery_hw_present(void)
+{
+ /* The GPIO is low when the battery is physically present */
+ return gpio_get_level(GPIO_BATTERY_PRESENT_L) ? BP_NO : BP_YES;
+}
+
+static int battery_init(void)
+{
+ int batt_status;
+
+ return battery_status(&batt_status) ? 0 :
+ !!(batt_status & STATUS_INITIALIZED);
+}
+
+/*
+ * Check for case where both XCHG and XDSG bits are set indicating that even
+ * though the FG can be read from the battery, the battery is not able to be
+ * charged or discharged. This situation will happen if a battery disconnect was
+ * intiaited via H1 setting the DISCONN signal to the battery. This will put the
+ * battery pack into a sleep state and when power is reconnected, the FG can be
+ * read, but the battery is still not able to provide power to the system. The
+ * calling function returns batt_pres = BP_NO, which instructs the charging
+ * state machine to prevent powering up the AP on battery alone which could lead
+ * to a brownout event when the battery isn't able yet to provide power to the
+ * system. .
+ */
+static int battery_check_disconnect(void)
+{
+ int rv;
+ uint8_t data[6];
+
+ /* Check if battery charging + discharging is disabled. */
+ rv = sb_read_mfgacc(PARAM_OPERATION_STATUS,
+ SB_ALT_MANUFACTURER_ACCESS, data, sizeof(data));
+ if (rv)
+ return BATTERY_DISCONNECT_ERROR;
+
+ /* TODO(philipchen): Verify if Nautilus battery supports this check. */
+ if ((data[3] & (BATTERY_DISCHARGING_DISABLED |
+ BATTERY_CHARGING_DISABLED)) ==
+ (BATTERY_DISCHARGING_DISABLED | BATTERY_CHARGING_DISABLED))
+ return BATTERY_DISCONNECTED;
+
+ return BATTERY_NOT_DISCONNECTED;
+}
+
+enum battery_present battery_is_present(void)
+{
+ enum battery_present batt_pres;
+
+ /* Get the physical hardware status */
+ batt_pres = battery_hw_present();
+
+ /*
+ * Make sure battery status is implemented, I2C transactions are
+ * success & the battery status is Initialized to find out if it
+ * is a working battery and it is not in the cut-off mode.
+ *
+ * If battery I2C fails but VBATT is high, battery is booting from
+ * cut-off mode.
+ *
+ * FETs are turned off after Power Shutdown time.
+ * The device will wake up when a voltage is applied to PACK.
+ * Battery status will be inactive until it is initialized.
+ */
+ if (batt_pres == BP_YES && batt_pres_prev != batt_pres &&
+ (battery_is_cut_off() != BATTERY_CUTOFF_STATE_NORMAL ||
+ battery_check_disconnect() != BATTERY_NOT_DISCONNECTED ||
+ battery_init() == 0)) {
+ batt_pres = BP_NO;
+ }
+
+ batt_pres_prev = batt_pres;
+ return batt_pres;
+}
+
diff --git a/board/nami/board.c b/board/nami/board.c
index 08335ad6b3..165a5b9597 100644
--- a/board/nami/board.c
+++ b/board/nami/board.c
@@ -3,43 +3,43 @@
* found in the LICENSE file.
*/
-/* Fizz board-specific configuration */
+/* Poppy board-specific configuration */
#include "adc.h"
#include "adc_chip.h"
-#include "als.h"
-#include "battery.h"
#include "bd99992gw.h"
#include "board_config.h"
#include "button.h"
#include "charge_manager.h"
#include "charge_state.h"
+#include "charge_ramp.h"
#include "charger.h"
#include "chipset.h"
#include "console.h"
-#include "driver/pmic_tps650x30.h"
-#include "driver/temp_sensor/tmp432.h"
+#include "driver/accelgyro_bmi160.h"
+#include "driver/accel_bma2x2.h"
+#include "driver/baro_bmp280.h"
#include "driver/tcpm/ps8xxx.h"
#include "driver/tcpm/tcpci.h"
#include "driver/tcpm/tcpm.h"
-#include "espi.h"
+#include "driver/temp_sensor/bd99992gw.h"
#include "extpower.h"
-#include "espi.h"
-#include "fan.h"
-#include "fan_chip.h"
#include "gpio.h"
#include "hooks.h"
#include "host_command.h"
#include "i2c.h"
+#include "keyboard_scan.h"
+#include "lid_switch.h"
#include "math_util.h"
+#include "motion_lid.h"
+#include "motion_sense.h"
#include "pi3usb9281.h"
#include "power.h"
#include "power_button.h"
-#include "pwm.h"
-#include "pwm_chip.h"
#include "spi.h"
#include "switch.h"
#include "system.h"
+#include "tablet_mode.h"
#include "task.h"
#include "temp_sensor.h"
#include "timer.h"
@@ -49,13 +49,18 @@
#include "usb_pd.h"
#include "usb_pd_tcpm.h"
#include "util.h"
+#include "espi.h"
#define CPRINTS(format, args...) cprints(CC_USBCHARGE, format, ## args)
#define CPRINTF(format, args...) cprintf(CC_USBCHARGE, format, ## args)
static void tcpc_alert_event(enum gpio_signal signal)
{
- if (!gpio_get_level(GPIO_USB_C0_PD_RST_ODL))
+ if ((signal == GPIO_USB_C0_PD_INT_ODL) &&
+ !gpio_get_level(GPIO_USB_C0_PD_RST_L))
+ return;
+ else if ((signal == GPIO_USB_C1_PD_INT_ODL) &&
+ !gpio_get_level(GPIO_USB_C1_PD_RST_L))
return;
#ifdef HAS_TASK_PDCMD
@@ -64,72 +69,55 @@ static void tcpc_alert_event(enum gpio_signal signal)
#endif
}
-#define ADP_DEBOUNCE_MS 1000 /* Debounce time for BJ plug/unplug */
-/*
- * ADP_IN pin state. It's initialized to 1 (=unplugged) because the IRQ won't
- * be triggered if BJ is the power source.
- */
-static int adp_in_state = 1;
+/* Set PD discharge whenever VBUS detection is high (i.e. below threshold). */
+static void vbus_discharge_handler(void)
+{
+ if (system_get_board_version() >= 2) {
+ pd_set_vbus_discharge(0,
+ gpio_get_level(GPIO_USB_C0_VBUS_WAKE_L));
+ pd_set_vbus_discharge(1,
+ gpio_get_level(GPIO_USB_C1_VBUS_WAKE_L));
+ }
+}
+DECLARE_DEFERRED(vbus_discharge_handler);
-static void adp_in_deferred(void);
-DECLARE_DEFERRED(adp_in_deferred);
-static void adp_in_deferred(void)
+void vbus0_evt(enum gpio_signal signal)
{
- struct charge_port_info pi = { 0 };
- int level = gpio_get_level(GPIO_ADP_IN_L);
+ /* VBUS present GPIO is inverted */
+ usb_charger_vbus_change(0, !gpio_get_level(signal));
+ task_wake(TASK_ID_PD_C0);
- /* Debounce */
- if (level == adp_in_state)
- return;
- if (!level) {
- /* BJ is inserted but the voltage isn't effective because PU3
- * is still disabled. */
- pi.voltage = 19000;
- if (chipset_in_state(CHIPSET_STATE_ANY_OFF)) {
- /* If type-c voltage is higher than BJ voltage, PU3 will
- * shut down due to reverse current protection. So, we
- * need to lower the voltage first. */
- if (charge_manager_get_charger_voltage() > pi.voltage) {
- pd_set_external_voltage_limit(
- CHARGE_PORT_TYPEC0, pi.voltage);
- hook_call_deferred(&adp_in_deferred_data,
- ADP_DEBOUNCE_MS * MSEC);
- return;
- }
- if (gpio_get_level(GPIO_POWER_RATE))
- pi.current = 4620;
- else
- pi.current = 3330;
- }
- }
- charge_manager_update_charge(CHARGE_SUPPLIER_DEDICATED,
- DEDICATED_CHARGE_PORT, &pi);
- /*
- * Explicitly notifies the host that BJ is plugged or unplugged
- * (when running on a type-c adapter).
- */
- pd_send_host_event(PD_EVENT_POWER_CHANGE);
- adp_in_state = level;
+ hook_call_deferred(&vbus_discharge_handler_data, 0);
}
-/* IRQ for BJ plug/unplug. It shouldn't be called if BJ is the power source. */
-void adp_in(enum gpio_signal signal)
+void vbus1_evt(enum gpio_signal signal)
{
- if (adp_in_state == gpio_get_level(GPIO_ADP_IN_L))
- return;
- hook_call_deferred(&adp_in_deferred_data, ADP_DEBOUNCE_MS * MSEC);
+ /* VBUS present GPIO is inverted */
+ usb_charger_vbus_change(1, !gpio_get_level(signal));
+ task_wake(TASK_ID_PD_C1);
+
+ hook_call_deferred(&vbus_discharge_handler_data, 0);
}
-void vbus0_evt(enum gpio_signal signal)
+void usb0_evt(enum gpio_signal signal)
{
- task_wake(TASK_ID_PD_C0);
+ task_set_event(TASK_ID_USB_CHG_P0, USB_CHG_EVENT_BC12, 0);
+}
+
+void usb1_evt(enum gpio_signal signal)
+{
+ task_set_event(TASK_ID_USB_CHG_P1, USB_CHG_EVENT_BC12, 0);
}
#include "gpio_list.h"
/* power signal list. Must match order of enum power_signal. */
const struct power_signal_info power_signal_list[] = {
- {GPIO_PCH_SLP_S0_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_S0_DEASSERTED"},
+#ifdef CONFIG_POWER_S0IX
+ {GPIO_PCH_SLP_S0_L,
+ POWER_SIGNAL_ACTIVE_HIGH | POWER_SIGNAL_DISABLE_AT_BOOT,
+ "SLP_S0_DEASSERTED"},
+#endif
#ifdef CONFIG_ESPI_VW_SIGNALS
{VW_SLP_S3_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_S3_DEASSERTED"},
{VW_SLP_S4_L, POWER_SIGNAL_ACTIVE_HIGH, "SLP_S4_DEASSERTED"},
@@ -145,13 +133,17 @@ BUILD_ASSERT(ARRAY_SIZE(power_signal_list) == POWER_SIGNAL_COUNT);
/* Hibernate wake configuration */
const enum gpio_signal hibernate_wake_pins[] = {
+ GPIO_AC_PRESENT,
GPIO_POWER_BUTTON_L,
};
const int hibernate_wake_pins_used = ARRAY_SIZE(hibernate_wake_pins);
/* ADC channels */
const struct adc_t adc_channels[] = {
- /* Vbus sensing (1/10 voltage divider). */
+ /* Base detection */
+ [ADC_BASE_DET] = {"BASE_DET", NPCX_ADC_CH0,
+ ADC_MAX_VOLT, ADC_READ_MAX+1, 0},
+ /* Vbus sensing (10x voltage divider). */
[ADC_VBUS] = {"VBUS", NPCX_ADC_CH2, ADC_MAX_VOLT*10, ADC_READ_MAX+1, 0},
/*
* Adapter current output or battery charging/discharging current (uV)
@@ -162,42 +154,20 @@ const struct adc_t adc_channels[] = {
};
BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
-/******************************************************************************/
-/* Physical fans. These are logically separate from pwm_channels. */
-const struct fan_t fans[] = {
- [FAN_CH_0] = {
- .flags = FAN_USE_RPM_MODE,
- .rpm_min = 2800,
- .rpm_start = 2800,
- .rpm_max = 5600,
- .ch = MFT_CH_0, /* Use MFT id to control fan */
- .pgood_gpio = -1,
- .enable_gpio = GPIO_FAN_PWR_EN,
- },
-};
-BUILD_ASSERT(ARRAY_SIZE(fans) == FAN_CH_COUNT);
-
-/******************************************************************************/
-/* MFT channels. These are logically separate from pwm_channels. */
-const struct mft_t mft_channels[] = {
- [MFT_CH_0] = {NPCX_MFT_MODULE_2, TCKC_LFCLK, PWM_CH_FAN},
-};
-BUILD_ASSERT(ARRAY_SIZE(mft_channels) == MFT_CH_COUNT);
-
/* I2C port map */
const struct i2c_port_t i2c_ports[] = {
- {"tcpc", NPCX_I2C_PORT0_0, 400, GPIO_I2C0_0_SCL, GPIO_I2C0_0_SDA},
- {"eeprom", NPCX_I2C_PORT0_1, 400, GPIO_I2C0_1_SCL, GPIO_I2C0_1_SDA},
- {"charger", NPCX_I2C_PORT1, 100, GPIO_I2C1_SCL, GPIO_I2C1_SDA},
- {"pmic", NPCX_I2C_PORT2, 400, GPIO_I2C2_SCL, GPIO_I2C2_SDA},
- {"thermal", NPCX_I2C_PORT3, 400, GPIO_I2C3_SCL, GPIO_I2C3_SDA},
+ {"tcpc0", NPCX_I2C_PORT0_0, 400, GPIO_I2C0_0_SCL, GPIO_I2C0_0_SDA},
+ {"tcpc1", NPCX_I2C_PORT0_1, 400, GPIO_I2C0_1_SCL, GPIO_I2C0_1_SDA},
+ {"charger", NPCX_I2C_PORT1, 100, GPIO_I2C1_SCL, GPIO_I2C1_SDA},
+ {"pmic", NPCX_I2C_PORT2, 400, GPIO_I2C2_SCL, GPIO_I2C2_SDA},
+ {"accelgyro", NPCX_I2C_PORT3, 400, GPIO_I2C3_SCL, GPIO_I2C3_SDA},
};
const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
/* TCPC mux configuration */
const struct tcpc_config_t tcpc_config[CONFIG_USB_PD_PORT_COUNT] = {
- {NPCX_I2C_PORT0_0, I2C_ADDR_TCPC0, &ps8xxx_tcpm_drv,
- TCPC_ALERT_ACTIVE_LOW},
+ {NPCX_I2C_PORT0_0, 0x16, &ps8xxx_tcpm_drv, TCPC_ALERT_ACTIVE_LOW},
+ {NPCX_I2C_PORT0_1, 0x16, &ps8xxx_tcpm_drv, TCPC_ALERT_ACTIVE_LOW},
};
struct usb_mux usb_muxes[CONFIG_USB_PD_PORT_COUNT] = {
@@ -205,46 +175,49 @@ struct usb_mux usb_muxes[CONFIG_USB_PD_PORT_COUNT] = {
.port_addr = 0,
.driver = &tcpci_tcpm_usb_mux_driver,
.hpd_update = &ps8xxx_tcpc_update_hpd_status,
+ },
+ {
+ .port_addr = 1,
+ .driver = &tcpci_tcpm_usb_mux_driver,
+ .hpd_update = &ps8xxx_tcpc_update_hpd_status,
}
};
-const int usb_port_enable[USB_PORT_COUNT] = {
- GPIO_USB1_ENABLE,
- GPIO_USB2_ENABLE,
- GPIO_USB3_ENABLE,
- GPIO_USB4_ENABLE,
- GPIO_USB5_ENABLE,
+struct pi3usb9281_config pi3usb9281_chips[] = {
+ {
+ .i2c_port = I2C_PORT_USB_CHARGER_0,
+ .mux_lock = NULL,
+ },
+ {
+ .i2c_port = I2C_PORT_USB_CHARGER_1,
+ .mux_lock = NULL,
+ },
};
+BUILD_ASSERT(ARRAY_SIZE(pi3usb9281_chips) ==
+ CONFIG_BC12_DETECT_PI3USB9281_CHIP_COUNT);
void board_reset_pd_mcu(void)
{
- gpio_set_level(GPIO_USB_C0_PD_RST_ODL, 0);
+ /* Assert reset */
+ gpio_set_level(GPIO_USB_C0_PD_RST_L, 0);
+ gpio_set_level(GPIO_USB_C1_PD_RST_L, 0);
msleep(1);
- gpio_set_level(GPIO_USB_C0_PD_RST_ODL, 1);
+ gpio_set_level(GPIO_USB_C0_PD_RST_L, 1);
+ gpio_set_level(GPIO_USB_C1_PD_RST_L, 1);
}
void board_tcpc_init(void)
{
- int port, reg;
+ int port;
/* Only reset TCPC if not sysjump */
if (!system_jumped_to_this_image()) {
- /* Power on PS8751 */
- gpio_set_level(GPIO_PP3300_USB_PD, 1);
- /* TODO(crosbug.com/p/61098): How long do we need to wait? */
- msleep(10);
board_reset_pd_mcu();
}
- /*
- * Wake up PS8751. 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(I2C_PORT_TCPC0, I2C_ADDR_TCPC0, 0xA0, &reg);
-
/* Enable TCPC interrupts */
gpio_enable_interrupt(GPIO_USB_C0_PD_INT_ODL);
+ gpio_enable_interrupt(GPIO_USB_C1_PD_INT_ODL);
/*
* Initialize HPD to low; after sysjump SOC needs to see
@@ -252,6 +225,7 @@ void board_tcpc_init(void)
*/
for (port = 0; port < CONFIG_USB_PD_PORT_COUNT; port++) {
const struct usb_mux *mux = &usb_muxes[port];
+
mux->hpd_update(port, 0, 0);
}
}
@@ -262,330 +236,515 @@ uint16_t tcpc_get_alert_status(void)
uint16_t status = 0;
if (!gpio_get_level(GPIO_USB_C0_PD_INT_ODL)) {
- if (gpio_get_level(GPIO_USB_C0_PD_RST_ODL))
+ if (gpio_get_level(GPIO_USB_C0_PD_RST_L))
status |= PD_STATUS_TCPC_ALERT_0;
}
+ if (!gpio_get_level(GPIO_USB_C1_PD_INT_ODL)) {
+ if (gpio_get_level(GPIO_USB_C1_PD_RST_L))
+ status |= PD_STATUS_TCPC_ALERT_1;
+ }
+
return status;
}
-/*
- * Temperature sensors data; must be in same order as enum temp_sensor_id.
- * Sensor index and name must match those present in coreboot:
- * src/mainboard/google/${board}/acpi/dptf.asl
- */
const struct temp_sensor_t temp_sensors[] = {
- {"TMP432_Internal", TEMP_SENSOR_TYPE_BOARD, tmp432_get_val,
- TMP432_IDX_LOCAL, 4},
- {"TMP432_Sensor_1", TEMP_SENSOR_TYPE_BOARD, tmp432_get_val,
- TMP432_IDX_REMOTE1, 4},
- {"TMP432_Sensor_2", TEMP_SENSOR_TYPE_BOARD, tmp432_get_val,
- TMP432_IDX_REMOTE2, 4},
+ {"Battery", TEMP_SENSOR_TYPE_BATTERY, charge_get_battery_temp, 0, 4},
+
+ /* These BD99992GW temp sensors are only readable in S0 */
+ {"Charger", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM1, 4},
+ {"DRAM", TEMP_SENSOR_TYPE_BOARD, bd99992gw_get_val,
+ BD99992GW_ADC_CHANNEL_SYSTHERM2, 4},
};
BUILD_ASSERT(ARRAY_SIZE(temp_sensors) == TEMP_SENSOR_COUNT);
/*
- * Thermal limits for each temp sensor. All temps are in degrees K. Must be in
- * same order as enum temp_sensor_id. To always ignore any temp, use 0.
+ * Check if PMIC fault registers indicate VR fault. If yes, print out fault
+ * register info to console. Additionally, set panic reason so that the OS can
+ * check for fault register info by looking at offset 0x14(PWRSTAT1) and
+ * 0x15(PWRSTAT2) in cros ec panicinfo.
*/
-struct ec_thermal_config thermal_params[] = {
- /* {Twarn, Thigh, Thalt}, <on>
- * {Twarn, Thigh, X }, <off>
- * fan_off, fan_max
- */
- {{0, C_TO_K(87), C_TO_K(89)}, {0, C_TO_K(86), 0},
- C_TO_K(44), C_TO_K(81)},/* TMP432_Internal */
- {{0, 0, 0}, {0, 0, 0}, 0, 0}, /* TMP432_Sensor_1 */
- {{0, 0, 0}, {0, 0, 0}, 0, 0}, /* TMP432_Sensor_2 */
-};
-BUILD_ASSERT(ARRAY_SIZE(thermal_params) == TEMP_SENSOR_COUNT);
+static void board_report_pmic_fault(const char *str)
+{
+ int vrfault, pwrstat1 = 0, pwrstat2 = 0;
+ uint32_t info;
-/* Initialize PMIC */
-#define I2C_PMIC_READ(reg, data) \
- i2c_read8(I2C_PORT_PMIC, TPS650X30_I2C_ADDR1, (reg), (data))
+ /* RESETIRQ1 -- Bit 4: VRFAULT */
+ if (i2c_read8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x8, &vrfault)
+ != EC_SUCCESS)
+ return;
-#define I2C_PMIC_WRITE(reg, data) \
- i2c_write8(I2C_PORT_PMIC, TPS650X30_I2C_ADDR1, (reg), (data))
+ if (!(vrfault & (1 << 4)))
+ return;
-static void board_pmic_init(void)
-{
- int err;
- int error_count = 0;
- static uint8_t pmic_initialized = 0;
+ /* VRFAULT has occurred, print VRFAULT status bits. */
- if (pmic_initialized)
- return;
+ /* PWRSTAT1 */
+ i2c_read8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x16, &pwrstat1);
- /* Read vendor ID */
- while (1) {
- int data;
- err = I2C_PMIC_READ(TPS650X30_REG_VENDORID, &data);
- if (!err && data == TPS650X30_VENDOR_ID)
- break;
- else if (error_count > 5)
- goto pmic_error;
- error_count++;
- }
+ /* PWRSTAT2 */
+ i2c_read8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x17, &pwrstat2);
- /*
- * VCCIOCNT register setting
- * [6] : CSDECAYEN
- * otherbits: default
- */
- err = I2C_PMIC_WRITE(TPS650X30_REG_VCCIOCNT, 0x4A);
- if (err)
- goto pmic_error;
+ CPRINTS("PMIC VRFAULT: %s", str);
+ CPRINTS("PMIC VRFAULT: PWRSTAT1=0x%02x PWRSTAT2=0x%02x", pwrstat1,
+ pwrstat2);
+
+ /* Clear all faults -- Write 1 to clear. */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x8, (1 << 4));
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x16, pwrstat1);
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x17, pwrstat2);
/*
- * VRMODECTRL:
- * [4] : VCCIOLPM clear
- * otherbits: default
+ * Status of the fault registers can be checked in the OS by looking at
+ * offset 0x14(PWRSTAT1) and 0x15(PWRSTAT2) in cros ec panicinfo.
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_VRMODECTRL, 0x2F);
- if (err)
- goto pmic_error;
+ info = ((pwrstat2 & 0xFF) << 8) | (pwrstat1 & 0xFF);
+ panic_set_reason(PANIC_SW_PMIC_FAULT, info, 0);
+}
+static void board_pmic_disable_slp_s0_vr_decay(void)
+{
/*
- * PGMASK1 : Exclude VCCIO from Power Good Tree
- * [7] : MVCCIOPG clear
- * otherbits: default
+ * VCCIOCNT:
+ * Bit 6 (0) - Disable decay of VCCIO on SLP_S0# assertion
+ * Bits 5:4 (00) - Nominal output voltage: 0.975V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_PGMASK1, 0x80);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x30, 0xa);
/*
- * PWFAULT_MASK1 Register settings
- * [7] : 1b V4 Power Fault Masked
- * [4] : 1b V7 Power Fault Masked
- * [2] : 1b V9 Power Fault Masked
- * [0] : 1b V13 Power Fault Masked
+ * V18ACNT:
+ * Bits 7:6 (00) - Disable low power mode on SLP_S0# assertion
+ * Bits 5:4 (10) - Nominal voltage set to 1.8V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_PWFAULT_MASK1, 0x95);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x34, 0x2a);
/*
- * Discharge control 4 register configuration
- * [7:6] : 00b Reserved
- * [5:4] : 01b V3.3S discharge resistance (V6S), 100 Ohm
- * [3:2] : 01b V18S discharge resistance (V8S), 100 Ohm
- * [1:0] : 01b V100S discharge resistance (V11S), 100 Ohm
+ * V100ACNT:
+ * Bits 7:6 (00) - Disable low power mode on SLP_S0# assertion
+ * Bits 5:4 (01) - Nominal voltage 1.0V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_DISCHCNT4, 0x15);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x37, 0x1a);
/*
- * Discharge control 3 register configuration
- * [7:6] : 01b V1.8U_2.5U discharge resistance (V9), 100 Ohm
- * [5:4] : 01b V1.2U discharge resistance (V10), 100 Ohm
- * [3:2] : 01b V100A discharge resistance (V11), 100 Ohm
- * [1:0] : 01b V085A discharge resistance (V12), 100 Ohm
+ * V085ACNT:
+ * Bits 7:6 (00) - Disable low power mode on SLP_S0# assertion
+ * Bits 5:4 (11) - Nominal voltage 1.0V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_DISCHCNT3, 0x55);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x38, 0x3a);
+}
+static void board_pmic_enable_slp_s0_vr_decay(void)
+{
/*
- * Discharge control 2 register configuration
- * [7:6] : 01b V5ADS3 discharge resistance (V5), 100 Ohm
- * [5:4] : 01b V33A_DSW discharge resistance (V6), 100 Ohm
- * [3:2] : 01b V33PCH discharge resistance (V7), 100 Ohm
- * [1:0] : 01b V18A discharge resistance (V8), 100 Ohm
+ * VCCIOCNT:
+ * Bit 6 (1) - Enable decay of VCCIO on SLP_S0# assertion
+ * Bits 5:4 (00) - Nominal output voltage: 0.975V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_DISCHCNT2, 0x55);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x30, 0x4a);
/*
- * Discharge control 1 register configuration
- * [7:2] : 00b Reserved
- * [1:0] : 01b VCCIO discharge resistance (V4), 100 Ohm
+ * V18ACNT:
+ * Bits 7:6 (01) - Enable low power mode on SLP_S0# assertion
+ * Bits 5:4 (10) - Nominal voltage set to 1.8V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_DISCHCNT1, 0x01);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x34, 0x6a);
/*
- * Increase Voltage
- * [7:0] : 0x2a default
- * [5:4] : 10b default
- * [5:4] : 01b 5.1V (0x1a)
+ * V100ACNT:
+ * Bits 7:6 (01) - Enable low power mode on SLP_S0# assertion
+ * Bits 5:4 (01) - Nominal voltage 1.0V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_V5ADS3CNT, 0x1a);
- if (err)
- goto pmic_error;
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x37, 0x5a);
/*
- * PBCONFIG Register configuration
- * [7] : 1b Power button debounce, 0ms (no debounce)
- * [6] : 0b Power button reset timer logic, no action (default)
- * [5:0] : 011111b Force an Emergency reset time, 31s (default)
+ * V085ACNT:
+ * Bits 7:6 (01) - Enable low power mode on SLP_S0# assertion
+ * Bits 5:4 (11) - Nominal voltage 1.0V
+ * Bits 3:2 (10) - VR set to AUTO on SLP_S0# de-assertion
+ * Bits 1:0 (10) - VR set to AUTO operating mode
*/
- err = I2C_PMIC_WRITE(TPS650X30_REG_PBCONFIG, 0x9F);
- if (err)
- goto pmic_error;
-
- CPRINTS("PMIC init done");
- pmic_initialized = 1;
- return;
-
-pmic_error:
- CPRINTS("PMIC init failed");
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x38, 0x7a);
}
-static void chipset_pre_init(void)
+void power_board_handle_host_sleep_event(enum host_sleep_event state)
{
- board_pmic_init();
+ if (state == HOST_SLEEP_EVENT_S0IX_SUSPEND)
+ board_pmic_enable_slp_s0_vr_decay();
+ else if (state == HOST_SLEEP_EVENT_S0IX_RESUME)
+ board_pmic_disable_slp_s0_vr_decay();
}
-DECLARE_HOOK(HOOK_CHIPSET_PRE_INIT, chipset_pre_init, HOOK_PRIO_DEFAULT);
-/**
- * Notify the AC presence GPIO to the PCH.
- */
-static void board_extpower(void)
+static void board_pmic_init(void)
{
- gpio_set_level(GPIO_PCH_ACPRESENT, extpower_is_present());
+ board_report_pmic_fault("SYSJUMP");
+
+ if (system_jumped_to_this_image())
+ return;
+
+ /* DISCHGCNT3 - enable 100 ohm discharge on V1.00A */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x3e, 0x04);
+
+ board_pmic_disable_slp_s0_vr_decay();
+
+ /* VRMODECTRL - disable low-power mode for all rails */
+ i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x3b, 0x1f);
}
-DECLARE_HOOK(HOOK_AC_CHANGE, board_extpower, HOOK_PRIO_DEFAULT);
+DECLARE_HOOK(HOOK_INIT, board_pmic_init, HOOK_PRIO_DEFAULT);
/* Initialize board. */
static void board_init(void)
{
+ /*
+ * This enables pull-down on F_DIO1 (SPI MISO), and F_DIO0 (SPI MOSI),
+ * whenever the EC is not doing SPI flash transactions. This avoids
+ * floating SPI buffer input (MISO), which causes power leakage (see
+ * b/64797021).
+ */
+ NPCX_PUPD_EN1 |= (1 << NPCX_DEVPU1_F_SPI_PUD_EN);
+
/* Provide AC status to the PCH */
- board_extpower();
+ gpio_set_level(GPIO_PCH_ACOK, extpower_is_present());
+ /* Enable sensors power supply */
+ gpio_set_level(GPIO_PP1800_DX_SENSOR, 1);
+
+ /* Enable VBUS interrupt */
gpio_enable_interrupt(GPIO_USB_C0_VBUS_WAKE_L);
+ gpio_enable_interrupt(GPIO_USB_C1_VBUS_WAKE_L);
+
+ /* Enable pericom BC1.2 interrupts */
+ gpio_enable_interrupt(GPIO_USB_C0_BC12_INT_L);
+ gpio_enable_interrupt(GPIO_USB_C1_BC12_INT_L);
+
+ /* Level of sensor's I2C and interrupt are 3.3V on proto board */
+ if(system_get_board_version() < 2) {
+ /* ACCELGYRO3_INT_L */
+ gpio_set_flags(GPIO_ACCELGYRO3_INT_L, GPIO_INT_FALLING);
+ /* I2C3_SCL / I2C3_SDA */
+ gpio_set_flags(GPIO_I2C3_SCL, GPIO_INPUT);
+ gpio_set_flags(GPIO_I2C3_SDA, GPIO_INPUT);
+ }
}
DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);
-void board_set_charge_limit(int port, int supplier, int charge_ma,
- int max_ma, int charge_mv)
+/**
+ * Buffer the AC present GPIO to the PCH.
+ */
+static void board_extpower(void)
{
- /* Turn on/off power shortage alert. Performs the same check as
- * system_can_boot_ap(). It's repeated here because charge_manager
- * hasn't updated charge_current/voltage when board_set_charge_limit
- * is called. */
- led_alert(charge_ma * charge_mv <
- CONFIG_CHARGER_LIMIT_POWER_THRESH_CHG_MW * 1000);
+ gpio_set_level(GPIO_PCH_ACOK, extpower_is_present());
+}
+DECLARE_HOOK(HOOK_AC_CHANGE, board_extpower, HOOK_PRIO_DEFAULT);
- /*
- * We have two FETs connected to two registers: PR257 & PR258.
- * These control thresholds of the over current monitoring system.
- *
- * PR257, PR258
- * For 4.62A (90W BJ adapter), on, off
- * For 3.33A (65W BJ adapter), off, on
- * For 3.00A (Type-C adapter), off, off
- *
- * The over current monitoring system doesn't support less than 3A
- * (e.g. 2.25A, 2.00A). These current most likely won't be enough to
- * power the system. However, if they're needed, EC can monitor
- * PMON_PSYS and trigger H_PROCHOT by itself.
- */
- if (charge_ma >= 4620) {
- gpio_set_level(GPIO_U42_P, 1);
- gpio_set_level(GPIO_U22_C, 0);
- } else if (charge_ma >= 3330) {
- gpio_set_level(GPIO_U42_P, 0);
- gpio_set_level(GPIO_U22_C, 1);
- } else if (charge_ma >= 3000) {
- gpio_set_level(GPIO_U42_P, 0);
- gpio_set_level(GPIO_U22_C, 0);
+/**
+ * Set active charge port -- only one port can be active at a time.
+ *
+ * @param charge_port Charge port to enable.
+ *
+ * Returns EC_SUCCESS if charge port is accepted and made active,
+ * EC_ERROR_* otherwise.
+ */
+int board_set_active_charge_port(int charge_port)
+{
+ /* charge port is a physical port */
+ int is_real_port = (charge_port >= 0 &&
+ charge_port < CONFIG_USB_PD_PORT_COUNT);
+ /* check if we are source VBUS on the port */
+ int source = gpio_get_level(charge_port == 0 ? GPIO_USB_C0_5V_EN :
+ GPIO_USB_C1_5V_EN);
+
+ if (is_real_port && source) {
+ CPRINTF("Skip enable p%d", charge_port);
+ return EC_ERROR_INVAL;
+ }
+
+ CPRINTF("New chg p%d", charge_port);
+
+ if (charge_port == CHARGE_PORT_NONE) {
+ /* Disable both ports */
+ gpio_set_level(GPIO_USB_C0_CHARGE_L, 1);
+ gpio_set_level(GPIO_USB_C1_CHARGE_L, 1);
} else {
- /* TODO(http://crosbug.com/p/65013352) */
- CPRINTS("Current %dmA not supported", charge_ma);
+ /* Make sure non-charging port is disabled */
+ gpio_set_level(charge_port ? GPIO_USB_C0_CHARGE_L :
+ GPIO_USB_C1_CHARGE_L, 1);
+ /* Enable charging port */
+ gpio_set_level(charge_port ? GPIO_USB_C1_CHARGE_L :
+ GPIO_USB_C0_CHARGE_L, 0);
}
+
+ return EC_SUCCESS;
}
-enum battery_present battery_is_present(void)
+/**
+ * Set the charge limit based upon desired maximum.
+ *
+ * @param port Port number.
+ * @param supplier Charge supplier type.
+ * @param charge_ma Desired charge limit (mA).
+ * @param charge_mv Negotiated charge voltage (mV).
+ */
+void board_set_charge_limit(int port, int supplier, int charge_ma,
+ int max_ma, int charge_mv)
{
- /* The GPIO is low when the battery is present */
- return BP_NO;
+ /*
+ * Limit the input current to 96% negotiated limit,
+ * to account for the charger chip margin.
+ */
+ charge_ma = charge_ma * 96 / 100;
+ charge_set_input_current_limit(MAX(charge_ma,
+ CONFIG_CHARGER_INPUT_CURRENT), charge_mv);
}
-int64_t get_time_dsw_pwrok(void)
+/**
+ * Return whether ramping is allowed for given supplier
+ */
+int board_is_ramp_allowed(int supplier)
{
- /* DSW_PWROK is turned on before EC was powered. */
- return -20 * MSEC;
+ /* Don't allow ramping in RO when write protected */
+ if (!system_is_in_rw() && system_is_locked())
+ return 0;
+ else
+ return (supplier == CHARGE_SUPPLIER_BC12_DCP ||
+ supplier == CHARGE_SUPPLIER_BC12_SDP ||
+ supplier == CHARGE_SUPPLIER_BC12_CDP ||
+ supplier == CHARGE_SUPPLIER_OTHER);
}
-int board_has_working_reset_flags(void)
+/**
+ * Return the maximum allowed input current
+ */
+int board_get_ramp_current_limit(int supplier, int sup_curr)
{
- int version = system_get_board_version();
+ switch (supplier) {
+ case CHARGE_SUPPLIER_BC12_DCP:
+ return 2000;
+ case CHARGE_SUPPLIER_BC12_SDP:
+ return 1000;
+ case CHARGE_SUPPLIER_BC12_CDP:
+ case CHARGE_SUPPLIER_PROPRIETARY:
+ return sup_curr;
+ default:
+ return 500;
+ }
+}
- /* Board Rev0 will lose reset flags on power cycle. */
- if (version == 0)
- return 0;
+void board_hibernate(void)
+{
+ CPRINTS("Triggering PMIC shutdown.");
+ uart_flush_output();
+
+ /* Trigger PMIC shutdown. */
+ if (i2c_write8(I2C_PORT_PMIC, I2C_ADDR_BD99992, 0x49, 0x01)) {
+ /*
+ * If we can't tell the PMIC to shutdown, instead reset
+ * and don't start the AP. Hopefully we'll be able to
+ * communicate with the PMIC next time.
+ */
+ CPRINTS("PMIC i2c failed.");
+ system_reset(SYSTEM_RESET_LEAVE_AP_OFF);
+ }
- /* All other board versions should have working reset flags */
- return 1;
+ /* Await shutdown. */
+ while (1)
+ ;
}
-const struct pwm_t pwm_channels[] = {
- [PWM_CH_LED_RED] = { 3, PWM_CONFIG_DSLEEP, 100 },
- [PWM_CH_LED_GREEN] = { 5, PWM_CONFIG_DSLEEP, 100 },
- [PWM_CH_FAN] = {4, PWM_CONFIG_OPEN_DRAIN, 25000},
+/* Lid Sensor mutex */
+static struct mutex g_lid_mutex;
+static struct mutex g_base_mutex;
+
+static struct bmi160_drv_data_t g_bmi160_data;
+
+/* BMA255 private data */
+static struct bma2x2_accel_data g_bma255_data;
+
+/* Matrix to rotate accelrator into standard reference frame */
+const matrix_3x3_t base_standard_ref = {
+ { FLOAT_TO_FP(-1), 0, 0},
+ { 0, FLOAT_TO_FP(1), 0},
+ { 0, 0, FLOAT_TO_FP(-1)}
};
-BUILD_ASSERT(ARRAY_SIZE(pwm_channels) == PWM_CH_COUNT);
-struct fan_step {
- int on;
- int off;
- int rpm;
+const matrix_3x3_t lid_standard_ref = {
+ { FLOAT_TO_FP(-1), 0, 0},
+ { 0, FLOAT_TO_FP(-1), 0},
+ { 0, 0, FLOAT_TO_FP(1)}
};
-/* Do not make the fan on/off point equal to 0 or 100 */
-const struct fan_step fan_table[] = {
- {.off = 2, .rpm = 0},
- {.on = 16, .off = 2, .rpm = 2800},
- {.on = 27, .off = 18, .rpm = 3200},
- {.on = 35, .off = 29, .rpm = 3400},
- {.on = 43, .off = 37, .rpm = 4200},
- {.on = 54, .off = 45, .rpm = 4800},
- {.on = 64, .off = 56, .rpm = 5200},
- {.on = 97, .off = 83, .rpm = 5600},
+struct motion_sensor_t motion_sensors[] = {
+ [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_ACCEL,
+ .addr = BMI160_ADDR0,
+ .rot_standard_ref = &base_standard_ref,
+ .min_frequency = BMI160_ACCEL_MIN_FREQ,
+ .max_frequency = BMI160_ACCEL_MAX_FREQ,
+ .default_range = 2, /* g, to support tablet mode */
+ .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 in S3 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0
+ },
+ },
+ },
+ [BASE_GYRO] = {
+ .name = "Base Gyro",
+ .active_mask = SENSOR_ACTIVE_S0_S3,
+ .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_ACCEL,
+ .addr = BMI160_ADDR0,
+ .default_range = 1000, /* dps */
+ .rot_standard_ref = &base_standard_ref,
+ .min_frequency = BMI160_GYRO_MIN_FREQ,
+ .max_frequency = BMI160_GYRO_MAX_FREQ,
+ .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_ACCEL] = {
+ .name = "Lid Accel",
+ .active_mask = SENSOR_ACTIVE_S0_S3,
+ .chip = MOTIONSENSE_CHIP_BMA255,
+ .type = MOTIONSENSE_TYPE_ACCEL,
+ .location = MOTIONSENSE_LOC_LID,
+ .drv = &bma2x2_accel_drv,
+ .mutex = &g_lid_mutex,
+ .drv_data = &g_bma255_data,
+ .port = I2C_PORT_ACCEL,
+ .addr = BMA2x2_I2C_ADDR1,
+ .rot_standard_ref = &lid_standard_ref,
+ .min_frequency = BMA255_ACCEL_MIN_FREQ,
+ .max_frequency = BMA255_ACCEL_MAX_FREQ,
+ .default_range = 2, /* g, to support tablet mode */
+ .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 in S3 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 10000 | ROUND_UP_FLAG,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ },
+ },
};
-#define NUM_FAN_LEVELS ARRAY_SIZE(fan_table)
+const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
-int fan_percent_to_rpm(int fan, int pct)
+/* Enable or disable input devices, based on chipset state and tablet mode */
+#ifndef TEST_BUILD
+void lid_angle_peripheral_enable(int enable)
{
- static int current_level;
- static int previous_pct;
- int i;
+ /* 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
- /*
- * Compare the pct and previous pct, we have the three paths :
- * 1. decreasing path. (check the off point)
- * 2. increasing path. (check the on point)
- * 3. invariant path. (return the current RPM)
- */
- if (pct < previous_pct) {
- for (i = current_level; i >= 0; i--) {
- if (pct <= fan_table[i].off)
- current_level = i - 1;
- else
- break;
- }
- } else if (pct > previous_pct) {
- for (i = current_level + 1; i < NUM_FAN_LEVELS; i++) {
- if (pct >= fan_table[i].on)
- current_level = i;
- else
- break;
- }
- }
+static void board_chipset_reset(void)
+{
+ board_report_pmic_fault("CHIPSET RESET");
+}
+DECLARE_HOOK(HOOK_CHIPSET_RESET, board_chipset_reset, HOOK_PRIO_DEFAULT);
- if (current_level < 0)
- current_level = 0;
+/* Called on AP S3 -> S0 transition */
+static void board_chipset_resume(void)
+{
+ gpio_set_level(GPIO_ENABLE_BACKLIGHT, 1);
+}
+DECLARE_HOOK(HOOK_CHIPSET_RESUME, board_chipset_resume, HOOK_PRIO_DEFAULT);
- previous_pct = pct;
+/* Called on AP S0 -> S3 transition */
+static void board_chipset_suspend(void)
+{
+ gpio_set_level(GPIO_ENABLE_BACKLIGHT, 0);
+}
+DECLARE_HOOK(HOOK_CHIPSET_SUSPEND, board_chipset_suspend, HOOK_PRIO_DEFAULT);
- if (fan_table[current_level].rpm !=
- fan_get_rpm_target(fans[fan].ch))
- cprintf(CC_THERMAL, "[%T Setting fan RPM to %d]\n",
- fan_table[current_level].rpm);
+static void board_chipset_startup(void)
+{
+ gpio_set_level(GPIO_ENABLE_TOUCHPAD, 1);
+}
+DECLARE_HOOK(HOOK_CHIPSET_STARTUP, board_chipset_startup, HOOK_PRIO_DEFAULT);
- return fan_table[current_level].rpm;
+static void board_chipset_shutdown(void)
+{
+ gpio_set_level(GPIO_ENABLE_TOUCHPAD, 0);
}
+DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, board_chipset_shutdown, HOOK_PRIO_DEFAULT);
diff --git a/board/nami/board.h b/board/nami/board.h
index 23d84376d7..57bbeeb3df 100644
--- a/board/nami/board.h
+++ b/board/nami/board.h
@@ -12,30 +12,35 @@
* Allow dangerous commands.
* TODO: Remove this config before production.
*/
-#undef CONFIG_SYSTEM_UNLOCKED
-#define CONFIG_USB_PD_COMM_LOCKED
+#define CONFIG_SYSTEM_UNLOCKED
/* EC */
#define CONFIG_ADC
+#define CONFIG_BACKLIGHT_LID
#define CONFIG_BOARD_VERSION
-#define CONFIG_DEDICATED_RECOVERY_BUTTON
-#define CONFIG_EMULATED_SYSRQ
-#define CONFIG_LED_COMMON
-#define CONFIG_KEYBOARD_PROTOCOL_MKBP
-#define CONFIG_MKBP_USE_HOST_EVENT
+#define CONFIG_CASE_CLOSED_DEBUG_EXTERNAL
#define CONFIG_DPTF
+#define CONFIG_DPTF_DEVICE_ORIENTATION
#define CONFIG_FLASH_SIZE 0x80000
#define CONFIG_FPU
#define CONFIG_I2C
#define CONFIG_I2C_MASTER
-#undef CONFIG_LID_SWITCH
-#define CONFIG_POWER_BUTTON_IGNORE_LID
-#define CONFIG_PWM
+#define CONFIG_KEYBOARD_COL2_INVERTED
+#define CONFIG_KEYBOARD_PROTOCOL_8042
+#define CONFIG_LED_COMMON
+#define CONFIG_LID_SWITCH
+#define CONFIG_LOW_POWER_IDLE
#define CONFIG_LTO
#define CONFIG_CHIP_PANIC_BACKUP
+#define CONFIG_SOFTWARE_PANIC
#define CONFIG_SPI_FLASH_REGS
#define CONFIG_SPI_FLASH_W25X40
#define CONFIG_UART_HOST 0
+#define CONFIG_VBOOT_HASH
+#define CONFIG_SHA256_UNROLLED
+#define CONFIG_VOLUME_BUTTONS
+#define CONFIG_VSTORE
+#define CONFIG_VSTORE_SLOT_COUNT 1
#define CONFIG_WATCHDOG_HELP
#define CONFIG_WIRELESS
#define CONFIG_WIRELESS_SUSPEND \
@@ -43,48 +48,89 @@
#define WIRELESS_GPIO_WLAN GPIO_WLAN_OFF_L
#define WIRELESS_GPIO_WLAN_POWER GPIO_PP3300_DX_WLAN
#define WIRELESS_GPIO_WWAN GPIO_PP3300_DX_LTE
-#define CONFIG_FANS 1
-#define CONFIG_FAN_RPM_CUSTOM
-#define CONFIG_THROTTLE_AP
-#define CONFIG_CHIPSET_CAN_THROTTLE
-#define CONFIG_PWM
/* EC console commands */
+#define CONFIG_CMD_ACCELS
+#define CONFIG_CMD_ACCEL_INFO
#define CONFIG_CMD_BUTTON
+/* Port80 */
+#undef CONFIG_PORT80_HISTORY_LEN
+#define CONFIG_PORT80_HISTORY_LEN 256
+
/* SOC */
#define CONFIG_CHIPSET_SKYLAKE
#define CONFIG_CHIPSET_HAS_PLATFORM_PMIC_RESET
#define CONFIG_CHIPSET_RESET_HOOK
-#undef CONFIG_PECI
#define CONFIG_ESPI
-/* Eve and Poppy all have wires from GPIO to PCH but CONFIG_ESPI_VW_SIGNALS
- * is defined. So, those GPIOs are not used by EC. */
#define CONFIG_ESPI_VW_SIGNALS
#define CONFIG_LPC
+#undef CONFIG_PECI
+
+/* Battery */
+#define CONFIG_BATTERY_CUT_OFF
+#define CONFIG_BATTERY_HW_PRESENT_CUSTOM
+#define CONFIG_BATTERY_DEVICE_CHEMISTRY "LION"
+#define CONFIG_BATTERY_SMART
/* Charger */
#define CONFIG_CHARGE_MANAGER
-
-#define CONFIG_CHARGER_LIMIT_POWER_THRESH_CHG_MW 50000
-
+#define CONFIG_CHARGE_RAMP_HW /* This, or just RAMP? */
+
+#define CONFIG_CHARGER
+#define CONFIG_CHARGER_V2
+#define CONFIG_CHARGER_ISL9238
+#define CONFIG_CHARGER_DISCHARGE_ON_AC
+#define CONFIG_CHARGER_INPUT_CURRENT 512
+#define CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON 2
+#define CONFIG_CHARGER_NARROW_VDC
+#define CONFIG_CHARGER_PROFILE_OVERRIDE
+#define CONFIG_CHARGER_PSYS
+#define CONFIG_CHARGER_SENSE_RESISTOR 10
+#define CONFIG_CHARGER_SENSE_RESISTOR_AC 20
+#define CONFIG_CMD_CHARGER_ADC_AMON_BMON
#define CONFIG_CMD_PD_CONTROL
#define CONFIG_EXTPOWER_GPIO
-#undef CONFIG_EXTPOWER_DEBOUNCE_MS
-#define CONFIG_EXTPOWER_DEBOUNCE_MS 1000
+#undef CONFIG_EXTPOWER_DEBOUNCE_MS
+#define CONFIG_EXTPOWER_DEBOUNCE_MS 1000
#define CONFIG_POWER_BUTTON
#define CONFIG_POWER_BUTTON_X86
-#define CONFIG_POWER_BUTTON_INIT_IDLE
#define CONFIG_POWER_COMMON
#define CONFIG_POWER_SIGNAL_INTERRUPT_STORM_DETECT_THRESHOLD 30
-#define CONFIG_DELAY_DSW_PWROK_TO_PWRBTN
+#define CONFIG_POWER_S0IX
+#define CONFIG_POWER_TRACK_HOST_SLEEP_STATE
/* Sensor */
#define CONFIG_TEMP_SENSOR
-#define CONFIG_TEMP_SENSOR_TMP432
+#define CONFIG_TEMP_SENSOR_BD99992GW
+/* TODO(crosbug.com/p/61098): Is this the correct thermistor? */
+#define CONFIG_THERMISTOR_NCP15WB
+
+#define CONFIG_MKBP_EVENT
+#define CONFIG_MKBP_USE_HOST_EVENT
+#define CONFIG_ACCELGYRO_BMI160
+#define CONFIG_ACCELGYRO_BMI160_INT_EVENT TASK_EVENT_CUSTOM(4)
+#define CONFIG_ACCELGYRO_BMI160_INT2_OUTPUT
+#define CONFIG_ACCEL_BMA255
+#define CONFIG_ACCEL_INTERRUPTS
+#define CONFIG_LID_ANGLE
+#define CONFIG_LID_ANGLE_SENSOR_BASE BASE_ACCEL
+#define CONFIG_LID_ANGLE_SENSOR_LID LID_ACCEL
+#define CONFIG_LID_ANGLE_UPDATE
+#define CONFIG_LID_ANGLE_TABLET_MODE
+#define CONFIG_LID_ANGLE_INVALID_CHECK
+
+/* 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)
+
+#define CONFIG_TABLET_MODE
+#define CONFIG_TABLET_MODE_SWITCH
/* USB */
-#undef CONFIG_USB_CHARGER /* dnojiri: verify */
+#define CONFIG_USB_CHARGER
#define CONFIG_USB_PD_ALT_MODE
#define CONFIG_USB_PD_ALT_MODE_DFP
#define CONFIG_USB_PD_CUSTOM_VDM
@@ -93,7 +139,8 @@
#define CONFIG_USB_PD_DUAL_ROLE
#define CONFIG_USB_PD_DUAL_ROLE_AUTO_TOGGLE
#define CONFIG_USB_PD_LOGGING
-#define CONFIG_USB_PD_PORT_COUNT 1
+#define CONFIG_USB_PD_MAX_SINGLE_SOURCE_CURRENT TYPEC_RP_3A0
+#define CONFIG_USB_PD_PORT_COUNT 2
#define CONFIG_USB_PD_VBUS_DETECT_GPIO
#define CONFIG_USB_PD_TCPC_LOW_POWER
#define CONFIG_USB_PD_TCPM_MUX
@@ -106,78 +153,42 @@
#define CONFIG_USBC_VCONN
#define CONFIG_USBC_VCONN_SWAP
-/* Charge ports */
-#undef CONFIG_DEDICATED_CHARGE_PORT_COUNT
-#define CONFIG_DEDICATED_CHARGE_PORT_COUNT 1
-#define DEDICATED_CHARGE_PORT 1
-
-/* USB-A config */
-#define CONFIG_USB_PORT_POWER_DUMB
-#define USB_PORT_COUNT 5
+/* BC 1.2 charger */
+#define CONFIG_BC12_DETECT_PI3USB9281
+#define CONFIG_BC12_DETECT_PI3USB9281_CHIP_COUNT 2
/* Optional feature to configure npcx chip */
#define NPCX_UART_MODULE2 1 /* 1:GPIO64/65 as UART */
#define NPCX_JTAG_MODULE2 0 /* 0:GPIO21/17/16/20 as JTAG */
-#define NPCX_TACH_SEL2 1 /* 0:GPIO40/73 1:GPIO93/A6 as TACH */
+#define NPCX_TACH_SEL2 0 /* 0:GPIO40/73 as TACH */
/* I2C ports */
#define I2C_PORT_TCPC0 NPCX_I2C_PORT0_0
-#define I2C_PORT_EEPROM NPCX_I2C_PORT0_1
-#define I2C_PORT_BATTERY NPCX_I2C_PORT1
+#define I2C_PORT_TCPC1 NPCX_I2C_PORT0_1
+#define I2C_PORT_USB_CHARGER_1 NPCX_I2C_PORT0_1
+#define I2C_PORT_USB_CHARGER_0 NPCX_I2C_PORT1
#define I2C_PORT_CHARGER NPCX_I2C_PORT1
+#define I2C_PORT_BATTERY NPCX_I2C_PORT1
#define I2C_PORT_PMIC NPCX_I2C_PORT2
-#define I2C_PORT_THERMAL NPCX_I2C_PORT3
+#define I2C_PORT_MP2949 NPCX_I2C_PORT2
+#define I2C_PORT_GYRO NPCX_I2C_PORT3
+#define I2C_PORT_BARO NPCX_I2C_PORT3
+#define I2C_PORT_ACCEL I2C_PORT_GYRO
+#define I2C_PORT_THERMAL I2C_PORT_PMIC
/* I2C addresses */
-#define I2C_ADDR_TCPC0 0x16
-
-/* Verify and jump to RW image on boot */
-#define CONFIG_VBOOT_EFS
-#define CONFIG_VBOOT_HASH
-#define CONFIG_VSTORE
-#define CONFIG_VSTORE_SLOT_COUNT 1
-
-/*
- * Flash layout. Since config_flash_layout.h is included before board.h,
- * we can only overwrite (=undef/define) these parameters here.
- *
- * Flash stores 3 images: RO, RW_A, RW_B. We divide the flash by 4.
- * A public key is stored at the end of RO. Signatures are stored at the
- * end of RW_A and RW_B, respectively.
- */
-#define CONFIG_RW_B
-#define CONFIG_RW_B_MEM_OFF CONFIG_RO_MEM_OFF
-#undef CONFIG_RO_SIZE
-#define CONFIG_RO_SIZE (CONFIG_FLASH_SIZE / 4)
-#undef CONFIG_RW_SIZE
-#define CONFIG_RW_SIZE CONFIG_RO_SIZE
-#define CONFIG_RW_A_STORAGE_OFF CONFIG_RW_STORAGE_OFF
-#define CONFIG_RW_B_STORAGE_OFF (CONFIG_RW_A_STORAGE_OFF + \
- CONFIG_RW_SIZE)
-#define CONFIG_RW_A_SIGN_STORAGE_OFF (CONFIG_RW_A_STORAGE_OFF + \
- CONFIG_RW_SIZE - CONFIG_RW_SIG_SIZE)
-#define CONFIG_RW_B_SIGN_STORAGE_OFF (CONFIG_RW_B_STORAGE_OFF + \
- CONFIG_RW_SIZE - CONFIG_RW_SIG_SIZE)
-
-#define CONFIG_RWSIG
-#define CONFIG_RWSIG_TYPE_RWSIG
-#define CONFIG_RSA
-#define CONFIG_SHA256
-#define CONFIG_RSA_KEY_SIZE 3072
-#define CONFIG_RSA_EXPONENT_3
+#define I2C_ADDR_BD99992 0x60
+#define I2C_ADDR_MP2949 0x40
#ifndef __ASSEMBLER__
#include "gpio_signal.h"
#include "registers.h"
-enum charge_port {
- CHARGE_PORT_TYPEC0,
- CHARGE_PORT_BARRELJACK,
-};
-
enum power_signal {
+#ifdef CONFIG_POWER_S0IX
X86_SLP_S0_DEASSERTED,
+#endif
X86_SLP_S3_DEASSERTED,
X86_SLP_S4_DEASSERTED,
X86_SLP_SUS_DEASSERTED,
@@ -186,39 +197,34 @@ enum power_signal {
POWER_SIGNAL_COUNT
};
+/* Nautilus doesn't have systherm0 and systherm3 */
enum temp_sensor_id {
+ TEMP_SENSOR_BATTERY, /* BD99956GW TSENSE */
TEMP_SENSOR_CHARGER, /* BD99992GW SYSTHERM1 */
TEMP_SENSOR_DRAM, /* BD99992GW SYSTHERM2 */
- TEMP_SENSOR_EMMC, /* BD99992GW SYSTHERM3 */
TEMP_SENSOR_COUNT
};
+/*
+ * 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 {
+ BASE_ACCEL = 0,
+ BASE_GYRO,
+ LID_ACCEL,
+};
+
enum adc_channel {
+ ADC_BASE_DET,
ADC_VBUS,
ADC_AMON_BMON,
ADC_CH_COUNT
};
-enum pwm_channel {
- PWM_CH_LED_RED,
- PWM_CH_LED_GREEN,
- PWM_CH_FAN,
- /* Number of PWM channels */
- PWM_CH_COUNT
-};
-
-enum fan_channel {
- FAN_CH_0,
- /* Number of FAN channels */
- FAN_CH_COUNT
-};
-
-enum mft_channel {
- MFT_CH_0,
- /* Number of MFT channels */
- MFT_CH_COUNT
-};
-
/* TODO(crosbug.com/p/61098): Verify the numbers below. */
/*
* delay to turn on the power supply max is ~16ms.
@@ -232,8 +238,7 @@ enum mft_channel {
/* Define typical operating power and max power */
#define PD_OPERATING_POWER_MW 15000
-#define PD_MAX_POWER_MW 60000
-/* We can't go above the cable capacity until we add e-marked cable detection */
+#define PD_MAX_POWER_MW 45000
#define PD_MAX_CURRENT_MA 3000
#define PD_MAX_VOLTAGE_MV 20000
@@ -241,9 +246,6 @@ enum mft_channel {
int board_get_version(void);
void board_reset_pd_mcu(void);
void board_set_tcpc_power_mode(int port, int mode);
-int board_get_battery_soc(void);
-void led_alert(int enable);
-void led_critical(void);
#endif /* !__ASSEMBLER__ */
diff --git a/board/nami/build.mk b/board/nami/build.mk
index 74094ac834..f4bf21113d 100644
--- a/board/nami/build.mk
+++ b/board/nami/build.mk
@@ -10,5 +10,6 @@ CHIP:=npcx
CHIP_VARIANT:=npcx5m6g
board-y=board.o
+board-$(CONFIG_BATTERY_SMART)+=battery.o
+board-$(CONFIG_LED_COMMON)+=led.o
board-$(CONFIG_USB_POWER_DELIVERY)+=usb_pd_policy.o
-board-y+=led.o
diff --git a/board/nami/ec.tasklist b/board/nami/ec.tasklist
index b60ae990a7..0ef0783898 100644
--- a/board/nami/ec.tasklist
+++ b/board/nami/ec.tasklist
@@ -21,11 +21,17 @@
*/
#define CONFIG_TASK_LIST \
- TASK_ALWAYS(HOOKS, hook_task, NULL, 2048) \
- /* Larger stack for RW verification (i.e. sha256, rsa) */ \
- TASK_NOTEST(CHIPSET, chipset_task, NULL, TASK_STACK_SIZE) \
+ TASK_ALWAYS(HOOKS, hook_task, NULL, LARGER_TASK_STACK_SIZE) \
+ TASK_ALWAYS(USB_CHG_P0, usb_charger_task, NULL, TASK_STACK_SIZE) \
+ TASK_ALWAYS(USB_CHG_P1, 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, LARGER_TASK_STACK_SIZE) \
TASK_ALWAYS(POWERBTN, power_button_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(PD_C0, pd_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/nami/gpio.inc b/board/nami/gpio.inc
index c1b3be59c7..93642ac6a0 100644
--- a/board/nami/gpio.inc
+++ b/board/nami/gpio.inc
@@ -8,11 +8,11 @@
/* Declare symbolic names for all the GPIOs that we care about.
* Note: Those with interrupt handlers must be declared first. */
-GPIO_INT(USB_C0_PD_INT_ODL, PIN(3, 7), GPIO_INT_FALLING | GPIO_PULL_UP, tcpc_alert_event)
-GPIO_INT(AC_PRESENT, PIN(C, 1), GPIO_INT_BOTH, extpower_interrupt)
-GPIO_INT(POWER_BUTTON_L, PIN(0, 4), GPIO_INT_BOTH | GPIO_PULL_UP, power_button_interrupt) /* MECH_PWR_BTN_ODL */
-
+GPIO_INT(USB_C0_PD_INT_ODL, PIN(3, 7), GPIO_INT_FALLING, tcpc_alert_event)
+GPIO_INT(USB_C1_PD_INT_ODL, PIN(C, 5), GPIO_INT_FALLING, tcpc_alert_event)
+#ifdef CONFIG_POWER_S0IX
GPIO_INT(PCH_SLP_S0_L, PIN(7, 5), GPIO_INT_BOTH, power_signal_interrupt)
+#endif
/* Use VW signals instead of GPIOs */
#ifndef CONFIG_ESPI_VW_SIGNALS
GPIO_INT(PCH_SLP_S3_L, PIN(7, 3), GPIO_INT_BOTH, power_signal_interrupt)
@@ -21,91 +21,103 @@ GPIO_INT(PCH_SLP_S4_L, PIN(8, 6), GPIO_INT_BOTH, power_signal_interrupt)
GPIO_INT(PCH_SLP_SUS_L, PIN(6, 2), GPIO_INT_BOTH, power_signal_interrupt)
GPIO_INT(RSMRST_L_PGOOD, PIN(B, 0), GPIO_INT_BOTH, power_signal_interrupt)
GPIO_INT(PMIC_DPWROK, PIN(C, 7), GPIO_INT_BOTH, power_signal_interrupt)
-GPIO_INT(WP_L, PIN(9, 3), GPIO_INT_BOTH, switch_interrupt)
-GPIO_INT(ADP_IN_L, PIN(C, 5), GPIO_INT_BOTH | GPIO_PULL_UP, adp_in) /* Low: BJ detected */
-GPIO_INT(USB_C0_VBUS_WAKE_L, PIN(9, 7), GPIO_INT_BOTH | GPIO_PULL_UP, vbus0_evt)
-GPIO_INT(RECOVERY_L, PIN(8, 2), GPIO_INT_BOTH, button_interrupt) /* Recovery button */
-GPIO(PCH_RTCRST, PIN(E, 7), GPIO_OUT_LOW) /* RTCRST# to SOC */
+GPIO_INT(POWER_BUTTON_L, PIN(0, 4), GPIO_INT_BOTH | GPIO_PULL_UP, power_button_interrupt)
+GPIO_INT(LID_OPEN, PIN(6, 7), GPIO_INT_BOTH, lid_interrupt)
+GPIO_INT(VOLUME_DOWN_L, PIN(8, 3), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt)
+GPIO_INT(VOLUME_UP_L, PIN(8, 2), GPIO_INT_BOTH | GPIO_PULL_UP, button_interrupt)
+GPIO_INT(WP_L, PIN(4, 0), GPIO_INT_BOTH, switch_interrupt)
+GPIO_INT(AC_PRESENT, PIN(C, 1), GPIO_INT_BOTH, extpower_interrupt)
+GPIO_INT(USB_C0_VBUS_WAKE_L, PIN(9, 3), GPIO_INT_BOTH | GPIO_PULL_UP, vbus0_evt)
+GPIO_INT(USB_C1_VBUS_WAKE_L, PIN(9, 7), GPIO_INT_BOTH | GPIO_PULL_UP, vbus1_evt)
+GPIO_INT(USB_C0_BC12_INT_L, PIN(D, 3), GPIO_INT_FALLING, usb0_evt)
+GPIO_INT(USB_C1_BC12_INT_L, PIN(3, 3), GPIO_INT_FALLING, usb1_evt)
+GPIO_INT(ACCELGYRO3_INT_L, PIN(3, 6), GPIO_INT_FALLING | GPIO_SEL_1P8V, bmi160_interrupt)
+
+GPIO(ENABLE_TOUCHPAD, PIN(4, 5), GPIO_OUT_LOW)
+GPIO(PCH_RTCRST, PIN(2, 7), GPIO_OUT_LOW) /* RTCRST# to SOC (>= rev4) */
+GPIO(ENABLE_BACKLIGHT, PIN(5, 6), GPIO_OUT_LOW) /* Enable Backlight */
GPIO(WLAN_OFF_L, PIN(7, 2), GPIO_OUT_LOW) /* Disable WLAN */
GPIO(PP3300_DX_WLAN, PIN(A, 7), GPIO_OUT_LOW) /* Enable WLAN 3.3V Power */
GPIO(CPU_PROCHOT, PIN(8, 1), GPIO_OUT_HIGH) /* PROCHOT# to SOC */
-GPIO(PCH_ACPRESENT, PIN(5, 0), GPIO_ODR_LOW) /* ACOK to SOC */
+GPIO(PCH_ACOK, PIN(5, 0), GPIO_ODR_LOW) /* ACOK to SOC */
GPIO(PCH_WAKE_L, PIN(A, 3), GPIO_ODR_HIGH) /* Wake SOC */
GPIO(PCH_RSMRST_L, PIN(7, 0), GPIO_OUT_LOW) /* RSMRST# to SOC */
-GPIO(PCH_PWRBTN_L, PIN(7, 4), GPIO_ODR_HIGH) /* Power Button to SOC */
-GPIO(EC_PLATFORM_RST, PIN(4, 5), GPIO_OUT_LOW) /* EC Reset to LDO_EN */
+GPIO(PCH_PWRBTN_L, PIN(4, 1), GPIO_ODR_HIGH) /* Power Button to SOC */
+GPIO(EC_PLATFORM_RST, PIN(A, 6), GPIO_OUT_LOW) /* EC Reset to LDO_EN */
GPIO(SYS_RESET_L, PIN(6, 1), GPIO_ODR_HIGH) /* Cold Reset to SOC */
GPIO(PMIC_SLP_SUS_L, PIN(8, 5), GPIO_OUT_LOW) /* SLP_SUS# to PMIC */
+GPIO(BATTERY_PRESENT_L, PIN(3, 4), GPIO_INPUT) /* Battery Present */
GPIO(CCD_MODE_ODL, PIN(6, 3), GPIO_INPUT) /* Case Closed Debug Mode */
-GPIO(EC_HAVEN_RESET_ODL, PIN(0, 2), GPIO_ODR_HIGH) /* H1 Reset */
GPIO(ENTERING_RW, PIN(7, 6), GPIO_OUTPUT) /* EC Entering RW */
GPIO(PMIC_INT_L, PIN(6, 0), GPIO_INPUT) /* PMIC interrupt */
-GPIO(U42_P, PIN(3, 3), GPIO_OUTPUT | GPIO_PULL_DOWN)
-GPIO(U22_C, PIN(3, 4), GPIO_OUTPUT | GPIO_PULL_DOWN)
-GPIO(POWER_RATE, PIN(7, 1), GPIO_INPUT) /* High: i3/5/7. Low: Celeron */
-
-/* Fizz specific pins */
-GPIO(LAN_PWR_EN, PIN(8, 3), GPIO_OUT_HIGH) /* Ethernet power enabled */
-
-/* TODO(crosbug.com/p/61098): Make use of these GPIOs */
-GPIO(PP3300_USB_PD, PIN(6, 7), GPIO_OUTPUT)
+#ifndef CONFIG_POWER_S0IX
+GPIO(PCH_SLP_S0_L, PIN(7, 5), GPIO_INPUT)
+#endif
-GPIO(PP5000_DX_NFC, PIN(1, 5), GPIO_OUTPUT)
+/* NC pins */
+GPIO(GPIOD2_NC, PIN(D, 2), GPIO_INPUT | GPIO_PULL_UP)
-GPIO(PP3300_DX_CAM, PIN(1, 0), GPIO_OUT_HIGH)
-GPIO(CAM_PMIC_RST_L, PIN(0, 7), GPIO_INPUT)
+/* TODO(b/35585396): Make use of these GPIOs */
+GPIO(PP1800_DX_SENSOR, PIN(E, 7), GPIO_OUTPUT)
GPIO(WLAN_PE_RST, PIN(1, 2), GPIO_OUTPUT)
-GPIO(PP3300_DX_LTE, PIN(0, 5), GPIO_OUT_LOW)
-GPIO(PP3300_DX_BASE, PIN(1, 1), GPIO_OUT_LOW)
+GPIO(PP3300_DX_LTE, PIN(0, 2), GPIO_OUT_LOW)
+GPIO(LTE_GPS_OFF_L, PIN(0, 0), GPIO_ODR_HIGH)
+GPIO(LTE_BODY_SAR_L, PIN(0, 1), GPIO_ODR_HIGH)
+GPIO(LTE_WAKE_L, PIN(7, 1), GPIO_INPUT)
+GPIO(LTE_OFF_ODL, PIN(8, 0), GPIO_ODR_LOW)
+/* end of TODO */
/* I2C pins - these will be reconfigured for alternate function below */
-GPIO(I2C0_0_SCL, PIN(B, 5), GPIO_INPUT) /* EC_I2C_USB_C0_PD_SCL */
-GPIO(I2C0_0_SDA, PIN(B, 4), GPIO_INPUT) /* EC_I2C_USB_C0_PD_SDA */
-GPIO(I2C0_1_SCL, PIN(B, 3), GPIO_INPUT) /* EC_I2C_EEPROM_SCL */
-GPIO(I2C0_1_SDA, PIN(B, 2), GPIO_INPUT) /* EC_I2C_EEPROM_SDA */
-GPIO(I2C1_SCL, PIN(9, 0), GPIO_INPUT) /* EC_I2C_BAT_SCL */
-GPIO(I2C1_SDA, PIN(8, 7), GPIO_INPUT) /* EC_I2C_BAT_SDA */
-GPIO(I2C2_SCL, PIN(9, 2), GPIO_INPUT) /* EC_ROP_I2C_CLK */
-GPIO(I2C2_SDA, PIN(9, 1), GPIO_INPUT) /* EC_ROP_I2C_SDA */
-GPIO(I2C3_SCL, PIN(D, 1), GPIO_INPUT) /* EC_THEM_CLK */
-GPIO(I2C3_SDA, PIN(D, 0), GPIO_INPUT) /* EC_THEM_SDA */
+GPIO(I2C0_0_SCL, PIN(B, 5), GPIO_INPUT) /* EC_I2C0_0_USBC_3V3_SCL */
+GPIO(I2C0_0_SDA, PIN(B, 4), GPIO_INPUT) /* EC_I2C0_0_USBC_3V3_SDA */
+GPIO(I2C0_1_SCL, PIN(B, 3), GPIO_INPUT) /* EC_I2C0_1_USBC_3V3_SCL */
+GPIO(I2C0_1_SDA, PIN(B, 2), GPIO_INPUT) /* EC_I2C0_1_USBC_3V3_SDA */
+GPIO(I2C1_SCL, PIN(9, 0), GPIO_INPUT) /* EC_I2C1_3V3_SCL */
+GPIO(I2C1_SDA, PIN(8, 7), GPIO_INPUT) /* EC_I2C1_3V3_SDA */
+GPIO(I2C2_SCL, PIN(9, 2), GPIO_INPUT) /* EC_I2C2_PMIC_3V3_SCL */
+GPIO(I2C2_SDA, PIN(9, 1), GPIO_INPUT) /* EC_I2C2_PMIC_3V3_SDA */
+GPIO(I2C3_SCL, PIN(D, 1), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C3_SENSOR_1V8_SCL */
+GPIO(I2C3_SDA, PIN(D, 0), GPIO_INPUT | GPIO_SEL_1P8V) /* EC_I2C3_SENSOR_1V8_SDA */
-/* 5V enables: INPUT=1.5A, OUT_LOW=OFF, OUT_HIGH=3A */
-GPIO(USB_C0_5V_EN, PIN(4, 2), GPIO_OUT_LOW | GPIO_PULL_UP) /* C0 5V Enable */
+/* rev0: 5V enables: INPUT=1.5A, OUT_LOW=OFF, OUT_HIGH=3A */
+GPIO(USB_C0_5V_EN, PIN(4, 2), GPIO_OUT_LOW) /* C0 5V Enable */
+GPIO(USB_C0_3A_EN, PIN(6, 6), GPIO_OUT_LOW) /* C0 Enable 3A */
GPIO(USB_C0_CHARGE_L, PIN(C, 0), GPIO_OUT_LOW) /* C0 Charge enable */
-GPIO(AC_JACK_CHARGE_L, PIN(C, 3), GPIO_OUT_LOW) /* AC jack charge enable */
-GPIO(USB_C0_PD_RST_ODL, PIN(0, 3), GPIO_OUT_LOW) /* C0 PD Reset */
+GPIO(USB_C1_5V_EN, PIN(B, 1), GPIO_OUT_LOW) /* C1 5V Enable */
+GPIO(USB_C1_3A_EN, PIN(3, 5), GPIO_OUT_LOW) /* C1 3A Enable */
+GPIO(USB_C1_CHARGE_L, PIN(C, 3), GPIO_OUT_LOW) /* C1 Charge enable */
+GPIO(USB_C0_PD_RST_L, PIN(0, 3), GPIO_ODR_HIGH) /* C0 PD Reset */
+GPIO(USB_C1_PD_RST_L, PIN(7, 4), GPIO_ODR_HIGH) /* C1 PD Reset */
GPIO(USB_C0_DP_HPD, PIN(9, 4), GPIO_INPUT) /* C0 DP Hotplug Detect */
+GPIO(USB_C1_DP_HPD, PIN(A, 5), GPIO_INPUT) /* C1 DP Hotplug Detect */
GPIO(USB_C0_TCPC_PWR, PIN(8, 4), GPIO_OUT_LOW) /* Enable C0 TCPC Power */
-GPIO(FAN_PWR_EN, PIN(9, 5), GPIO_OUT_HIGH) /* Fan power */
-GPIO(USB1_ENABLE, PIN(3, 2), GPIO_OUT_LOW) /* Rear port, bottom */
-GPIO(USB2_ENABLE, PIN(C, 6), GPIO_OUT_LOW) /* Rear port, top */
-GPIO(USB3_ENABLE, PIN(A, 1), GPIO_OUT_LOW) /* Rear port, single */
-GPIO(USB4_ENABLE, PIN(0, 0), GPIO_OUT_LOW) /* Front port 1 */
-GPIO(USB5_ENABLE, PIN(B, 1), GPIO_OUT_LOW) /* Front port 2 */
-GPIO(USB_A_CHARGE_EN_L, PIN(A, 5), GPIO_OUT_LOW)
+GPIO(USB2_OTG_ID, PIN(A, 1), GPIO_ODR_LOW) /* OTG ID */
+GPIO(USB2_OTG_VBUSSENSE, PIN(9, 5), GPIO_OUT_LOW) /* OTG VBUS Sense */
-/* Board ID */
-GPIO(BOARD_VERSION1, PIN(C, 4), GPIO_INPUT) /* Board ID bit0 */
-GPIO(BOARD_VERSION2, PIN(C, 2), GPIO_INPUT) /* Board ID bit1 */
-GPIO(BOARD_VERSION3, PIN(0, 1), GPIO_INPUT) /* Board ID bit2 */
+/* LEDs (2 colors on each port) */
+GPIO(LED_ACIN, PIN(B, 6), GPIO_OUT_LOW) /* ACIN LED */
+GPIO(POWER_LED, PIN(B, 7), GPIO_OUT_LOW) /* Power LED */
+GPIO(LED_CHARGE, PIN(C, 6), GPIO_OUT_LOW) /* Charge LED */
-/* Test points */
-GPIO(TP248, PIN(5, 7), GPIO_INPUT | GPIO_PULL_UP) /* EC_GPIO57 */
-GPIO(TP249, PIN(6, 6), GPIO_INPUT | GPIO_PULL_UP) /* EC_GPO66_ARM_L */
-GPIO(TP250, PIN(3, 5), GPIO_INPUT | GPIO_PULL_UP) /* EC_GPIO35_TEST_L */
+/* Board ID */
+GPIO(BOARD_VERSION1, PIN(8, 6), GPIO_INPUT) /* Board ID bit0 */
+GPIO(BOARD_VERSION2, PIN(C, 2), GPIO_INPUT) /* Board ID bit1 */
+GPIO(BOARD_VERSION3, PIN(C, 4), GPIO_INPUT) /* Board ID bit2 */
/* Alternate functions GPIO definitions */
ALTERNATE(PIN_MASK(6, 0x30), 1, MODULE_UART, 0) /* GPIO64-65 */ /* UART from EC to Servo */
ALTERNATE(PIN_MASK(8, 0x80), 1, MODULE_I2C, 0) /* GPIO87 */ /* EC_I2C1_3V3_SDA */
ALTERNATE(PIN_MASK(9, 0x01), 1, MODULE_I2C, 0) /* GPIO90 */ /* EC_I2C1_3V3_SCL */
ALTERNATE(PIN_MASK(9, 0x06), 1, MODULE_I2C, 0) /* GPIO91-92 */ /* EC_I2C2_PMIC_3V3_SDA/SCL */
-ALTERNATE(PIN_MASK(A, 0x40), 1, MODULE_PWM, 0) /* GPIOA6 */ /* TACH2 */
ALTERNATE(PIN_MASK(B, 0x30), 1, MODULE_I2C, 0) /* GPIOB4-B5 */ /* EC_I2C0_0_USBC_3V3_SDA/SCL */
-ALTERNATE(PIN_MASK(B, 0x40), 1, MODULE_PWM, 0) /* GPIOB6 */ /* EC_FAN_PWM */
ALTERNATE(PIN_MASK(B, 0x0C), 1, MODULE_I2C, 0) /* GPOPB2-B3 */ /* EC_I2C0_1_3V3_SDA/SCL */
ALTERNATE(PIN_MASK(D, 0x03), 1, MODULE_I2C, 0) /* GPIOD0-D1 */ /* EC_I2C3_SENSOR_1V8_SDA/SCL */
-/* Alternate functions for LED PWM */
-ALTERNATE(PIN_MASK(8, 0x01), 1, MODULE_PWM, 0) /* GPIO80 PWM3 Red*/
-ALTERNATE(PIN_MASK(B, 0x80), 1, MODULE_PWM, 0) /* GPOB7 PWM5 Green*/
+
+/* Keyboard pins */
+ALTERNATE(PIN_MASK(3, 0x03), 0, MODULE_KEYBOARD_SCAN, 0)
+ALTERNATE(PIN_MASK(2, 0xfc), 0, MODULE_KEYBOARD_SCAN, 0)
+ALTERNATE(PIN_MASK(2, 0x03), 0, MODULE_KEYBOARD_SCAN, 0)
+ALTERNATE(PIN_MASK(0, 0xe0), 0, MODULE_KEYBOARD_SCAN, 0)
+ALTERNATE(PIN_MASK(1, 0x7f), 0, MODULE_KEYBOARD_SCAN, 0)
+GPIO(KBD_KSO2, PIN(1, 7), GPIO_OUT_LOW)
diff --git a/board/nami/led.c b/board/nami/led.c
index 9b6942d241..6b92ab6992 100644
--- a/board/nami/led.c
+++ b/board/nami/led.c
@@ -2,231 +2,132 @@
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*
- * Power and battery LED control for Fizz
+ * Power and battery LED control.
*/
+#include "battery.h"
+#include "charge_manager.h"
+#include "charge_state.h"
#include "chipset.h"
-#include "console.h"
#include "ec_commands.h"
#include "gpio.h"
#include "hooks.h"
+#include "host_command.h"
#include "led_common.h"
-#include "pwm.h"
-#include "timer.h"
+#include "system.h"
#include "util.h"
-const enum ec_led_id supported_led_ids[] = {EC_LED_ID_POWER_LED};
+#define BAT_LED_ON 1
+#define BAT_LED_OFF 0
+
+#define LED_TOTAL_TICKS 16
+#define LED_ON_TICKS 8
+
+const enum ec_led_id supported_led_ids[] = {
+ EC_LED_ID_POWER_LED,
+ EC_LED_ID_BATTERY_LED};
+
const int supported_led_ids_count = ARRAY_SIZE(supported_led_ids);
enum led_color {
LED_OFF = 0,
LED_RED,
LED_GREEN,
- LED_AMBER,
+ LED_BLUE,
/* Number of colors, not a color itself */
LED_COLOR_COUNT
};
-static int set_color_power(enum led_color color, int duty)
-{
- int green = 0;
- int red = 0;
-
- if (duty < 0 || 100 < duty)
- return EC_ERROR_UNKNOWN;
-
- switch (color) {
- case LED_OFF:
- break;
- case LED_GREEN:
- green = 1;
- break;
- case LED_RED:
- red = 1;
- break;
- case LED_AMBER:
- green = 1;
- red = 1;
- break;
- default:
- return EC_ERROR_UNKNOWN;
- }
-
- if (red)
- pwm_set_duty(PWM_CH_LED_RED, duty);
- else
- pwm_set_duty(PWM_CH_LED_RED, 0);
-
- if (green)
- pwm_set_duty(PWM_CH_LED_GREEN, duty);
- else
- pwm_set_duty(PWM_CH_LED_GREEN, 0);
-
- return EC_SUCCESS;
-}
-
-static int set_color(enum ec_led_id id, enum led_color color, int duty)
+/**
+ * Set LED color
+ *
+ * @param color Enumerated color value
+ */
+static void set_color(enum led_color color)
{
- switch (id) {
- case EC_LED_ID_POWER_LED:
- return set_color_power(color, duty);
- default:
- return EC_ERROR_UNKNOWN;
- }
+ gpio_set_level(GPIO_POWER_LED, !(color == LED_BLUE));
+ gpio_set_level(GPIO_LED_ACIN, !(color == LED_GREEN));
+ gpio_set_level(GPIO_LED_CHARGE, !(color == LED_RED));
}
-#define LED_PULSE_US (2 * SECOND)
-/* 40 msec for nice and smooth transition. */
-#define LED_PULSE_TICK_US (40 * MSEC)
-
-/* When pulsing is enabled, brightness is incremented by <duty_inc> every
- * <interval> usec from 0 to 100% in LED_PULSE_US usec. Then it's decremented
- * likewise in LED_PULSE_US usec. */
-static struct {
- uint32_t interval;
- int duty_inc;
- enum led_color color;
- int duty;
-} led_pulse;
-
-#define CONFIG_TICK(interval, color) \
- config_tick((interval), 100 / (LED_PULSE_US / (interval)), (color))
-
-static void config_tick(uint32_t interval, int duty_inc, enum led_color color)
+void led_get_brightness_range(enum ec_led_id led_id, uint8_t *brightness_range)
{
- led_pulse.interval = interval;
- led_pulse.duty_inc = duty_inc;
- led_pulse.color = color;
- led_pulse.duty = 0;
+ brightness_range[EC_LED_COLOR_RED] = 1;
+ brightness_range[EC_LED_COLOR_BLUE] = 1;
+ brightness_range[EC_LED_COLOR_GREEN] = 1;
}
-static void pulse_power_led(enum led_color color)
+int led_set_brightness(enum ec_led_id led_id, const uint8_t *brightness)
{
- set_color(EC_LED_ID_POWER_LED, color, led_pulse.duty);
- if (led_pulse.duty + led_pulse.duty_inc > 100)
- led_pulse.duty_inc = led_pulse.duty_inc * -1;
- else if (led_pulse.duty + led_pulse.duty_inc < 0)
- led_pulse.duty_inc = led_pulse.duty_inc * -1;
- led_pulse.duty += led_pulse.duty_inc;
-}
+ gpio_set_level(GPIO_POWER_LED, !brightness[EC_LED_COLOR_BLUE]);
+ gpio_set_level(GPIO_LED_ACIN, !brightness[EC_LED_COLOR_GREEN]);
+ gpio_set_level(GPIO_LED_CHARGE, !brightness[EC_LED_COLOR_RED]);
-static void led_tick(void);
-DECLARE_DEFERRED(led_tick);
-static void led_tick(void)
-{
- uint32_t elapsed;
- uint32_t next = 0;
- uint32_t start = get_time().le.lo;
- static uint8_t pwm_enabled = 0;
-
- if (!pwm_enabled) {
- pwm_enable(PWM_CH_LED_RED, 1);
- pwm_enable(PWM_CH_LED_GREEN, 1);
- pwm_enabled = 1;
- }
- if (led_auto_control_is_enabled(EC_LED_ID_POWER_LED))
- pulse_power_led(led_pulse.color);
- elapsed = get_time().le.lo - start;
- next = led_pulse.interval > elapsed ? led_pulse.interval - elapsed : 0;
- hook_call_deferred(&led_tick_data, next);
+ return EC_SUCCESS;
}
-static void led_suspend(void)
-{
- CONFIG_TICK(LED_PULSE_TICK_US, LED_GREEN);
- led_tick();
-}
-DECLARE_HOOK(HOOK_CHIPSET_SUSPEND, led_suspend, HOOK_PRIO_DEFAULT);
-static void led_shutdown(void)
+static void nautilus_led_set_power_battery(void)
{
- hook_call_deferred(&led_tick_data, -1);
- if (led_auto_control_is_enabled(EC_LED_ID_POWER_LED))
- set_color(EC_LED_ID_POWER_LED, LED_OFF, 0);
-}
-DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, led_shutdown, HOOK_PRIO_DEFAULT);
+ static unsigned int power_ticks;
+ enum led_color cur_led_color = LED_RED;
+ enum charge_state chg_state = charge_get_state();
+ int charge_percent = charge_get_percent();
+
+ if (chipset_in_state(CHIPSET_STATE_ON)) {
+ set_color(LED_BLUE);
+ return;
+ }
-static void led_resume(void)
-{
- /* Assume there is no race condition with led_tick, which also
- * runs in hook_task. */
- hook_call_deferred(&led_tick_data, -1);
- if (led_auto_control_is_enabled(EC_LED_ID_POWER_LED))
- set_color(EC_LED_ID_POWER_LED, LED_GREEN, 100);
-}
-DECLARE_HOOK(HOOK_CHIPSET_RESUME, led_resume, HOOK_PRIO_DEFAULT);
+ /* Flash red on critical battery, which usually inhibits AP power-on. */
+ if (battery_is_present() != BP_YES ||
+ charge_percent < CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON) {
+ set_color(((power_ticks++ % LED_TOTAL_TICKS) < LED_ON_TICKS) ?
+ LED_RED : LED_OFF);
+ return;
+ }
-void led_alert(int enable)
-{
- if (enable) {
- /* Overwrite the current signal */
- config_tick(1 * SECOND, 100, LED_RED);
- led_tick();
- } else {
- /* Restore the previous signal */
- if (chipset_in_state(CHIPSET_STATE_ON))
- led_resume();
- else if (chipset_in_state(CHIPSET_STATE_SUSPEND))
- led_suspend();
- else if (chipset_in_state(CHIPSET_STATE_ANY_OFF))
- led_shutdown();
+ /* CHIPSET_STATE_OFF */
+ switch (chg_state) {
+ case PWR_STATE_DISCHARGE:
+ if ((charge_get_flags() & CHARGE_FLAG_EXTERNAL_POWER) &&
+ charge_percent >= BATTERY_LEVEL_NEAR_FULL)
+ cur_led_color = LED_GREEN;
+ else
+ cur_led_color = LED_OFF;
+ break;
+ case PWR_STATE_CHARGE:
+ cur_led_color = LED_RED;
+ break;
+ case PWR_STATE_ERROR:
+ cur_led_color = ((power_ticks++ % LED_TOTAL_TICKS)
+ < LED_ON_TICKS) ? LED_RED : LED_GREEN;
+ break;
+ case PWR_STATE_CHARGE_NEAR_FULL:
+ case PWR_STATE_IDLE: /* External power connected in IDLE. */
+ cur_led_color = LED_GREEN;
+ break;
+ default:
+ cur_led_color = LED_RED;
+ break;
}
-}
-void led_critical(void)
-{
- hook_call_deferred(&led_tick_data, -1);
- if (led_auto_control_is_enabled(EC_LED_ID_POWER_LED))
- set_color(EC_LED_ID_POWER_LED, LED_RED, 100);
-}
+ set_color(cur_led_color);
-static int command_led(int argc, char **argv)
-{
- enum ec_led_id id = EC_LED_ID_POWER_LED;
-
- if (argc < 2)
- return EC_ERROR_PARAM_COUNT;
-
- if (!strcasecmp(argv[1], "debug")) {
- led_auto_control(id, !led_auto_control_is_enabled(id));
- ccprintf("o%s\n", led_auto_control_is_enabled(id) ? "ff" : "n");
- } else if (!strcasecmp(argv[1], "off")) {
- set_color(id, LED_OFF, 0);
- } else if (!strcasecmp(argv[1], "red")) {
- set_color(id, LED_RED, 100);
- } else if (!strcasecmp(argv[1], "green")) {
- set_color(id, LED_GREEN, 100);
- } else if (!strcasecmp(argv[1], "amber")) {
- set_color(id, LED_AMBER, 100);
- } else if (!strcasecmp(argv[1], "alert")) {
- led_alert(1);
- } else if (!strcasecmp(argv[1], "crit")) {
- led_critical();
- } else {
- return EC_ERROR_PARAM1;
- }
- return EC_SUCCESS;
+ if (chg_state != PWR_STATE_ERROR)
+ power_ticks = 0;
}
-DECLARE_CONSOLE_COMMAND(led, command_led,
- "[debug|red|green|amber|off|alert|crit]",
- "Turn on/off LED.");
-void led_get_brightness_range(enum ec_led_id led_id, uint8_t *brightness_range)
+/**
+ * Called by hook task every 250 ms
+ */
+static void led_tick(void)
{
- brightness_range[EC_LED_COLOR_RED] = 100;
- brightness_range[EC_LED_COLOR_GREEN] = 100;
- brightness_range[EC_LED_COLOR_AMBER] = 100;
+ if (led_auto_control_is_enabled(EC_LED_ID_POWER_LED) &&
+ led_auto_control_is_enabled(EC_LED_ID_BATTERY_LED)) {
+ nautilus_led_set_power_battery();
+ }
}
-int led_set_brightness(enum ec_led_id id, const uint8_t *brightness)
-{
- if (brightness[EC_LED_COLOR_RED])
- return set_color(id, LED_RED, brightness[EC_LED_COLOR_RED]);
- else if (brightness[EC_LED_COLOR_GREEN])
- return set_color(id, LED_GREEN, brightness[EC_LED_COLOR_GREEN]);
- else if (brightness[EC_LED_COLOR_AMBER])
- return set_color(id, LED_AMBER, brightness[EC_LED_COLOR_AMBER]);
- else
- return set_color(id, LED_OFF, 0);
-}
+DECLARE_HOOK(HOOK_TICK, led_tick, HOOK_PRIO_DEFAULT);
diff --git a/board/nami/usb_pd_policy.c b/board/nami/usb_pd_policy.c
index 717a30fb22..749eaff051 100644
--- a/board/nami/usb_pd_policy.c
+++ b/board/nami/usb_pd_policy.c
@@ -3,13 +3,11 @@
* found in the LICENSE file.
*/
-#include "adc.h"
#include "atomic.h"
#include "extpower.h"
#include "charge_manager.h"
#include "common.h"
#include "console.h"
-#include "driver/tcpm/anx74xx.h"
#include "driver/tcpm/ps8xxx.h"
#include "gpio.h"
#include "hooks.h"
@@ -29,10 +27,15 @@
#define PDO_FIXED_FLAGS (PDO_FIXED_DUAL_ROLE | PDO_FIXED_DATA_SWAP |\
PDO_FIXED_COMM_CAP)
+/* TODO(crosbug.com/p/61098): fill in correct source and sink capabilities */
const uint32_t pd_src_pdo[] = {
- PDO_FIXED(5000, 3000, PDO_FIXED_FLAGS),
+ PDO_FIXED(5000, 1500, PDO_FIXED_FLAGS),
};
const int pd_src_pdo_cnt = ARRAY_SIZE(pd_src_pdo);
+const uint32_t pd_src_pdo_max[] = {
+ PDO_FIXED(5000, 3000, PDO_FIXED_FLAGS),
+};
+const int pd_src_pdo_max_cnt = ARRAY_SIZE(pd_src_pdo_max);
const uint32_t pd_snk_pdo[] = {
PDO_FIXED(5000, 500, PDO_FIXED_FLAGS),
@@ -51,20 +54,71 @@ void pd_transition_voltage(int idx)
/* No-operation: we are always 5V */
}
+static uint8_t vbus_en[CONFIG_USB_PD_PORT_COUNT];
+static uint8_t vbus_rp[CONFIG_USB_PD_PORT_COUNT] = {TYPEC_RP_1A5, TYPEC_RP_1A5};
+
int board_vbus_source_enabled(int port)
{
- if (port != 0)
- return 0;
- return gpio_get_level(GPIO_USB_C0_5V_EN);
+ return vbus_en[port];
+}
+
+static void board_vbus_update_source_current(int port)
+{
+ enum gpio_signal gpio_5v_en = port ? GPIO_USB_C1_5V_EN :
+ GPIO_USB_C0_5V_EN;
+ enum gpio_signal gpio_3a_en = port ? GPIO_USB_C1_3A_EN :
+ GPIO_USB_C0_3A_EN;
+
+ if (system_get_board_version() >= 1) {
+ /*
+ * For rev1 and beyond, 1.5 vs 3.0 A limit is controlled by a
+ * dedicated gpio where high = 3.0A and low = 1.5A. VBUS on/off
+ * is controlled by GPIO_USB_C0/1_5V_EN. Both of these signals
+ * can remain outputs.
+ */
+ gpio_set_level(gpio_3a_en, vbus_rp[port] == TYPEC_RP_3A0 ?
+ 1 : 0);
+ gpio_set_level(gpio_5v_en, vbus_en[port]);
+ } else {
+ /*
+ * 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.
+ */
+ int flags = (vbus_rp[port] == TYPEC_RP_1A5 && vbus_en[port]) ?
+ (GPIO_INPUT | GPIO_PULL_UP) :
+ (GPIO_OUTPUT | GPIO_PULL_UP);
+ gpio_set_level(gpio_5v_en, vbus_en[port]);
+ gpio_set_flags(gpio_5v_en, flags);
+ }
+}
+
+void typec_set_source_current_limit(int port, int rp)
+{
+ vbus_rp[port] = rp;
+
+ /* change the GPIO driving the load switch if needed */
+ board_vbus_update_source_current(port);
}
int pd_set_power_supply_ready(int port)
{
/* Disable charging */
- gpio_set_level(GPIO_USB_C0_CHARGE_L, 1);
+ gpio_set_level(port ? GPIO_USB_C1_CHARGE_L :
+ GPIO_USB_C0_CHARGE_L, 1);
+
+ /* Ensure we advertise the proper available current quota */
+ charge_manager_source_port(port, 1);
- /* Enable VBUS source */
- gpio_set_level(GPIO_USB_C0_5V_EN, 1);
+ /* Provide VBUS */
+ vbus_en[port] = 1;
+ board_vbus_update_source_current(port);
+
+ if (system_get_board_version() >= 2)
+ pd_set_vbus_discharge(port, 0);
/* notify host of power info change */
pd_send_host_event(PD_EVENT_POWER_CHANGE);
@@ -74,8 +128,20 @@ int pd_set_power_supply_ready(int port)
void pd_power_supply_reset(int port)
{
- /* Disable VBUS source */
- gpio_set_level(GPIO_USB_C0_5V_EN, 0);
+ int prev_en;
+
+ prev_en = vbus_en[port];
+
+ /* Disable VBUS */
+ vbus_en[port] = 0;
+ board_vbus_update_source_current(port);
+
+ /* Enable discharge if we were previously sourcing 5V */
+ if (system_get_board_version() >= 2 && prev_en)
+ pd_set_vbus_discharge(port, 1);
+
+ /* Give back the current quota we are no longer using */
+ charge_manager_source_port(port, 0);
/* notify host of power info change */
pd_send_host_event(PD_EVENT_POWER_CHANGE);
@@ -83,7 +149,8 @@ void pd_power_supply_reset(int port)
int pd_snk_is_vbus_provided(int port)
{
- return !gpio_get_level(GPIO_USB_C0_VBUS_WAKE_L);
+ return !gpio_get_level(port ? GPIO_USB_C1_VBUS_WAKE_L :
+ GPIO_USB_C0_VBUS_WAKE_L);
}
int pd_board_checks(void)
@@ -93,9 +160,6 @@ int pd_board_checks(void)
int pd_check_power_swap(int port)
{
- /* If type-c port is supplying power, we never swap PR (to source) */
- if (port == charge_manager_get_active_charge_port())
- return 0;
/*
* Allow power swap as long as we are acting as a dual role device,
* otherwise assume our role is fixed (not in S0 or console command
@@ -106,8 +170,15 @@ int pd_check_power_swap(int port)
int pd_check_data_swap(int port, int data_role)
{
- /* Allow data swap if we are a UFP, otherwise don't allow */
- return (data_role == PD_ROLE_UFP) ? 1 : 0;
+ /*
+ * Allow data swap if we are a UFP, otherwise don't allow.
+ *
+ * When we are still in the Read-Only firmware, avoid swapping roles
+ * so we don't jump in RW as a SNK/DFP and potentially confuse the
+ * power supply by sending a soft-reset with wrong data role.
+ */
+ return (data_role == PD_ROLE_UFP) &&
+ (system_get_image_copy() != SYSTEM_IMAGE_RO) ? 1 : 0;
}
int pd_check_vconn_swap(int port)
@@ -145,7 +216,9 @@ void pd_check_pr_role(int port, int pr_role, int flags)
void pd_check_dr_role(int port, int dr_role, int flags)
{
/* If UFP, try to switch to DFP */
- if ((flags & PD_FLAGS_PARTNER_DR_DATA) && dr_role == PD_ROLE_UFP)
+ if ((flags & PD_FLAGS_PARTNER_DR_DATA) &&
+ dr_role == PD_ROLE_UFP &&
+ system_get_image_copy() != SYSTEM_IMAGE_RO)
pd_request_data_swap(port);
}
/* ----------------- Vendor Defined Messages ------------------ */
@@ -219,99 +292,6 @@ int pd_custom_vdm(int port, int cnt, uint32_t *payload,
return 0;
}
-/*
- * Since fizz has no battery, it must source all of its power from either
- * USB-C or the barrel jack (preferred). Fizz operates in continuous safe
- * mode (charge_manager_leave_safe_mode() will never be called), which
- * modifies port / ILIM selection as follows:
- *
- * - Dual-role / dedicated capability of the port partner is ignored.
- * - Charge ceiling on PD voltage transition is ignored.
- * - CHARGE_PORT_NONE will never be selected.
- */
-static void board_charge_manager_init(void)
-{
- int input_voltage;
- enum charge_port input_port;
- int i, j;
- struct charge_port_info cpi = { 0 };
-
- /* Initialize all charge suppliers to 0 */
- for (i = 0; i < CHARGE_PORT_COUNT; i++) {
- for (j = 0; j < CHARGE_SUPPLIER_COUNT; j++)
- charge_manager_update_charge(j, i, &cpi);
- }
-
- input_voltage = adc_read_channel(ADC_VBUS);
- input_port = gpio_get_level(GPIO_ADP_IN_L) ?
- CHARGE_PORT_TYPEC0 : CHARGE_PORT_BARRELJACK;
- CPRINTS("Power Source: p%d (%dmV)", input_port, input_voltage);
-
- /* Initialize the power source supplier */
- switch (input_port) {
- case CHARGE_PORT_TYPEC0:
- typec_set_input_current_limit(input_port, 3000, input_voltage);
- break;
- case CHARGE_PORT_BARRELJACK:
- cpi.voltage = input_voltage;
- if (gpio_get_level(GPIO_POWER_RATE))
- cpi.current = 4620;
- else
- cpi.current = 3330;
- charge_manager_update_charge(CHARGE_SUPPLIER_DEDICATED,
- DEDICATED_CHARGE_PORT, &cpi);
- break;
- }
-}
-DECLARE_HOOK(HOOK_INIT, board_charge_manager_init, HOOK_PRIO_INIT_ADC + 1);
-
-int board_set_active_charge_port(int port)
-{
- const int active_port = charge_manager_get_active_charge_port();
-
- if (port < 0 || CHARGE_PORT_COUNT <= port)
- return EC_ERROR_INVAL;
-
- if (port == active_port)
- return EC_SUCCESS;
-
- /* Don't charge from a source port */
- if (board_vbus_source_enabled(port))
- return EC_ERROR_INVAL;
-
- CPRINTS("New charger p%d", port);
-
- switch (port) {
- case CHARGE_PORT_TYPEC0:
- gpio_set_level(GPIO_USB_C0_CHARGE_L, 0);
- gpio_set_level(GPIO_AC_JACK_CHARGE_L, 1);
- gpio_enable_interrupt(GPIO_ADP_IN_L);
- break;
- case CHARGE_PORT_BARRELJACK :
- gpio_set_level(GPIO_AC_JACK_CHARGE_L, 0);
- /* If this is switching from type-c to BJ, we have to wait until
- * PU3 comes up to keep the system continuously powered.
- * NX20P5090 datasheet says turn-on time for 20V is 29 msec. */
- if (active_port == CHARGE_PORT_TYPEC0)
- msleep(30);
- /* We don't check type-c voltage here. If it's higher than
- * BJ voltage, we'll brown out due to the reverse current
- * protection of PU3. */
- gpio_set_level(GPIO_USB_C0_CHARGE_L, 1);
- gpio_disable_interrupt(GPIO_ADP_IN_L);
- break;
- default:
- return EC_ERROR_INVAL;
- }
-
- return EC_SUCCESS;
-}
-
-int board_get_battery_soc(void)
-{
- return 100;
-}
-
#ifdef CONFIG_USB_PD_ALT_MODE_DFP
static int dp_flags[CONFIG_USB_PD_PORT_COUNT];
static uint32_t dp_status[CONFIG_USB_PD_PORT_COUNT];