From 234841682afec177ef94960100bfea9c8bad1238 Mon Sep 17 00:00:00 2001 From: Katie Roberts-Hoffman Date: Mon, 13 Jan 2014 16:52:43 -0800 Subject: Initial skate support Just cloning spring support for now BUG=chrome-os-partner:24704 TEST=emerge-daisy_skate chromeos-ec Change-Id: Iebddb64a6913390bec925112a62c25cd24a46c40 Reviewed-on: https://chromium-review.googlesource.com/182390 Reviewed-by: Dave Parker Commit-Queue: Katie Roberts-Hoffman Tested-by: Katie Roberts-Hoffman Reviewed-by: Bernie Thompson --- board/skate/board.c | 477 ++++++++++++++++ board/skate/board.h | 198 +++++++ board/skate/build.mk | 11 + board/skate/ec.tasklist | 24 + board/skate/usb_charging.c | 1201 +++++++++++++++++++++++++++++++++++++++++ chip/stm32/keyboard_scan.c | 2 +- common/battery_skate.c | 160 ++++++ common/build.mk | 1 + common/pmu_tps65090_charger.c | 2 +- common/system_common.c | 2 +- util/flash_ec | 2 +- 11 files changed, 2076 insertions(+), 4 deletions(-) create mode 100644 board/skate/board.c create mode 100644 board/skate/board.h create mode 100644 board/skate/build.mk create mode 100644 board/skate/ec.tasklist create mode 100644 board/skate/usb_charging.c create mode 100644 common/battery_skate.c diff --git a/board/skate/board.c b/board/skate/board.c new file mode 100644 index 0000000000..99c37a6734 --- /dev/null +++ b/board/skate/board.c @@ -0,0 +1,477 @@ +/* Copyright (c) 2014 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. + */ +/* Skate board-specific configuration */ + +#include "adc.h" +#include "chipset.h" +#include "common.h" +#include "console.h" +#include "dma.h" +#include "ec_commands.h" +#include "gpio.h" +#include "hooks.h" +#include "host_command.h" +#include "i2c.h" +#include "lp5562.h" +#include "pmu_tpschrome.h" +#include "registers.h" +#include "smart_battery.h" +#include "stm32_adc.h" +#include "system.h" +#include "timer.h" +#include "util.h" + +#define GPIO_KB_INPUT (GPIO_INPUT | GPIO_PULL_UP | GPIO_INT_BOTH) +#define GPIO_KB_OUTPUT (GPIO_OUTPUT | GPIO_OPEN_DRAIN) + +#define INT_BOTH_FLOATING (GPIO_INPUT | GPIO_INT_BOTH) +#define INT_BOTH_PULL_UP (GPIO_INPUT | GPIO_PULL_UP | GPIO_INT_BOTH) + +#define HARD_RESET_TIMEOUT_MS 5 + +#define GREEN_LED_THRESHOLD 94 + +/* Minimal interval between changing LED color to green and yellow. */ +#define LED_WAIT_INTERVAL (15 * SECOND) + +/* We use yellow LED instead of blue LED. Re-map colors here. */ +#define LED_COLOR_NONE LP5562_COLOR_NONE +#define LED_COLOR_GREEN LP5562_COLOR_GREEN(0x10) +#define LED_COLOR_YELLOW LP5562_COLOR_BLUE(0x40) +#define LED_COLOR_RED LP5562_COLOR_RED(0x80) + +/* LED states */ +enum led_state_t { + LED_STATE_SOLID_RED, + LED_STATE_SOLID_GREEN, + LED_STATE_SOLID_YELLOW, + + /* Not an actual state */ + LED_STATE_OFF, + + /* Used to force next LED color update */ + LED_STATE_INVALID, +}; + +static enum led_state_t last_state = LED_STATE_OFF; +static int led_auto_control = 1; + +/* GPIO interrupt handlers prototypes */ +#ifndef CONFIG_TASK_GAIAPOWER +#define gaia_power_event NULL +#define gaia_suspend_event NULL +#define gaia_lid_event NULL +#else +void gaia_power_event(enum gpio_signal signal); +void gaia_suspend_event(enum gpio_signal signal); +void gaia_lid_event(enum gpio_signal signal); +#endif +#ifndef CONFIG_TASK_KEYSCAN +#define matrix_interrupt NULL +#endif +void usb_charge_interrupt(enum gpio_signal signal); + +/* GPIO signal list. Must match order from enum gpio_signal. */ +const struct gpio_info gpio_list[GPIO_COUNT] = { + /* Inputs with interrupt handlers are first for efficiency */ + {"KB_PWR_ON_L", GPIO_B, (1<<5), GPIO_INT_BOTH, gaia_power_event}, + {"PP1800_LDO2", GPIO_A, (1<<1), GPIO_INT_BOTH, gaia_power_event}, + {"XPSHOLD", GPIO_A, (1<<3), GPIO_INT_BOTH, gaia_power_event}, + {"CHARGER_INT", GPIO_C, (1<<4), GPIO_INT_FALLING, pmu_irq_handler}, + {"LID_OPEN", GPIO_C, (1<<13), GPIO_INT_RISING, gaia_lid_event}, + {"SUSPEND_L", GPIO_A, (1<<7), INT_BOTH_FLOATING, gaia_suspend_event}, + {"WP_L", GPIO_A, (1<<13), GPIO_INPUT, NULL}, + {"KB_IN00", GPIO_C, (1<<8), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN01", GPIO_C, (1<<9), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN02", GPIO_C, (1<<10), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN03", GPIO_C, (1<<11), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN04", GPIO_C, (1<<12), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN05", GPIO_C, (1<<14), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN06", GPIO_C, (1<<15), GPIO_KB_INPUT, matrix_interrupt}, + {"KB_IN07", GPIO_D, (1<<2), GPIO_KB_INPUT, matrix_interrupt}, + {"USB_CHG_INT", GPIO_A, (1<<6), GPIO_INT_FALLING, + usb_charge_interrupt}, + /* Other inputs */ + {"BCHGR_VACG", GPIO_A, (1<<0), GPIO_INT_BOTH, NULL}, + /* + * I2C pins should be configured as inputs until I2C module is + * initialized. This will avoid driving the lines unintentionally. + */ + {"I2C1_SCL", GPIO_B, (1<<6), GPIO_INPUT, NULL}, + {"I2C1_SDA", GPIO_B, (1<<7), GPIO_INPUT, NULL}, + {"I2C2_SCL", GPIO_B, (1<<10), GPIO_INPUT, NULL}, + {"I2C2_SDA", GPIO_B, (1<<11), GPIO_INPUT, NULL}, + /* Outputs */ + {"EN_PP1350", GPIO_A, (1<<14), GPIO_OUT_LOW, NULL}, + {"EN_PP5000", GPIO_A, (1<<11), GPIO_OUT_LOW, NULL}, + {"EN_PP3300", GPIO_A, (1<<8), GPIO_OUT_LOW, NULL}, + {"PMIC_PWRON_L",GPIO_A, (1<<12), GPIO_OUT_HIGH, NULL}, + {"PMIC_RESET", GPIO_A, (1<<15), GPIO_OUT_LOW, NULL}, + {"ENTERING_RW", GPIO_D, (1<<0), GPIO_INPUT, NULL}, + {"CHARGER_EN", GPIO_B, (1<<2), GPIO_OUT_LOW, NULL}, + {"EC_INT", GPIO_B, (1<<9), GPIO_HI_Z, NULL}, + {"ID_MUX", GPIO_D, (1<<1), GPIO_OUT_LOW, NULL}, + {"KB_OUT00", GPIO_B, (1<<0), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT01", GPIO_B, (1<<8), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT02", GPIO_B, (1<<12), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT03", GPIO_B, (1<<13), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT04", GPIO_B, (1<<14), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT05", GPIO_B, (1<<15), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT06", GPIO_C, (1<<0), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT07", GPIO_C, (1<<1), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT08", GPIO_C, (1<<2), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT09", GPIO_B, (1<<1), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT10", GPIO_C, (1<<5), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT11", GPIO_C, (1<<6), GPIO_KB_OUTPUT, NULL}, + {"KB_OUT12", GPIO_C, (1<<7), GPIO_KB_OUTPUT, NULL}, + {"BOOST_EN", GPIO_B, (1<<3), GPIO_OUT_HIGH, NULL}, + {"ILIM", GPIO_B, (1<<4), GPIO_OUT_LOW, NULL}, +}; + +/* ADC channels */ +const struct adc_t adc_channels[ADC_CH_COUNT] = { + /* + * VBUS voltage sense pin. + * Sense pin 3.3V is converted to 4096. Accounting for the 2x + * voltage divider, the conversion factor is 6600mV/4096. + */ + [ADC_CH_USB_VBUS_SNS] = {"USB_VBUS_SNS", 6600, 4096, 0, STM32_AIN(5)}, + /* Micro USB D+ sense pin. Converted to mV (3300mV/4096). */ + [ADC_CH_USB_DP_SNS] = {"USB_DP_SNS", 3300, 4096, 0, STM32_AIN(2)}, + /* Micro USB D- sense pin. Converted to mV (3300mV/4096). */ + [ADC_CH_USB_DN_SNS] = {"USB_DN_SNS", 3300, 4096, 0, STM32_AIN(4)}, +}; + +void configure_board(void) +{ + uint32_t val; + + dma_init(); + + /* Enable all GPIOs clocks + * TODO: more fine-grained enabling for power saving + */ + STM32_RCC_APB2ENR |= 0x1fd; + + /* remap OSC_IN/OSC_OUT to PD0/PD1 */ + STM32_GPIO_AFIO_MAPR |= 1 << 15; + + /* + * use PA13, PA14, PA15, PB3, PB4 as a GPIO, + * so disable JTAG and SWD + */ + STM32_GPIO_AFIO_MAPR = (STM32_GPIO_AFIO_MAPR & ~(0x7 << 24)) + | (4 << 24); + + /* remap TIM3_CH1 to PB4 */ + STM32_GPIO_AFIO_MAPR = (STM32_GPIO_AFIO_MAPR & ~(0x3 << 10)) + | (2 << 10); + + /* Analog input for ADC pins (PA2, PA4, PA5) */ + STM32_GPIO_CRL_OFF(GPIO_A) &= ~0x00ff0f00; + + /* + * Set alternate function for USART1. For alt. function input + * the port is configured in either floating or pull-up/down + * input mode (ref. section 7.1.4 in datasheet RM0041): + * PA9: Tx, alt. function output + * PA10: Rx, input with pull-down + * + * note: see crosbug.com/p/12223 for more info + */ + val = STM32_GPIO_CRH_OFF(GPIO_A) & ~0x00000ff0; + val |= 0x00000890; + STM32_GPIO_CRH_OFF(GPIO_A) = val; + + /* EC_INT is output, open-drain */ + val = STM32_GPIO_CRH_OFF(GPIO_B) & ~0xf0; + val |= 0x50; + STM32_GPIO_CRH_OFF(GPIO_B) = val; + /* put GPIO in Hi-Z state */ + gpio_set_level(GPIO_EC_INT, 1); +} + +/* GPIO configuration to be done after I2C module init */ +void board_i2c_post_init(int port) +{ + uint32_t val; + + /* enable alt. function (open-drain) */ + if (port == STM32_I2C1_PORT) { + /* I2C1 is on PB6-7 */ + val = STM32_GPIO_CRL_OFF(GPIO_B) & ~0xff000000; + val |= 0xdd000000; + STM32_GPIO_CRL_OFF(GPIO_B) = val; + } else if (port == STM32_I2C2_PORT) { + /* I2C2 is on PB10-11 */ + val = STM32_GPIO_CRH_OFF(GPIO_B) & ~0x0000ff00; + val |= 0x0000dd00; + STM32_GPIO_CRH_OFF(GPIO_B) = val; + } +} + +void board_interrupt_host(int active) +{ + /* interrupt host by using active low EC_INT signal */ + gpio_set_level(GPIO_EC_INT, !active); +} + +static void board_startup_hook(void) +{ + gpio_set_flags(GPIO_SUSPEND_L, INT_BOTH_PULL_UP); + +#ifdef CONFIG_PMU_FORCE_FET + /* Enable lcd panel power */ + pmu_enable_fet(FET_LCD_PANEL, 1, NULL); + /* Enable backlight power */ + pmu_enable_fet(FET_BACKLIGHT, 1, NULL); +#endif /* CONFIG_PMU_FORCE_FET */ +} +DECLARE_HOOK(HOOK_CHIPSET_STARTUP, board_startup_hook, HOOK_PRIO_DEFAULT); + +static void board_shutdown_hook(void) +{ +#ifdef CONFIG_PMU_FORCE_FET + /* Power off backlight power */ + pmu_enable_fet(FET_BACKLIGHT, 0, NULL); + /* Power off lcd panel */ + pmu_enable_fet(FET_LCD_PANEL, 0, NULL); +#endif /* CONFIG_PMU_FORCE_FET */ + + /* Disable pull-up on SUSPEND_L during shutdown to prevent leakage */ + gpio_set_flags(GPIO_SUSPEND_L, INT_BOTH_FLOATING); +} +DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, board_shutdown_hook, HOOK_PRIO_DEFAULT); + +/* + * Force the pmic to reset completely. This forces an entire system reset, + * and therefore should never return + */ +void board_hard_reset(void) +{ + /* record the TPS65090 reset in a backup register */ + system_set_scratchpad(system_get_scratchpad() | 0x8000); + + /* Force a hard reset of tps Chrome */ + gpio_set_level(GPIO_PMIC_RESET, 1); + + /* Delay while the power is cut */ + udelay(HARD_RESET_TIMEOUT_MS * 1000); + + /* Shouldn't get here unless the board doesn't have this capability */ + panic_puts("Hard reset failed! (this board may not be capable)\n"); +} + +#ifdef CONFIG_PMU_BOARD_INIT + +/** + * Initialize PMU register settings + * + * PMU init settings depend on board configuration. This function should be + * called inside PMU init function. + */ +int board_pmu_init(void) +{ + int failure = 0; + + /* + * Adjust charging parameters to match the expectations + * of the hardware fixing the cap ringing on DVT+ machines. + */ + failure |= pmu_set_term_current(RANGE_T01, TERM_I0875); + failure |= pmu_set_term_current(RANGE_T12, TERM_I0875); + failure |= pmu_set_term_current(RANGE_T23, TERM_I0875); + failure |= pmu_set_term_current(RANGE_T34, TERM_I0875); + failure |= pmu_set_term_current(RANGE_T40, TERM_I1000); + failure |= pmu_set_term_voltage(RANGE_T01, TERM_V2100); + failure |= pmu_set_term_voltage(RANGE_T12, TERM_V2100); + failure |= pmu_set_term_voltage(RANGE_T23, TERM_V2100); + failure |= pmu_set_term_voltage(RANGE_T34, TERM_V2100); + failure |= pmu_set_term_voltage(RANGE_T40, TERM_V2100); + + /* Set fast charging timeout to 10 hours*/ + if (!failure) + failure = pmu_set_fastcharge(TIMEOUT_10HRS); + /* Enable external gpio CHARGER_EN control */ + if (!failure) + failure = pmu_enable_ext_control(1); + /* Disable force charging */ + if (!failure) + failure = pmu_enable_charger(0); + + /* Set NOITERM bit */ + if (!failure) + failure = pmu_low_current_charging(1); + + return failure ? EC_ERROR_UNKNOWN : EC_SUCCESS; +} +#endif /* CONFIG_BOARD_PMU_INIT */ + +static int set_led_color(enum led_state_t state) +{ + int rv = EC_SUCCESS; + + if (!led_auto_control || state == last_state) + return EC_SUCCESS; + + switch (state) { + case LED_STATE_SOLID_RED: + rv = lp5562_set_color(LED_COLOR_RED); + break; + case LED_STATE_SOLID_GREEN: + rv = lp5562_set_color(LED_COLOR_GREEN); + break; + case LED_STATE_SOLID_YELLOW: + rv = lp5562_set_color(LED_COLOR_YELLOW); + break; + default: + break; + } + + if (rv == EC_SUCCESS) + last_state = state; + else + last_state = LED_STATE_INVALID; + return rv; +} + +/*****************************************************************************/ +/* Hooks */ + +static void board_battery_led_update(void) +{ + int rv; + int state_of_charge; + enum led_state_t state = LED_STATE_OFF; + + /* Current states and next states */ + static int led_power = -1; + int new_led_power; + + /* + * The time before which we should not change LED + * color between green and yellow. + */ + static timestamp_t led_update_deadline = {.val = 0}; + + /* Determine LED power */ + new_led_power = board_get_ac(); + if (new_led_power != led_power) { + if (new_led_power) { + rv = lp5562_poweron(); + } else { + rv = lp5562_poweroff(); + set_led_color(LED_STATE_OFF); + led_update_deadline.val = 0; + } + if (!rv) + led_power = new_led_power; + } + if (!new_led_power) + return; + + /* + * LED power is controlled by accessory detection. We only + * set color here. + */ + switch (charge_get_state()) { + case ST_REINIT: + case ST_BAD_COND: + case ST_PRE_CHARGING: + state = LED_STATE_SOLID_YELLOW; + break; + case ST_IDLE: + case ST_DISCHARGING: + case ST_CHARGING: + if (battery_state_of_charge(&state_of_charge)) { + /* Cannot talk to the battery. Set LED to red. */ + state = LED_STATE_SOLID_RED; + break; + } + + if (state_of_charge < GREEN_LED_THRESHOLD) + state = LED_STATE_SOLID_YELLOW; + else + state = LED_STATE_SOLID_GREEN; + break; + case ST_CHARGING_ERROR: + state = LED_STATE_SOLID_RED; + break; + } + + if (state == LED_STATE_SOLID_GREEN || + state == LED_STATE_SOLID_YELLOW) { + if (!timestamp_expired(led_update_deadline, NULL)) + return; + led_update_deadline.val = + get_time().val + LED_WAIT_INTERVAL; + } else { + led_update_deadline.val = 0; + } + + set_led_color(state); +} +DECLARE_HOOK(HOOK_SECOND, board_battery_led_update, HOOK_PRIO_DEFAULT); + +/*****************************************************************************/ +/* Host commands */ + +static int power_command_info(struct host_cmd_handler_args *args) +{ + struct ec_response_power_info *r = args->response; + + r->voltage_ac = adc_read_channel(ADC_CH_USB_VBUS_SNS); + r->voltage_system = pmu_adc_read(ADC_VAC, ADC_FLAG_KEEP_ON) + * 17000 / 1024; + r->current_system = pmu_adc_read(ADC_IAC, 0) + * (1000 / R_INPUT_MOHM) * 33 / 1024; + r->usb_dev_type = board_get_usb_dev_type(); + r->usb_current_limit = board_get_usb_current_limit(); + args->response_size = sizeof(*r); + + return EC_RES_SUCCESS; +} +DECLARE_HOST_COMMAND(EC_CMD_POWER_INFO, power_command_info, EC_VER_MASK(0)); + +static int led_command_control(struct host_cmd_handler_args *args) +{ + const struct ec_params_led_control *p = args->params; + struct ec_response_led_control *r = args->response; + int i; + uint8_t clipped[EC_LED_COLOR_COUNT]; + + /* Only support battery LED control */ + if (p->led_id != EC_LED_ID_BATTERY_LED) + return EC_RES_INVALID_PARAM; + + if (p->flags & EC_LED_FLAGS_AUTO) { + if (!board_get_ac()) + lp5562_poweroff(); + last_state = LED_STATE_OFF; + led_auto_control = 1; + } else if (!(p->flags & EC_LED_FLAGS_QUERY)) { + for (i = 0; i < EC_LED_COLOR_COUNT; ++i) + clipped[i] = MIN(p->brightness[i], 0x80); + led_auto_control = 0; + if (!board_get_ac()) + lp5562_poweron(); + if (lp5562_set_color((clipped[EC_LED_COLOR_RED] << 16) + + (clipped[EC_LED_COLOR_GREEN] << 8) + + clipped[EC_LED_COLOR_YELLOW])) + return EC_RES_ERROR; + } + + r->brightness_range[EC_LED_COLOR_RED] = 0x80; + r->brightness_range[EC_LED_COLOR_GREEN] = 0x80; + r->brightness_range[EC_LED_COLOR_BLUE] = 0x0; + r->brightness_range[EC_LED_COLOR_YELLOW] = 0x80; + r->brightness_range[EC_LED_COLOR_WHITE] = 0x0; + args->response_size = sizeof(struct ec_response_led_control); + + return EC_RES_SUCCESS; +} +DECLARE_HOST_COMMAND(EC_CMD_LED_CONTROL, + led_command_control, + EC_VER_MASK(1)); diff --git a/board/skate/board.h b/board/skate/board.h new file mode 100644 index 0000000000..bb8b71e55b --- /dev/null +++ b/board/skate/board.h @@ -0,0 +1,198 @@ +/* Copyright (c) 2014 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. + */ + +/* Skate board configuration */ + +#ifndef __BOARD_H +#define __BOARD_H + +/* 16 MHz SYSCLK clock frequency */ +#define CPU_CLOCK 16000000 + +/* Use USART1 as console serial port */ +#define CONFIG_CONSOLE_UART 1 +#define CONFIG_CONSOLE_RESTRICTED_INPUT + +/* Console is not accessible when EC is write-protected */ +#define CONFIG_CONSOLE_RESTRICTED_INPUT + +/* use I2C for host communication */ +#define CONFIG_I2C + +#define CONFIG_HOST_COMMAND_STATUS + +/* Debug features */ +#define CONFIG_PANIC_HELP +#define CONFIG_ASSERT_HELP +#define CONFIG_CONSOLE_CMDHELP + +#undef CONFIG_TASK_PROFILING +#define CONFIG_WATCHDOG_HELP + +/* Auto battery cut-off */ +#define BATTERY_CUT_OFF_MAH 10 +#define BATTERY_CUT_OFF_DELAY (15 * SECOND) +#define BATTERY_CELL_CUT_OFF_MV 3200 /* 3.2V */ + +/* use STOP mode when we have nothing to do */ +#define CONFIG_LOW_POWER_IDLE + +/* Smart battery and TPSchrome are on a private I2C bus behind the EC */ +#define CONFIG_I2C_PASSTHROUGH + +/* allow to reset scratchpad from the EC command-line */ +#define CONFIG_CMD_SCRATCHPAD + +#ifndef __ASSEMBLER__ + +/* By default, enable all console messages except keyboard */ +#define CC_DEFAULT (CC_ALL & ~CC_MASK(CC_KEYSCAN)) + +/* EC drives 13 outputs to keyboard matrix */ +#define KB_OUTPUTS 13 + +/* Charging */ +#define CONFIG_SMART_BATTERY +#define CONFIG_PMU_TPS65090 +#define CONFIG_PMU_BOARD_INIT +#define I2C_PORT_HOST 0 +#define I2C_PORT_BATTERY I2C_PORT_HOST +#define I2C_PORT_CHARGER I2C_PORT_HOST +#define I2C_PORT_SLAVE 1 + +#define CONFIG_CMD_PMU + +/* Battery */ +#define CONFIG_BATTERY_SKATE + +/* Low battery threshold. In mAh. */ +#define BATTERY_AP_OFF_LEVEL 12 + +/* Charger/accessories detection */ +#define CONFIG_TSU6721 + +/* Battery LED driver */ +#define CONFIG_LP5562 + +/* Timer selection */ +#define TIM_CLOCK_MSB 2 +#define TIM_CLOCK_LSB 4 + +/* Current sense resistor values */ +#define R_INPUT_MOHM 20 /* mOhm */ +#define R_BATTERY_MOHM 33 /* mOhm */ + +/* ADC signal */ +#define CONFIG_ADC +enum adc_channel { + ADC_CH_USB_VBUS_SNS = 0, + ADC_CH_USB_DP_SNS, + ADC_CH_USB_DN_SNS, + + ADC_CH_COUNT +}; + +/* GPIO signal list */ +enum gpio_signal { + /* Inputs with interrupt handlers are first for efficiency */ + GPIO_KB_PWR_ON_L = 0, /* Keyboard power button */ + GPIO_PP1800_LDO2, /* LDO2 is ON (end of PMIC sequence) */ + GPIO_SOC1V8_XPSHOLD, /* App Processor ON */ + GPIO_CHARGER_INT, + GPIO_LID_OPEN, /* LID switch detection */ + GPIO_SUSPEND_L, /* AP suspend/resume state */ + GPIO_WRITE_PROTECTn, /* Write protection pin (low active) */ + /* Keyboard inputs */ + GPIO_KB_IN00, + GPIO_KB_IN01, + GPIO_KB_IN02, + GPIO_KB_IN03, + GPIO_KB_IN04, + GPIO_KB_IN05, + GPIO_KB_IN06, + GPIO_KB_IN07, + GPIO_USB_CHG_INT, + /* Other inputs */ + GPIO_BCHGR_VACG, /* AC good on TPSChrome */ + GPIO_I2C1_SCL, + GPIO_I2C1_SDA, + GPIO_I2C2_SCL, + GPIO_I2C2_SDA, + /* Outputs */ + GPIO_EN_PP1350, /* DDR 1.35v rail enable */ + GPIO_EN_PP5000, /* 5.0v rail enable */ + GPIO_EN_PP3300, /* 3.3v rail enable */ + GPIO_PMIC_PWRON_L, /* 5v rail ready */ + GPIO_PMIC_RESET, /* Force hard reset of the pmic */ + GPIO_ENTERING_RW, /* EC is R/W mode for the kbc mux */ + GPIO_CHARGER_EN, + GPIO_EC_INT, + GPIO_ID_MUX, + GPIO_KB_OUT00, + GPIO_KB_OUT01, + GPIO_KB_OUT02, + GPIO_KB_OUT03, + GPIO_KB_OUT04, + GPIO_KB_OUT05, + GPIO_KB_OUT06, + GPIO_KB_OUT07, + GPIO_KB_OUT08, + GPIO_KB_OUT09, + GPIO_KB_OUT10, + GPIO_KB_OUT11, + GPIO_KB_OUT12, + GPIO_BOOST_EN, + GPIO_ILIM, + /* Number of GPIOs; not an actual GPIO */ + GPIO_COUNT +}; + +/* ILIM pin control */ +enum ilim_config { + ILIM_CONFIG_MANUAL_OFF, + ILIM_CONFIG_MANUAL_ON, + ILIM_CONFIG_PWM, +}; + +/* Forward declaration */ +enum charging_state; + +void configure_board(void); + +void matrix_interrupt(enum gpio_signal signal); + +/* Signal to AP that data is waiting */ +void board_interrupt_host(int active); + +/* Initialize PMU registers using board settings */ +int board_pmu_init(void); + +/* Force the pmu to reset everything on the board */ +void board_hard_reset(void); + +/* Set ILIM pin control type */ +void board_ilim_config(enum ilim_config config); + +/* Set PWM duty cycle */ +void board_pwm_duty_cycle(int percent); + +/* Update USB port status */ +void board_usb_charge_update(int force_update); + +/* Get USB port device type */ +int board_get_usb_dev_type(void); + +/* Get USB port current limit */ +int board_get_usb_current_limit(void); + +/* Properly limit input power on EC boot */ +void board_pwm_init_limit(void); + +/* Do we have enough AC power to boot without a battery */ +int board_has_high_power_ac(void); + +#endif /* !__ASSEMBLER__ */ + +#endif /* __BOARD_H */ diff --git a/board/skate/build.mk b/board/skate/build.mk new file mode 100644 index 0000000000..065bafa5c1 --- /dev/null +++ b/board/skate/build.mk @@ -0,0 +1,11 @@ +# Copyright (c) 2014 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 + +# the IC is STmicro STM32F100RB +CHIP:=stm32 +CHIP_VARIANT:=stm32f100 + +board-y=board.o usb_charging.o diff --git a/board/skate/ec.tasklist b/board/skate/ec.tasklist new file mode 100644 index 0000000000..1fc0597d18 --- /dev/null +++ b/board/skate/ec.tasklist @@ -0,0 +1,24 @@ +/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the LICENSE file. + */ + +/** + * List of enabled tasks in the priority order + * + * The first one has the lowest priority. + * + * For each task, use the macro TASK(n, r, d, s) where : + * 'n' in the name of the task + * 'r' in the main routine of the task + * 'd' in an opaque parameter passed to the routine at startup + * 's' is the stack size in bytes; must be a multiple of 8 + */ +#define CONFIG_TASK_LIST \ + TASK(TICK, hook_task, NULL, TASK_STACK_SIZE) \ + TASK(VBOOTHASH, vboot_hash_task, NULL, TASK_STACK_SIZE) \ + TASK(PMU_TPS65090_CHARGER, pmu_charger_task, NULL, TASK_STACK_SIZE) \ + TASK(KEYSCAN, keyboard_scan_task, NULL, 256) \ + TASK(GAIAPOWER, gaia_power_task, NULL, TASK_STACK_SIZE) \ + TASK(CONSOLE, console_task, NULL, TASK_STACK_SIZE) \ + TASK(HOSTCMD, host_command_task, NULL, TASK_STACK_SIZE) diff --git a/board/skate/usb_charging.c b/board/skate/usb_charging.c new file mode 100644 index 0000000000..01d547b41d --- /dev/null +++ b/board/skate/usb_charging.c @@ -0,0 +1,1201 @@ +/* Copyright (c) 2014 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. + */ + +/* USB charging control for skate board */ + +#include "adc.h" +#include "board.h" +#include "chipset.h" +#include "clock.h" +#include "console.h" +#include "gpio.h" +#include "hooks.h" +#include "host_command.h" +#include "keyboard_scan.h" +#include "lp5562.h" +#include "pmu_tpschrome.h" +#include "registers.h" +#include "smart_battery.h" +#include "stm32_adc.h" +#include "system.h" +#include "task.h" +#include "timer.h" +#include "tsu6721.h" +#include "util.h" + +#define PWM_FREQUENCY 32000 /* Hz */ + +/* Console output macros */ +#define CPUTS(outstr) cputs(CC_USBCHARGE, outstr) +#define CPRINTF(format, args...) cprintf(CC_USBCHARGE, format, ## args) + +/* Devices that need VBUS power */ +#define POWERED_5000_DEVICE_TYPE (TSU6721_TYPE_OTG) +#define POWERED_3300_DEVICE_TYPE (TSU6721_TYPE_JIG_UART_ON) + +/* Toad cable */ +#define TOAD_DEVICE_TYPE (TSU6721_TYPE_UART | TSU6721_TYPE_AUDIO3) + +/* Voltage threshold of D+ for video */ +#define VIDEO_ID_THRESHOLD 1300 + +/* + * Mapping from PWM duty to current: + * Current = A + B * PWM_Duty + */ +#define PWM_MAPPING_A 2958 +#define PWM_MAPPING_B (-29) + +/* Map current in milli-amps to PWM duty cycle percentage */ +#define MA_TO_PWM(curr) (((curr) - PWM_MAPPING_A) / PWM_MAPPING_B) + +/* PWM controlled current limit */ +#define I_LIMIT_100MA MA_TO_PWM(100) +#define I_LIMIT_500MA MA_TO_PWM(500) +#define I_LIMIT_1000MA MA_TO_PWM(1000) +#define I_LIMIT_1500MA MA_TO_PWM(1500) +#define I_LIMIT_2000MA MA_TO_PWM(2000) +#define I_LIMIT_2400MA MA_TO_PWM(2400) +#define I_LIMIT_3000MA 0 + +/* lower bound for PWM duty cycle : max charger current */ +#define I_LIMIT_MAX I_LIMIT_3000MA + +/* PWM control loop parameters */ +#define PWM_CTRL_MAX_DUTY I_LIMIT_100MA /* Minimum current */ +#define PWM_CTRL_BEGIN_OFFSET 90 +#define PWM_CTRL_OC_MARGIN 15 +#define PWM_CTRL_OC_DETECT_TIME (1200 * MSEC) +#define PWM_CTRL_OC_BACK_OFF 3 +#define PWM_CTRL_OC_RETRY 2 +#define PWM_CTRL_STEP_DOWN 3 +#define PWM_CTRL_STEP_UP 5 +#define PWM_CTRL_VBUS_HARD_LOW 4400 +#define PWM_CTRL_VBUS_LOW 4500 +#define PWM_CTRL_VBUS_HIGH 4700 /* Must be higher than 4.5V */ +#define PWM_CTRL_VBUS_HIGH_500MA 4550 + +/* Delay before notifying kernel of device type change */ +#define BATTERY_KEY_DELAY (PWM_CTRL_OC_DETECT_TIME + 400 * MSEC) + +/* Delay to read again ID pin when VBUS went off */ +#define ID_REDETECTION_DELAY (200 * MSEC) +/* Threshold for glitch detection on the Spring charger */ +#define SPRING_GLITCH_THR (250 * MSEC) +/* Minimum delay before allowing the charger to go off idle mode */ +#define CHARGER_IDLE_MINIMUM_PERIOD (3 * MINUTE) + +/* Delay for signals to settle */ +#define DELAY_POWER_MS 20 +#define DELAY_USB_DP_DN_MS 20 +#define DELAY_ID_MUX_MS 30 +#define CABLE_DET_POLL_MS 100 +#define CABLE_DET_POLL_COUNT 6 + +/* Battery level thresholds for S5 boost control */ +#define S5_BOOST_CTRL_LOWER_BOUND 94 +#define S5_BOOST_CTRL_UPPER_BOUND 98 + +static timestamp_t jump_time; +static int jump_pwm_duty; + +static int current_dev_type = TSU6721_TYPE_NONE; +static int nominal_pwm_duty; +static int current_pwm_duty; +static int user_pwm_duty = -1; + +static int pending_tsu6721_reset; +static int pending_adc_watchdog_disable; +static int pending_dev_type_update; +static int pending_video_power_off; +static int restore_id_mux; +static int charger_idle; /* Spring brick in idle mode */ +static timestamp_t charger_idle_time; /* last entry time in idle mode */ + +static int board_rev = 1; /* Assume new boards unless told otherwise */ + +static int s5_boost_ctrl; + +static enum { + LIMIT_NORMAL, + LIMIT_AGGRESSIVE, +} current_limit_mode = LIMIT_AGGRESSIVE; + +static enum { + ADC_WATCH_NONE, + ADC_WATCH_TOAD, + ADC_WATCH_USB, +} current_watchdog = ADC_WATCH_NONE; + +struct { + int type; + const char *name; +} const known_dev_types[] = { + {TSU6721_TYPE_OTG, "OTG"}, + {TSU6721_TYPE_USB_HOST, "USB"}, + {TSU6721_TYPE_CHG12, "Type-1/2-Chg"}, + {TSU6721_TYPE_NON_STD_CHG, "Non-Std-Chg"}, + {TSU6721_TYPE_DCP, "DCP"}, + {TSU6721_TYPE_CDP, "CDP"}, + {TSU6721_TYPE_U200_CHG, "U200-Chg"}, + {TSU6721_TYPE_APPLE_CHG, "Apple-Chg"}, + {TSU6721_TYPE_JIG_UART_ON, "Video"}, + {TSU6721_TYPE_AUDIO3, "Audio-3"}, + {TSU6721_TYPE_UART, "UART"}, + {TSU6721_TYPE_VBUS_DEBOUNCED, "Power"} }; + +/* + * Last time we see a power source removed. Also records the power source + * type and PWM duty cycle at that moment. + * Index: 0 = Unknown power source. + * 1 = Recognized power source. + */ +static timestamp_t power_removed_time[2]; +static uint32_t power_removed_type[2]; +static int power_removed_pwm_duty[2]; +static int oc_detect_retry[2] = {PWM_CTRL_OC_RETRY, PWM_CTRL_OC_RETRY}; + +/* PWM duty cycle limit based on over current event */ +static int over_current_pwm_duty; + +static enum ilim_config current_ilim_config = ILIM_CONFIG_MANUAL_OFF; + +static const int apple_charger_type[4] = {I_LIMIT_500MA, + I_LIMIT_1000MA, + I_LIMIT_2000MA, + I_LIMIT_2400MA}; + +static int video_power_enabled; + +#define NON_STD_CHARGER_REDETECT_DELAY (600 * MSEC) +static enum { + NO_REDETECT, + REDETECT_SCHEDULED, + REDETECTED, +} charger_need_redetect = NO_REDETECT; +static timestamp_t charger_redetection_time; + +static int get_video_power(void) +{ + return video_power_enabled; +} + +static void set_video_power(int enabled) +{ + int power_good; + + pmu_enable_fet(FET_VIDEO, enabled, enabled ? &power_good : NULL); + if (enabled && !power_good) + pmu_enable_fet(FET_VIDEO, 0, NULL); + video_power_enabled = enabled; +} + +static void board_ilim_use_gpio(void) +{ + /* Disable counter */ + STM32_TIM_CR1(3) &= ~0x1; + + /* Disable TIM3 clock */ + STM32_RCC_APB1ENR &= ~0x2; + + /* Switch to GPIO */ + gpio_set_flags(GPIO_ILIM, GPIO_OUTPUT); +} + +static void board_ilim_use_pwm(void) +{ + uint32_t val; + + /* Config alt. function (TIM3/PWM) */ + val = STM32_GPIO_CRL_OFF(GPIO_B) & ~0x000f0000; + val |= 0x00090000; + STM32_GPIO_CRL_OFF(GPIO_B) = val; + + /* Enable TIM3 clock */ + STM32_RCC_APB1ENR |= 0x2; + + /* Disable counter during setup */ + STM32_TIM_CR1(3) = 0x0000; + + /* + * CPU_CLOCK / (PSC + 1) determines how fast the counter operates. + * ARR determines the wave period, CCRn determines duty cycle. + * Thus, frequency = CPU_CLOCK / (PSC + 1) / ARR. + * + * Assuming 16MHz clock and ARR=100, PSC needed to achieve PWM_FREQUENCY + * is: PSC = CPU_CLOCK / PWM_FREQUENCY / ARR - 1 + */ + STM32_TIM_PSC(3) = CPU_CLOCK / PWM_FREQUENCY / 100 - 1; /* pre-scaler */ + STM32_TIM_ARR(3) = 100; /* auto-reload value */ + + /* + * Note that we don't set STM32_TIM_CCR1 here so as to prevent + * setting a wrong value. The caller of this function must ensure + * STM32_TIM_CCR1 is set correctly before calling this function. + */ + + /* CC1 configured as output, PWM mode 1, preload enable */ + STM32_TIM_CCMR1(3) = (6 << 4) | (1 << 3); + + /* CC1 output enable, active high */ + STM32_TIM_CCER(3) = (1 << 0); + + /* Generate update event to force loading of shadow registers */ + STM32_TIM_EGR(3) |= 1; + + /* Enable auto-reload preload, start counting */ + STM32_TIM_CR1(3) |= (1 << 7) | (1 << 0); +} + +void board_ilim_config(enum ilim_config config) +{ + if (config == current_ilim_config) + return; + current_ilim_config = config; + + switch (config) { + case ILIM_CONFIG_MANUAL_OFF: + case ILIM_CONFIG_MANUAL_ON: + board_ilim_use_gpio(); + gpio_set_level(GPIO_ILIM, + config == ILIM_CONFIG_MANUAL_ON ? 1 : 0); + break; + case ILIM_CONFIG_PWM: + board_ilim_use_pwm(); + break; + default: + break; + } +} + +/* Returns Apple charger current limit */ +static int board_apple_charger_current(void) +{ + int vp, vn; + int type = 0; + int data[ADC_CH_COUNT]; + + /* TODO(victoryang): Handle potential race condition. */ + tsu6721_disable_interrupts(); + tsu6721_mux(TSU6721_MUX_USB); + /* Wait 20ms for signal to stablize */ + msleep(DELAY_USB_DP_DN_MS); + adc_read_all_channels(data); + vp = data[ADC_CH_USB_DP_SNS]; + vn = data[ADC_CH_USB_DN_SNS]; + tsu6721_mux(TSU6721_MUX_AUTO); + tsu6721_enable_interrupts(); + if (vp > 1215) + type |= 0x2; + if (vn > 1215) + type |= 0x1; + + return apple_charger_type[type]; +} + +static int hard_current_limit(int limit) +{ + /* + * In aggressive mode, the PWM duty cycle goes lower than the nominal + * cycle for PWM_CTRL_OC_MARGIN. Therefore, increase duty cycle by + * PWM_CTRL_OC_MARGIN avoids going over the hard limit. + * (Note that lower PWM cycle translates to higher current) + */ + if (current_limit_mode == LIMIT_AGGRESSIVE) + return MIN(limit + PWM_CTRL_OC_MARGIN, 100); + else + return limit; +} + +static int video_dev_type(int device_type) +{ + return (device_type & ~TSU6721_TYPE_USB_HOST) | + TSU6721_TYPE_JIG_UART_ON; +} + +static int board_video_id_present(void) +{ + return adc_read_channel(ADC_CH_USB_DP_SNS) > VIDEO_ID_THRESHOLD; +} + +static int board_poll_video_id(void) +{ + int i; + for (i = 0; i < CABLE_DET_POLL_COUNT; ++i) { + msleep(CABLE_DET_POLL_MS); + if (board_video_id_present()) + return 1; + } + return 0; +} + +static int board_probe_video(int device_type) +{ + tsu6721_disable_interrupts(); + gpio_set_level(GPIO_ID_MUX, 1); + msleep(DELAY_ID_MUX_MS); + + if (board_poll_video_id()) { + /* Not USB host but video */ + device_type = video_dev_type(device_type); + return device_type; + } else { + if (adc_read_channel(ADC_CH_USB_VBUS_SNS) > 3500) { + /* + * Either USB host or video dongle. + * Leave ID_MUX high so we see the change on + * DP_SNS if any. + * + * ADC watchdog is responsible for sensing a + * detach event and switch back ID_MUX. + */ + return device_type; + } else { + /* Unhandled unpowered video dongle. Ignore it. */ + gpio_set_level(GPIO_ID_MUX, 0); + msleep(DELAY_ID_MUX_MS); + tsu6721_enable_interrupts(); + return TSU6721_TYPE_NONE; + } + } +} + +int board_has_high_power_ac(void) +{ + return board_get_usb_dev_type() & TSU6721_TYPE_CHG12; +} + +void board_pwm_duty_cycle(int percent) +{ + if (percent < I_LIMIT_MAX) + percent = I_LIMIT_MAX; + if (percent > 100) + percent = 100; + + /* + * If we are in RW, we need to prevent unsetting the PWM duty cycle RO + * set. Otherwise the EC might cut its own power when the battery is + * dead. + * + * If we jumped from RO within the last 20 seconds, only allow higher + * current than that when jumping. + */ + if (system_get_image_copy() == SYSTEM_IMAGE_RW) { + if (get_time().val - jump_time.val < (20 * SECOND) && + percent > jump_pwm_duty) + percent = MAX(jump_pwm_duty, I_LIMIT_MAX); + } + + STM32_TIM_CCR1(3) = percent; + if (current_ilim_config != ILIM_CONFIG_PWM) + board_ilim_config(ILIM_CONFIG_PWM); + current_pwm_duty = percent; +} + +void board_pwm_init_limit(void) +{ + if (system_get_image_copy() == SYSTEM_IMAGE_RW) { + jump_time = get_time(); + jump_pwm_duty = STM32_TIM_CCR1(3); + } + + /* + * put a high initial limit to avoid browning out the system + * when we turn on charging, lower power bricks might cut off + * but we will re-enable them with a lower limit later. + */ + board_pwm_duty_cycle(I_LIMIT_2400MA); +} + +/** + * Returns next lower PWM duty cycle, or -1 for unchanged duty cycle. + */ +static int board_pwm_get_next_lower(void) +{ + if (current_limit_mode == LIMIT_AGGRESSIVE) { + if (current_pwm_duty > nominal_pwm_duty - + PWM_CTRL_OC_MARGIN && + current_pwm_duty > over_current_pwm_duty && + current_pwm_duty > I_LIMIT_MAX) + return MAX(current_pwm_duty - PWM_CTRL_STEP_DOWN, + I_LIMIT_MAX); + return -1; + } else { + if (current_pwm_duty > nominal_pwm_duty && + current_pwm_duty > I_LIMIT_MAX) + return MAX(current_pwm_duty - PWM_CTRL_STEP_DOWN, + I_LIMIT_MAX); + else + return -1; + } +} + +static int board_pwm_check_vbus_high(int vbus) +{ + if (vbus > PWM_CTRL_VBUS_HIGH) + return 1; + if (vbus > PWM_CTRL_VBUS_HIGH_500MA && current_pwm_duty > I_LIMIT_500MA) + return 1; + return 0; +} + +static int board_pwm_check_vbus_low(int vbus, int battery_current) +{ + if (battery_current >= 0) + return vbus < PWM_CTRL_VBUS_LOW && current_pwm_duty < 100; + else + return vbus < PWM_CTRL_VBUS_HARD_LOW && current_pwm_duty < 100; +} + +static void board_pwm_tweak(void) +{ + int vbus, current; + int next; + + if (current_ilim_config != ILIM_CONFIG_PWM) + return; + + vbus = adc_read_channel(ADC_CH_USB_VBUS_SNS); + if (battery_current(¤t)) + current = 0; + + if (user_pwm_duty >= 0) { + if (current_pwm_duty != user_pwm_duty) + board_pwm_duty_cycle(user_pwm_duty); + return; + } + + /* + * If VBUS voltage is too low: + * - If battery is discharging, throttling more is going to draw + * more current from the battery, so do nothing unless VBUS is + * about to be lower than AC good threshold. + * - Otherwise, throttle input current to raise VBUS voltage. + * If VBUS voltage is high enough, allow more current until we hit + * current limit target. + */ + if (board_pwm_check_vbus_low(vbus, current)) { + board_pwm_duty_cycle(current_pwm_duty + PWM_CTRL_STEP_UP); + CPRINTF("[%T PWM duty up %d%%]\n", current_pwm_duty); + } else if (board_pwm_check_vbus_high(vbus)) { + next = board_pwm_get_next_lower(); + if (next >= I_LIMIT_MAX) { + board_pwm_duty_cycle(next); + CPRINTF("[%T PWM duty down %d%%]\n", current_pwm_duty); + } + } +} +DECLARE_HOOK(HOOK_SECOND, board_pwm_tweak, HOOK_PRIO_DEFAULT); + +void board_pwm_nominal_duty_cycle(int percent) +{ + int new_percent = percent; + + new_percent += PWM_CTRL_BEGIN_OFFSET; + new_percent = MIN(new_percent, PWM_CTRL_MAX_DUTY); + + board_pwm_duty_cycle(new_percent); + nominal_pwm_duty = percent; +} + +void usb_charge_interrupt(enum gpio_signal signal) +{ + task_wake(TASK_ID_PMU_TPS65090_CHARGER); +} + +static void board_adc_watch_vbus(int high, int low) +{ + adc_enable_watchdog(STM32_AIN(5), high, low); + task_clear_pending_irq(STM32_IRQ_ADC_1); + task_enable_irq(STM32_IRQ_ADC_1); +} + +static void board_adc_watch_toad(void) +{ + /* Watch VBUS and interrupt if voltage goes under 3V. */ + board_adc_watch_vbus(4095, 1800); + current_watchdog = ADC_WATCH_TOAD; +} + +static void board_adc_watch_usb(void) +{ + /* Watch VBUS and interrupt if voltage goes under 3V. */ + board_adc_watch_vbus(4095, 1800); + current_watchdog = ADC_WATCH_USB; +} + +static void board_adc_watchdog_interrupt(void) +{ + switch (current_watchdog) { + case ADC_WATCH_USB: + restore_id_mux = 1; + /* Fall through */ + case ADC_WATCH_TOAD: + pending_tsu6721_reset = 1; + pending_adc_watchdog_disable = 1; + task_disable_irq(STM32_IRQ_ADC_1); + task_wake(TASK_ID_PMU_TPS65090_CHARGER); + break; + default: + break; + } +} +DECLARE_IRQ(STM32_IRQ_ADC_1, board_adc_watchdog_interrupt, 2); + +static int usb_maybe_power_input(int dev_type) +{ + if (dev_type & TSU6721_TYPE_JIG_UART_ON) + return 1; + return (dev_type & TSU6721_TYPE_VBUS_DEBOUNCED) && + !(dev_type & POWERED_5000_DEVICE_TYPE); +} + +static int usb_has_power_input(int dev_type) +{ + return !!(usb_maybe_power_input(dev_type) && + (dev_type & TSU6721_TYPE_VBUS_DEBOUNCED)); +} + +static int usb_need_boost(int dev_type) +{ + if (dev_type & POWERED_5000_DEVICE_TYPE) + return 0; + if (chipset_in_state(CHIPSET_STATE_ON | CHIPSET_STATE_SUSPEND)) + return 1; + return (dev_type != TSU6721_TYPE_NONE); +} + +static void usb_s5_manage_boost(void) +{ + int chg, cap; + int boost = gpio_get_level(GPIO_BOOST_EN); + + if (!usb_maybe_power_input(current_dev_type)) { + if (boost) + gpio_set_level(GPIO_BOOST_EN, 0); + return; + } + + if (battery_remaining_capacity(&chg) || + battery_full_charge_capacity(&cap)) + return; + + if (boost == 0 && chg * 100 <= S5_BOOST_CTRL_LOWER_BOUND * cap) { + gpio_set_level(GPIO_BOOST_EN, 1); + gpio_set_level(GPIO_CHARGER_EN, 1); + } else if (boost == 1 && chg * 100 >= S5_BOOST_CTRL_UPPER_BOUND * cap) { + gpio_set_level(GPIO_CHARGER_EN, 0); + gpio_set_level(GPIO_BOOST_EN, 0); + } +} + +static void usb_boost_power_hook(int power_on) +{ + s5_boost_ctrl = !power_on; + if (power_on && usb_need_boost(current_dev_type)) + gpio_set_level(GPIO_BOOST_EN, 1); + else if (current_dev_type & TSU6721_TYPE_JIG_UART_ON) + set_video_power(power_on); +} + +static void usb_boost_pwr_on_hook(void) { usb_boost_power_hook(1); } +static void usb_boost_pwr_off_hook(void) { usb_boost_power_hook(0); } +DECLARE_HOOK(HOOK_CHIPSET_PRE_INIT, usb_boost_pwr_on_hook, HOOK_PRIO_DEFAULT); +DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, usb_boost_pwr_off_hook, HOOK_PRIO_DEFAULT); + +static void usb_otg_workaround(void) +{ + /* + * TSU6721 doesn't sense the removal of an OTG dongle in S5. If a + * charger is plugged in after OTG dongle is removed, we reset + * TSU6721 to force a redetection. On the other hand, if the system + * boots before a charger is plugged in, TSU6721 would report OTG + * dongle removal, and thus we don't need to do anything in this case. + */ + if ((current_dev_type & TSU6721_TYPE_OTG) && + (current_dev_type & TSU6721_TYPE_VBUS_DEBOUNCED) && + chipset_in_state(CHIPSET_STATE_ANY_OFF)) { + pending_tsu6721_reset = 1; + task_wake(TASK_ID_PMU_TPS65090_CHARGER); + } +} +DECLARE_HOOK(HOOK_SECOND, usb_otg_workaround, HOOK_PRIO_DEFAULT); + +static int usb_charger_removed(int dev_type) +{ + if (!(current_dev_type & TSU6721_TYPE_VBUS_DEBOUNCED)) + return 0; + + /* Charger is removed */ + if (dev_type == TSU6721_TYPE_NONE) + return 1; + + /* + * Device type changed from known type to unknown type. Assuming + * it went away and came back. + */ + if ((current_dev_type != TSU6721_TYPE_VBUS_DEBOUNCED) && + (dev_type == TSU6721_TYPE_VBUS_DEBOUNCED)) + return 1; + + return 0; +} + +static void check_skate_brick_deferred(void) +{ + uint8_t id = tsu6721_read(TSU6721_REG_ADC); + + if ((power_removed_type[1] & TSU6721_TYPE_CHG12) && + (current_dev_type == 0) && (id == 0x17) && !charger_idle) { + /* + * the power brick is still plugged + * but has internally cut its voltage. + */ + CPRINTF("[%T Spring brick went to IDLE\n"); + charger_idle = 1; + charger_idle_time.val = 0 /* no minimum idle period */; + } + +} +DECLARE_DEFERRED(check_skate_brick_deferred); + +/* + * When a power source is removed, record time, power source type, + * and PWM duty cycle. Then when we see a power source, compare type + * and calculate time difference to determine if we have just + * encountered an over current event. + */ +static void usb_detect_overcurrent(int dev_type) +{ + if (usb_charger_removed(dev_type)) { + int idx = !(current_dev_type == TSU6721_TYPE_VBUS_DEBOUNCED); + power_removed_time[idx] = get_time(); + power_removed_type[idx] = current_dev_type; + /* + * TODO(victoryang): Record the maximum current seen during + * retry? + */ + power_removed_pwm_duty[idx] = current_pwm_duty; + + /* + * if the Spring charger voltage went away, + * check later (after ADC re-sampling time) + * if the ID pin is still there. + */ + if (current_dev_type & TSU6721_TYPE_CHG12) + hook_call_deferred(check_skate_brick_deferred, + ID_REDETECTION_DELAY); + } else if (dev_type & TSU6721_TYPE_VBUS_DEBOUNCED) { + int idx = !(dev_type == TSU6721_TYPE_VBUS_DEBOUNCED); + timestamp_t now = get_time(); + if ((power_removed_type[1] & TSU6721_TYPE_CHG12) && + ((now.val - power_removed_time[1].val) < + SPRING_GLITCH_THR) && !charger_idle) { + /* + * the skate brick should not glitch, + * put it in idle. + */ + CPRINTF("[%T Spring brick GLITCH]\n"); + charger_idle = 1; + charger_idle_time = get_time(); + return; + } + now.val -= power_removed_time[idx].val; + if (now.val >= PWM_CTRL_OC_DETECT_TIME) { + oc_detect_retry[idx] = PWM_CTRL_OC_RETRY; + return; + } + if (power_removed_type[idx] == dev_type) { + if (oc_detect_retry[idx] > 0) { + CPRINTF("[%T USB overcurrent: Retry (%d)]\n", + oc_detect_retry[idx]); + oc_detect_retry[idx]--; + return; + } + over_current_pwm_duty = power_removed_pwm_duty[idx] + + PWM_CTRL_OC_BACK_OFF; + CPRINTF("[%T USB overcurrent: Limited to %d%%]\n", + over_current_pwm_duty); + } + } +} + +/* + * Supply 5V VBUS if needed. If we toggle power output, wait for a + * moment, and then update device type. To avoid race condition, check + * if power requirement changes during this time. + */ +static int usb_manage_boost(int dev_type) +{ + int need_boost; + int retry_limit = 3; + + do { + if (retry_limit-- <= 0) + break; + + need_boost = usb_need_boost(dev_type); + if (need_boost != gpio_get_level(GPIO_BOOST_EN)) { + gpio_set_level(GPIO_BOOST_EN, need_boost); + msleep(DELAY_POWER_MS); + dev_type = tsu6721_get_device_type(); + if (gpio_get_level(GPIO_ID_MUX)) + dev_type = video_dev_type(dev_type); + } + } while (need_boost == !usb_need_boost(dev_type)); + + return dev_type; +} + +/* Updates ILIM current limit according to device type. */ +static void usb_update_ilim(int dev_type) +{ + if (charger_idle) { + /* + * let charger in idle mode until it has been unplugged + * and re-detected. + */ + if ((dev_type == TSU6721_TYPE_VBUS_DEBOUNCED) && + ((charger_idle_time.val == 0) || + ((get_time().val - charger_idle_time.val) > + CHARGER_IDLE_MINIMUM_PERIOD))) { + charger_idle = 0; + CPRINTF("[%T RESET charger idle]\n"); + } else { + /* setting input current to 0 A */ + board_ilim_config(ILIM_CONFIG_MANUAL_ON); + CPRINTF("[%T CHARGER IDLE - ILIM 0A]\n"); + return; + } + } + + if (usb_maybe_power_input(dev_type)) { + /* Limit USB port current. 500mA for not listed types. */ + int current_limit = I_LIMIT_500MA; + if (dev_type & TSU6721_TYPE_CHG12) + current_limit = I_LIMIT_3000MA; + else if (dev_type & TSU6721_TYPE_APPLE_CHG) + current_limit = board_apple_charger_current(); + else if (dev_type & TSU6721_TYPE_CDP) + current_limit = I_LIMIT_1500MA; + else if (dev_type & TSU6721_TYPE_DCP) + current_limit = hard_current_limit(I_LIMIT_1500MA); + else if (dev_type & TSU6721_TYPE_JIG_UART_ON) + current_limit = hard_current_limit(I_LIMIT_2000MA); + else if (dev_type & TOAD_DEVICE_TYPE) + current_limit = hard_current_limit(I_LIMIT_500MA); + else if (dev_type == TSU6721_TYPE_VBUS_DEBOUNCED) + current_limit = hard_current_limit(I_LIMIT_100MA); + + board_pwm_nominal_duty_cycle(current_limit); + } else { + board_ilim_config(ILIM_CONFIG_MANUAL_ON); + } +} + +static void usb_log_dev_type(int dev_type) +{ + int i = sizeof(known_dev_types) / sizeof(known_dev_types[0]); + + CPRINTF("[%T USB: 0x%06x", dev_type); + for (--i; i >= 0; --i) + if (dev_type & known_dev_types[i].type) + CPRINTF(" %s", known_dev_types[i].name); + CPRINTF("]\n"); +} + +static void send_battery_key_deferred(void) +{ + keyboard_send_battery_key(); +} +DECLARE_DEFERRED(send_battery_key_deferred); + +static void usb_release_vac(void) +{ + gpio_set_level(GPIO_PMIC_RESET, 0); + CPRINTF("[%T Stop pulling VAC]\n"); +} +DECLARE_DEFERRED(usb_release_vac); + +static void usb_pull_vac(void) +{ + gpio_set_level(GPIO_PMIC_RESET, 1); + hook_call_deferred(usb_release_vac, 550 * MSEC); + CPRINTF("[%T Pulling VAC low]\n"); +} +DECLARE_DEFERRED(usb_pull_vac); + +static void notify_dev_type_change(int dev_type) +{ + int org_type = current_dev_type; + + current_dev_type = dev_type; + usb_log_dev_type(dev_type); + if (usb_has_power_input(org_type) != + usb_has_power_input(dev_type)) + hook_notify(HOOK_AC_CHANGE); + hook_call_deferred(send_battery_key_deferred, BATTERY_KEY_DELAY); + + /* + * If the charger is surely removed (not coming back within + * BATTERY_KEY_DELAY), pull down VAC. + */ + if (board_rev) { + if (!(dev_type & TSU6721_TYPE_VBUS_DEBOUNCED)) + hook_call_deferred(usb_pull_vac, BATTERY_KEY_DELAY); + else + hook_call_deferred(usb_pull_vac, -1); + } +} + +static int usb_want_redetect(int dev_type) +{ + if (chipset_in_state(CHIPSET_STATE_ANY_OFF) && + dev_type & TSU6721_TYPE_USB_HOST) + return 1; + return (dev_type & TSU6721_TYPE_NON_STD_CHG) || + (dev_type & TSU6721_TYPE_DCP) || + (dev_type == TSU6721_TYPE_VBUS_DEBOUNCED); +} + +static void usb_device_change(int dev_type) +{ + + if (current_dev_type == dev_type) + return; + + over_current_pwm_duty = 0; + + /* + * Video output is recognized incorrectly as USB host. When we see + * USB host, probe for video output. + */ + if (dev_type & TSU6721_TYPE_USB_HOST) + dev_type = board_probe_video(dev_type); + + usb_detect_overcurrent(dev_type); + + dev_type = usb_manage_boost(dev_type); + + /* Supply 3.3V VBUS if needed. */ + if (dev_type & POWERED_3300_DEVICE_TYPE) + set_video_power(1); + + usb_update_ilim(dev_type); + + if ((dev_type & TOAD_DEVICE_TYPE) && + (dev_type & TSU6721_TYPE_VBUS_DEBOUNCED)) + board_adc_watch_toad(); + else if (dev_type & TSU6721_TYPE_USB_HOST) + board_adc_watch_usb(); + + if (dev_type != current_dev_type) { + if (usb_want_redetect(dev_type) && + charger_need_redetect == NO_REDETECT) { + /* Schedule redetection */ + charger_need_redetect = REDETECT_SCHEDULED; + charger_redetection_time = get_time(); + charger_redetection_time.val += + NON_STD_CHARGER_REDETECT_DELAY; + } else if (!usb_want_redetect(dev_type)) { + /* Disarm redetection timer. */ + charger_need_redetect = NO_REDETECT; + } + notify_dev_type_change(dev_type); + } + + if (dev_type) + disable_sleep(SLEEP_MASK_USB_PWR); + else + enable_sleep(SLEEP_MASK_USB_PWR); +} + +static void board_usb_detach_video(void) +{ + if (!(current_dev_type & TSU6721_TYPE_JIG_UART_ON)) + return; + pending_video_power_off = 1; + restore_id_mux = 1; + pending_tsu6721_reset = 1; + task_wake(TASK_ID_PMU_TPS65090_CHARGER); +} +DECLARE_HOOK(HOOK_CHIPSET_SUSPEND, board_usb_detach_video, HOOK_PRIO_DEFAULT); +DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, board_usb_detach_video, HOOK_PRIO_DEFAULT); + +static void board_usb_monitor_detach(void) +{ + int vbus; + + if (!(current_dev_type & TSU6721_TYPE_JIG_UART_ON)) + return; + + if (!board_video_id_present()) { + board_usb_detach_video(); + return; + } + + /* Check if there is external power */ + vbus = adc_read_channel(ADC_CH_USB_VBUS_SNS); + if (get_video_power() && vbus > 4000) { + set_video_power(0); + notify_dev_type_change(current_dev_type | + TSU6721_TYPE_VBUS_DEBOUNCED); + } else if (!get_video_power() && vbus <= 4000) { + board_pwm_duty_cycle(100); + set_video_power(1); + notify_dev_type_change(current_dev_type & + ~TSU6721_TYPE_VBUS_DEBOUNCED); + } +} +DECLARE_HOOK(HOOK_SECOND, board_usb_monitor_detach, HOOK_PRIO_DEFAULT); + +static void board_usb_monitor_cable_det(void) +{ + if (!(current_dev_type & TSU6721_TYPE_USB_HOST)) + return; + + if (board_video_id_present()) + board_adc_watchdog_interrupt(); +} +DECLARE_HOOK(HOOK_SECOND, board_usb_monitor_cable_det, HOOK_PRIO_DEFAULT); + +static void board_usb_charger_redetect(void) +{ + if (charger_need_redetect != REDETECT_SCHEDULED) + return; + + if (timestamp_expired(charger_redetection_time, NULL)) { + CPRINTF("[%T USB Redetecting]\n"); + /* + * TSU6721 doesn't update device type if power or ID pin + * is present. Therefore, if the device type is the same, + * we need to reset TSU6721 to force a redetection. + */ + if (tsu6721_get_device_type() == current_dev_type) + pending_tsu6721_reset = 1; + else + pending_dev_type_update = 1; + if (gpio_get_level(GPIO_ID_MUX)) + restore_id_mux = 1; + charger_need_redetect = REDETECTED; + task_wake(TASK_ID_PMU_TPS65090_CHARGER); + } +} +DECLARE_HOOK(HOOK_SECOND, board_usb_charger_redetect, HOOK_PRIO_DEFAULT); + +void board_usb_charge_update(int force_update) +{ + int int_val = 0; + + if (restore_id_mux) { + gpio_set_level(GPIO_ID_MUX, 0); + msleep(DELAY_ID_MUX_MS); + restore_id_mux = 0; + } + + if (pending_adc_watchdog_disable) { + current_watchdog = ADC_WATCH_NONE; + adc_disable_watchdog(); + pending_adc_watchdog_disable = 0; + } + + if (pending_video_power_off) { + set_video_power(0); + pending_video_power_off = 0; + } + + if (pending_tsu6721_reset) { + tsu6721_reset(); + force_update = 1; + pending_tsu6721_reset = 0; + } + + if (pending_dev_type_update) { + force_update = 1; + pending_dev_type_update = 0; + } + + if (s5_boost_ctrl) + usb_s5_manage_boost(); + + /* + * Check device type except when: + * 1. Current device type is non-standard charger or undetermined + * charger type. This is handled by charger re-detection. + * 2. ID_MUX=1. This is handled by ADC watchdog. + */ + if (current_dev_type != TSU6721_TYPE_VBUS_DEBOUNCED && + !(current_dev_type & TSU6721_TYPE_NON_STD_CHG) && + gpio_get_level(GPIO_ID_MUX) == 0) + force_update |= (tsu6721_get_device_type() != current_dev_type); + + if (!force_update) + int_val = tsu6721_get_interrupts(); + + if (int_val & TSU6721_INT_DETACH) + usb_device_change(TSU6721_TYPE_NONE); + else if (int_val || force_update) + usb_device_change(tsu6721_get_device_type()); +} + +int board_get_usb_dev_type(void) +{ + uint8_t id = tsu6721_read(TSU6721_REG_ADC); + int dev_type = charger_idle ? 0 : current_dev_type; + + return ((int)id << 24) | dev_type; +} + +int board_get_usb_current_limit(void) +{ + /* Approximate value by PWM duty cycle */ + switch (current_ilim_config) { + case ILIM_CONFIG_MANUAL_OFF: + return 3000; + case ILIM_CONFIG_MANUAL_ON: + return 0; + case ILIM_CONFIG_PWM: + default: + return PWM_MAPPING_A + PWM_MAPPING_B * current_pwm_duty; + } +} + +int board_get_ac(void) +{ + static int last_vbus; + int vbus, vbus_good; + + if (!usb_maybe_power_input(current_dev_type)) + return 0; + + if (charger_idle) + return 0; + + /* + * UVLO is 4.1V. We consider AC bad when its voltage drops below 4.2V + * for two consecutive samples. This is to give PWM a chance to bring + * voltage up. + */ + vbus = adc_read_channel(ADC_CH_USB_VBUS_SNS); + vbus_good = (vbus >= 4200 || last_vbus >= 4200); + last_vbus = vbus; + + return vbus_good; +} + +/* + * Console commands for debugging. + * TODO(victoryang): Remove after charging control is done. + */ +static int command_ilim(int argc, char **argv) +{ + char *e; + int percent; + + if (argc >= 2) { + if (strcasecmp(argv[1], "on") == 0) + board_ilim_config(ILIM_CONFIG_MANUAL_ON); + else if (strcasecmp(argv[1], "off") == 0) + board_ilim_config(ILIM_CONFIG_MANUAL_OFF); + else { + percent = strtoi(argv[1], &e, 0); + if (*e) + return EC_ERROR_PARAM1; + board_pwm_duty_cycle(percent); + } + } + + if (current_ilim_config == ILIM_CONFIG_MANUAL_ON) + ccprintf("ILIM is GPIO high\n"); + else if (current_ilim_config == ILIM_CONFIG_MANUAL_OFF) + ccprintf("ILIM is GPIO low\n"); + else + ccprintf("ILIM is PWM duty cycle %d%%\n", STM32_TIM_CCR1(3)); + + return EC_SUCCESS; +} +DECLARE_CONSOLE_COMMAND(ilim, command_ilim, + "[percent | on | off]", + "Set or show ILIM duty cycle/GPIO value", + NULL); + +static int command_batdebug(int argc, char **argv) +{ + int val; + ccprintf("VBUS = %d mV\n", adc_read_channel(ADC_CH_USB_VBUS_SNS)); + ccprintf("VAC = %d mV\n", pmu_adc_read(ADC_VAC, ADC_FLAG_KEEP_ON) + * 17000 / 1024); + ccprintf("IAC = %d mA\n", pmu_adc_read(ADC_IAC, ADC_FLAG_KEEP_ON) + * (1000 / R_INPUT_MOHM) * 33 / 1024); + ccprintf("VBAT = %d mV\n", pmu_adc_read(ADC_VBAT, ADC_FLAG_KEEP_ON) + * 17000 / 1024); + ccprintf("IBAT = %d mA\n", pmu_adc_read(ADC_IBAT, 0) + * (1000 / R_BATTERY_MOHM) * 40 / 1024); + ccprintf("PWM = %d%%\n", STM32_TIM_CCR1(3)); + battery_current(&val); + ccprintf("Battery Current = %d mA\n", val); + battery_voltage(&val); + ccprintf("Battery Voltage= %d mV\n", val); + return EC_SUCCESS; +} +DECLARE_CONSOLE_COMMAND(batdebug, command_batdebug, + NULL, NULL, NULL); + +static int command_current_limit_mode(int argc, char **argv) +{ + if (1 == argc) { + if (current_limit_mode == LIMIT_NORMAL) + ccprintf("Normal mode\n"); + else + ccprintf("Aggressive mode\n"); + return EC_SUCCESS; + } else if (2 == argc) { + if (!strcasecmp(argv[1], "normal")) + current_limit_mode = LIMIT_NORMAL; + else if (!strcasecmp(argv[1], "aggressive")) + current_limit_mode = LIMIT_AGGRESSIVE; + else + return EC_ERROR_INVAL; + return EC_SUCCESS; + } + return EC_ERROR_INVAL; +} +DECLARE_CONSOLE_COMMAND(limitmode, command_current_limit_mode, + "[normal | aggressive]", + "Set current limit mode", + NULL); + +/*****************************************************************************/ +/* Host commands */ + +static int ext_power_command_current_limit(struct host_cmd_handler_args *args) +{ + const struct ec_params_ext_power_current_limit *p = args->params; + + if (system_is_locked()) + return EC_RES_ACCESS_DENIED; + + user_pwm_duty = ((int)(p->limit) - PWM_MAPPING_A) / PWM_MAPPING_B; + + return EC_SUCCESS; +} +DECLARE_HOST_COMMAND(EC_CMD_EXT_POWER_CURRENT_LIMIT, + ext_power_command_current_limit, + EC_VER_MASK(0)); + +static int ext_power_command_hack_board_rev(struct host_cmd_handler_args *args) +{ + const struct ec_params_hib_delay *p = args->params; + + if (p->delay_secs) + board_rev = 1; + else + board_rev = 0; + + return EC_RES_SUCCESS; +} +DECLARE_HOST_COMMAND(EC_CMD_SET_HIB_DELAY, + ext_power_command_hack_board_rev, + EC_VER_MASK(0)); diff --git a/chip/stm32/keyboard_scan.c b/chip/stm32/keyboard_scan.c index b11b7b2ccd..9fbd786c3c 100644 --- a/chip/stm32/keyboard_scan.c +++ b/chip/stm32/keyboard_scan.c @@ -76,7 +76,7 @@ struct kbc_gpio { int pin; }; -#if defined(BOARD_daisy) || defined(BOARD_snow) || defined(BOARD_spring) +#if defined(BOARD_daisy) || defined (BOARD_skate) || defined(BOARD_snow) || defined(BOARD_spring) static const uint32_t ports[] = { GPIO_B, GPIO_C, GPIO_D }; #else #error "Need to specify GPIO ports used by keyboard" diff --git a/common/battery_skate.c b/common/battery_skate.c new file mode 100644 index 0000000000..2789613b6b --- /dev/null +++ b/common/battery_skate.c @@ -0,0 +1,160 @@ +/* Copyright (c) 2014 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. + * + * Smart battery driver for Skate. + */ + +#include "battery_pack.h" +#include "chipset.h" +#include "clock.h" +#include "console.h" +#include "hooks.h" +#include "host_command.h" +#include "i2c.h" +#include "pmu_tpschrome.h" +#include "smart_battery.h" +#include "timer.h" +#include "util.h" + +#define PARAM_CUT_OFF_LOW 0x10 +#define PARAM_CUT_OFF_HIGH 0x00 + +#ifndef BATTERY_CUT_OFF_MAH +#define BATTERY_CUT_OFF_MAH 0 +#endif + +#ifndef BATTERY_CUT_OFF_DELAY +#define BATTERY_CUT_OFF_DELAY 0 +#endif + +#ifndef BATTERY_CELL_CUT_OFF_MV +#define BATTERY_CELL_CUT_OFF_MV 0 +#endif + +static timestamp_t last_cutoff; +static int has_cutoff; +static int pending_cutoff; + +int battery_cut_off(void) +{ + int rv; + uint8_t buf[3]; + + buf[0] = SB_MANUFACTURER_ACCESS & 0xff; + buf[1] = PARAM_CUT_OFF_LOW; + buf[2] = PARAM_CUT_OFF_HIGH; + + i2c_lock(); + rv = i2c_xfer(I2C_PORT_BATTERY, BATTERY_ADDR, buf, 3, NULL, 0); + rv = i2c_xfer(I2C_PORT_BATTERY, BATTERY_ADDR, buf, 3, NULL, 0); + i2c_unlock(); + + has_cutoff = 1; + last_cutoff = get_time(); + + return rv; +} + +int battery_is_cut_off(void) +{ + return has_cutoff && + get_time().val - last_cutoff.val < BATTERY_CUT_OFF_DELAY; +} + +int battery_cell_in_undervoltage(void) +{ + int i, v; + + if (BATTERY_CELL_CUT_OFF_MV) { + for (i = 0x3d; i <= 0x3f; ++i) { + if (sb_read(i, &v)) + continue; + if (v < BATTERY_CELL_CUT_OFF_MV) + return 1; + } + } + + return 0; +} + +static int battery_want_cut_off(void) +{ + int charge; + + if (battery_is_cut_off()) + return 0; + if (board_get_ac()) + return 0; + + if (BATTERY_CUT_OFF_MAH) + if (!battery_remaining_capacity(&charge) && + charge < BATTERY_CUT_OFF_MAH) + return 1; + + if (battery_cell_in_undervoltage()) + return 1; + + return 0; +} + +int battery_check_cut_off(void) +{ + if (!battery_want_cut_off()) + return 0; + ccprintf("[%T Cutting off battery]\n"); + cflush(); + battery_cut_off(); + return 1; +} + +static void cut_off_wrapper(void) +{ + battery_cut_off(); +} +DECLARE_DEFERRED(cut_off_wrapper); + +static void check_pending_cutoff(void) +{ + if (pending_cutoff) + hook_call_deferred(cut_off_wrapper, 5); +} +DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, check_pending_cutoff, HOOK_PRIO_LAST); + +int battery_command_cut_off(struct host_cmd_handler_args *args) +{ + pending_cutoff = 1; + + /* + * When cutting off the battery, the AP is off and AC is not present. + * This makes serial console unresponsive and hard to verify battery + * cut-off. Let's disable sleep here so one can check cut-off status + * if needed. This shouldn't matter because we are about to cut off + * the battery. + */ + disable_sleep(SLEEP_MASK_FORCE); + + return EC_RES_SUCCESS; +} +DECLARE_HOST_COMMAND(EC_CMD_BATTERY_CUT_OFF, battery_command_cut_off, + EC_VER_MASK(0)); + +static int command_cutoff(int argc, char **argv) +{ + int tries = 5; + + while (board_get_ac() && tries) { + ccprintf("Remove AC power in %d seconds...\n", tries); + tries--; + usleep(SECOND); + } + + if (board_get_ac()) + return EC_ERROR_UNKNOWN; + + ccprintf("Cutting off. Please wait for 10 seconds.\n"); + + return battery_cut_off(); +} +DECLARE_CONSOLE_COMMAND(cutoff, command_cutoff, NULL, + "Cut off the battery", NULL); diff --git a/common/build.mk b/common/build.mk index baa1c39e23..905067b1e0 100644 --- a/common/build.mk +++ b/common/build.mk @@ -11,6 +11,7 @@ common-y+=memory_commands.o shared_mem.o system_common.o hooks.o common-y+=gpio_commands.o version.o printf.o queue.o common-$(CONFIG_BATTERY_BQ20Z453)+=battery_bq20z453.o common-$(CONFIG_BATTERY_LINK)+=battery_link.o +common-$(CONFIG_BATTERY_SKATE)+=battery_skate.o common-$(CONFIG_BATTERY_SPRING)+=battery_spring.o common-$(CONFIG_CHARGER_BQ24725)+=charger_bq24725.o common-$(CONFIG_PMU_TPS65090)+=pmu_tps65090.o pmu_tps65090_charger.o diff --git a/common/pmu_tps65090_charger.c b/common/pmu_tps65090_charger.c index 229fc94b88..a73daa317f 100644 --- a/common/pmu_tps65090_charger.c +++ b/common/pmu_tps65090_charger.c @@ -310,7 +310,7 @@ static int calc_next_state(int state) return ST_REINIT; } -#ifdef BOARD_spring +#if defined(BOARD_skate) || defined(BOARD_spring) /* Re-init on charger timeout. */ if (pmu_is_charge_timeout()) { CPUTS("[pmu] charging: timeout\n"); diff --git a/common/system_common.c b/common/system_common.c index 003bde2c29..76cde4617a 100644 --- a/common/system_common.c +++ b/common/system_common.c @@ -303,7 +303,7 @@ static void jump_to_image(uint32_t init_addr) * EC is not in read-only firmware. (This is not technically true if * jumping from RO -> RO, but that's not a meaningful use case...) */ -#ifdef BOARD_spring +#if defined(BOARD_skate) || defined(BOARD_spring) int value; /* find whether we have a pull-up or a pull-down on the Silego side */ diff --git a/util/flash_ec b/util/flash_ec index 978d616e26..5e3969e53d 100755 --- a/util/flash_ec +++ b/util/flash_ec @@ -201,7 +201,7 @@ fi save="$(servo_save)" case "${BOARD}" in - daisy | snow | spring ) flash_daisy ;; + daisy | skate | snow | spring ) flash_daisy ;; link ) flash_link ;; *) die "board ${BOARD} not supported" ;; esac -- cgit v1.2.1