summaryrefslogtreecommitdiff
path: root/board/spring
diff options
context:
space:
mode:
Diffstat (limited to 'board/spring')
l---------board/spring/Makefile1
-rw-r--r--board/spring/battery.c40
-rw-r--r--board/spring/board.c188
-rw-r--r--board/spring/board.h81
-rw-r--r--board/spring/build.mk12
-rw-r--r--board/spring/ec.tasklist25
-rw-r--r--board/spring/gpio.inc65
-rw-r--r--board/spring/led.c202
8 files changed, 0 insertions, 614 deletions
diff --git a/board/spring/Makefile b/board/spring/Makefile
deleted file mode 120000
index 94aaae2c4d..0000000000
--- a/board/spring/Makefile
+++ /dev/null
@@ -1 +0,0 @@
-../../Makefile \ No newline at end of file
diff --git a/board/spring/battery.c b/board/spring/battery.c
deleted file mode 100644
index 246552786e..0000000000
--- a/board/spring/battery.c
+++ /dev/null
@@ -1,40 +0,0 @@
-/* Copyright (c) 2013 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 Spring.
- */
-
-#include "battery.h"
-#include "battery_smart.h"
-
-/* Shutdown mode parameter to write to manufacturer access register */
-#define SB_SHUTDOWN_DATA 0x0010
-
-/* Battery temperature ranges in degrees C */
-static const struct battery_info info = {
- .start_charging_min_c = 5,
- .start_charging_max_c = 45,
- .charging_min_c = 5,
- .charging_max_c = 60,
- .discharging_min_c = 0,
- .discharging_max_c = 100,
-};
-
-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_MANUFACTURER_ACCESS, SB_SHUTDOWN_DATA);
-
- if (rv != EC_SUCCESS)
- return rv;
-
- return sb_write(SB_MANUFACTURER_ACCESS, SB_SHUTDOWN_DATA);
-}
diff --git a/board/spring/board.c b/board/spring/board.c
deleted file mode 100644
index b501574cd1..0000000000
--- a/board/spring/board.c
+++ /dev/null
@@ -1,188 +0,0 @@
-/* Copyright (c) 2013 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.
- */
-/* Spring board-specific configuration */
-
-#include "adc.h"
-#include "adc_chip.h"
-#include "board_config.h"
-#include "chipset.h"
-#include "common.h"
-#include "console.h"
-#include "extpower.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "host_command.h"
-#include "i2c.h"
-#include "keyboard_raw.h"
-#include "lid_switch.h"
-#include "pmu_tpschrome.h"
-#include "power.h"
-#include "pwm.h"
-#include "pwm_chip.h"
-#include "registers.h"
-#include "timer.h"
-#include "util.h"
-
-#define GPIO_KB_INPUT (GPIO_INPUT | GPIO_PULL_UP | GPIO_INT_BOTH)
-#define GPIO_KB_OUTPUT GPIO_ODR_HIGH
-
-#define INT_BOTH_FLOATING (GPIO_INPUT | GPIO_INT_BOTH)
-#define INT_BOTH_PULL_UP (GPIO_INPUT | GPIO_PULL_UP | GPIO_INT_BOTH)
-
-#include "gpio_list.h"
-
-/* ADC channels */
-const struct adc_t adc_channels[] = {
- /*
- * 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)},
-};
-BUILD_ASSERT(ARRAY_SIZE(adc_channels) == ADC_CH_COUNT);
-
-/* PWM channels. Must be in the exactly same order as in enum pwm_channel. */
-const struct pwm_t pwm_channels[] = {
- {STM32_TIM(3), STM32_TIM_CH(1), 0, GPIO_ILIM},
-};
-BUILD_ASSERT(ARRAY_SIZE(pwm_channels) == PWM_CH_COUNT);
-
-/* I2C ports */
-const struct i2c_port_t i2c_ports[] = {
- {"master", I2C_PORT_MASTER, 100, GPIO_I2C1_SCL, GPIO_I2C1_SDA},
-};
-const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
-
-void board_config_pre_init(void)
-{
- uint32_t val;
-
- /* Enable all GPIOs clocks */
- 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(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(GPIO_A) & ~0x00000ff0;
- val |= 0x00000890;
- STM32_GPIO_CRH(GPIO_A) = val;
-
- /* EC_INT is output, open-drain */
- val = STM32_GPIO_CRH(GPIO_B) & ~0xf0;
- val |= 0x50;
- STM32_GPIO_CRH(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(GPIO_B) & ~0xff000000;
- val |= 0xdd000000;
- STM32_GPIO_CRL(GPIO_B) = val;
- } else if (port == STM32_I2C2_PORT) {
- /* I2C2 is on PB10-11 */
- val = STM32_GPIO_CRH(GPIO_B) & ~0x0000ff00;
- val |= 0x0000dd00;
- STM32_GPIO_CRH(GPIO_B) = val;
- }
-}
-
-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);
-
-int pmu_board_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 6 hours*/
- if (!failure)
- failure = pmu_set_fastcharge(TIMEOUT_6HRS);
- /* 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;
-}
diff --git a/board/spring/board.h b/board/spring/board.h
deleted file mode 100644
index 4424817679..0000000000
--- a/board/spring/board.h
+++ /dev/null
@@ -1,81 +0,0 @@
-/* Copyright (c) 2013 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.
- */
-
-/* Spring board configuration */
-
-#ifndef __BOARD_H
-#define __BOARD_H
-
-/* 16 MHz SYSCLK clock frequency */
-#define CPU_CLOCK 16000000
-
-
-/* Debug features */
-#undef CONFIG_TASK_PROFILING
-
-/* Optional features */
-#define CONFIG_ADC
-#define CONFIG_BATTERY_CUT_OFF
-#define CONFIG_BATTERY_SMART
-#define CONFIG_BOARD_PRE_INIT
-#define CONFIG_CHARGER_TPS65090
-#define CONFIG_CHIPSET_GAIA
-#define CONFIG_CMD_BATDEBUG
-#define CONFIG_CMD_ILIM
-#define CONFIG_CMD_PMU
-#define CONFIG_CONSOLE_RESTRICTED_INPUT
-#define CONFIG_EXTPOWER_SPRING
-#define CONFIG_HOST_COMMAND_STATUS
-#define CONFIG_I2C
-#define CONFIG_I2C_PASSTHROUGH
-#define CONFIG_KEYBOARD_PROTOCOL_MKBP
-#define CONFIG_LOW_POWER_IDLE /* Use STOP mode when we have nothing to do */
-#define CONFIG_LED_DRIVER_LP5562
-#define CONFIG_PMU_HARD_RESET
-#define CONFIG_PMU_TPS65090
-#define CONFIG_PWM
-#define CONFIG_USB_SWITCH_TSU6721
-#define CONFIG_VBOOT_HASH
-
-#ifndef __ASSEMBLER__
-
-/* Keyboard output port list */
-#define KB_OUT_PORT_LIST GPIO_B, GPIO_C
-
-/* Charging */
-#define I2C_PORT_MASTER 0
-#define I2C_PORT_BATTERY I2C_PORT_MASTER
-#define I2C_PORT_CHARGER I2C_PORT_MASTER
-#define I2C_PORT_SLAVE 1
-
-/* Low battery threshold. In mAh. */
-#define BATTERY_AP_OFF_LEVEL 1
-
-/* Timer selection */
-#define TIM_CLOCK_MSB 2
-#define TIM_CLOCK_LSB 4
-#define TIM_WATCHDOG 1
-
-/* ADC signal */
-enum adc_channel {
- ADC_CH_USB_VBUS_SNS = 0,
- ADC_CH_USB_DP_SNS,
- ADC_CH_USB_DN_SNS,
- /* Number of ADC channels */
- ADC_CH_COUNT
-};
-
-/* PWM signal */
-enum pwm_channel {
- PWM_CH_ILIM = 0,
- /* Number of PWM channels */
- PWM_CH_COUNT
-};
-
-#include "gpio_signal.h"
-
-#endif /* !__ASSEMBLER__ */
-
-#endif /* __BOARD_H */
diff --git a/board/spring/build.mk b/board/spring/build.mk
deleted file mode 100644
index 2d3d6770db..0000000000
--- a/board/spring/build.mk
+++ /dev/null
@@ -1,12 +0,0 @@
-# Copyright (c) 2013 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_FAMILY:=stm32f
-CHIP_VARIANT:=stm32f100
-
-board-y=board.o battery.o led.o
diff --git a/board/spring/ec.tasklist b/board/spring/ec.tasklist
deleted file mode 100644
index f96ee6e387..0000000000
--- a/board/spring/ec.tasklist
+++ /dev/null
@@ -1,25 +0,0 @@
-/* Copyright (c) 2013 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/**
- * List of enabled tasks in the priority order
- *
- * The first one has the lowest priority.
- *
- * For each task, use the macro TASK_ALWAYS(n, r, d, s) for base tasks and
- * TASK_NOTEST(n, r, d, s) for tasks that can be excluded in test binaries,
- * where :
- * 'n' in the name of the task
- * 'r' in the main routine of the task
- * 'd' in an opaque parameter passed to the routine at startup
- * 's' is the stack size in bytes; must be a multiple of 8
- */
-#define CONFIG_TASK_LIST \
- TASK_ALWAYS(HOOKS, hook_task, NULL, LARGER_TASK_STACK_SIZE) \
- TASK_ALWAYS(CHARGER, charger_task, NULL, TASK_STACK_SIZE) \
- TASK_NOTEST(CHIPSET, chipset_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(HOSTCMD, host_command_task, NULL, TASK_STACK_SIZE) \
- TASK_ALWAYS(CONSOLE, console_task, NULL, TASK_STACK_SIZE) \
- TASK_NOTEST(KEYSCAN, keyboard_scan_task, NULL, 320)
diff --git a/board/spring/gpio.inc b/board/spring/gpio.inc
deleted file mode 100644
index cb7c2b7e94..0000000000
--- a/board/spring/gpio.inc
+++ /dev/null
@@ -1,65 +0,0 @@
-/* -*- mode:c -*-
- *
- * 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.
- */
-
-/* Inputs with interrupt handlers are first for efficiency */
-/* Keyboard power button */
-GPIO_INT(KB_PWR_ON_L, PIN(B, 5), GPIO_INT_BOTH, power_signal_interrupt)
-GPIO_INT(PP1800_LDO2, PIN(A, 1), GPIO_INT_BOTH, power_signal_interrupt) /* LDO2 is ON (end of PMIC sequence) */
-GPIO_INT(SOC1V8_XPSHOLD, PIN(A, 3), GPIO_INT_BOTH, power_signal_interrupt) /* App Processor ON */
-GPIO_INT(CHARGER_INT_L, PIN(C, 4), GPIO_INT_FALLING, pmu_irq_handler)
-GPIO_INT(LID_OPEN, PIN(C, 13), GPIO_INT_BOTH, lid_interrupt) /* LID switch detection */
-GPIO_INT(SUSPEND_L, PIN(A, 7), INT_BOTH_FLOATING, power_signal_interrupt) /* AP suspend/resume state */
-
-/* Keyboard inputs */
-GPIO_INT(KB_IN00, PIN(C, 8), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN01, PIN(C, 9), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN02, PIN(C, 10), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN03, PIN(C, 11), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN04, PIN(C, 12), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN05, PIN(C, 14), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN06, PIN(C, 15), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(KB_IN07, PIN(D, 2), GPIO_KB_INPUT, keyboard_raw_gpio_interrupt)
-GPIO_INT(USB_CHG_INT, PIN(A, 6), GPIO_INT_FALLING, extpower_interrupt)
-
-/* Other inputs */
-GPIO(BCHGR_VACG, PIN(A, 0), GPIO_INT_BOTH) /* AC good on TPSChrome */
-GPIO(WP_L, PIN(A, 13), GPIO_INPUT) /* Write protection pin (low active) */
-
-/*
- * I2C pins should be configured as inputs until I2C module is
- * initialized. This will avoid driving the lines unintentionally.
- */
-GPIO(I2C1_SCL, PIN(B, 6), GPIO_INPUT)
-GPIO(I2C1_SDA, PIN(B, 7), GPIO_INPUT)
-GPIO(I2C2_SCL, PIN(B, 10), GPIO_INPUT)
-GPIO(I2C2_SDA, PIN(B, 11), GPIO_INPUT)
-
-/* Outputs */
-GPIO(EN_PP1350, PIN(A, 14), GPIO_OUT_LOW) /* DDR 1.35v rail enable */
-GPIO(EN_PP5000, PIN(A, 11), GPIO_OUT_LOW) /* 5.0v rail enable */
-GPIO(EN_PP3300, PIN(A, 8), GPIO_OUT_LOW) /* 3.3v rail enable */
-GPIO(PMIC_PWRON_L,PIN(A, 12), GPIO_OUT_HIGH) /* 5v rail ready */
-GPIO(PMIC_RESET, PIN(A, 15), GPIO_OUT_LOW) /* Force hard reset of the pmic */
-GPIO(ENTERING_RW, PIN(D, 0), GPIO_OUT_LOW) /* EC is R/W mode for the kbc mux */
-GPIO(CHARGER_EN, PIN(B, 2), GPIO_OUT_LOW)
-GPIO(EC_INT, PIN(B, 9), GPIO_ODR_HIGH)
-GPIO(ID_MUX, PIN(D, 1), GPIO_OUT_LOW)
-GPIO(KB_OUT00, PIN(B, 0), GPIO_KB_OUTPUT)
-GPIO(KB_OUT01, PIN(B, 8), GPIO_KB_OUTPUT)
-GPIO(KB_OUT02, PIN(B, 12), GPIO_KB_OUTPUT)
-GPIO(KB_OUT03, PIN(B, 13), GPIO_KB_OUTPUT)
-GPIO(KB_OUT04, PIN(B, 14), GPIO_KB_OUTPUT)
-GPIO(KB_OUT05, PIN(B, 15), GPIO_KB_OUTPUT)
-GPIO(KB_OUT06, PIN(C, 0), GPIO_KB_OUTPUT)
-GPIO(KB_OUT07, PIN(C, 1), GPIO_KB_OUTPUT)
-GPIO(KB_OUT08, PIN(C, 2), GPIO_KB_OUTPUT)
-GPIO(KB_OUT09, PIN(B, 1), GPIO_KB_OUTPUT)
-GPIO(KB_OUT10, PIN(C, 5), GPIO_KB_OUTPUT)
-GPIO(KB_OUT11, PIN(C, 6), GPIO_KB_OUTPUT)
-GPIO(KB_OUT12, PIN(C, 7), GPIO_KB_OUTPUT)
-GPIO(BOOST_EN, PIN(B, 3), GPIO_OUT_HIGH)
-GPIO(ILIM, PIN(B, 4), GPIO_OUT_LOW)
diff --git a/board/spring/led.c b/board/spring/led.c
deleted file mode 100644
index cbb1fd9ab9..0000000000
--- a/board/spring/led.c
+++ /dev/null
@@ -1,202 +0,0 @@
-/* Copyright (c) 2013 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- *
- * Battery LED state machine to drive RGB LED on LP5562
- */
-
-#include "battery.h"
-#include "battery_smart.h"
-#include "common.h"
-#include "driver/led/lp5562.h"
-#include "extpower.h"
-#include "hooks.h"
-#include "host_command.h"
-#include "pmu_tpschrome.h"
-#include "timer.h"
-#include "util.h"
-
-#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;
-
-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;
-}
-
-/**
- * Directly read state of charge (0-100) of battery.
- */
-static int battery_state_of_charge(int *percent)
-{
- return sb_read(SB_RELATIVE_STATE_OF_CHARGE, percent);
-}
-
-/*****************************************************************************/
-/* Host commands */
-
-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 (!extpower_is_present())
- 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 (!extpower_is_present())
- 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));
-
-/*****************************************************************************/
-/* Hooks */
-
-static void 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 = extpower_is_present();
- 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_IDLE0:
- 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, battery_led_update, HOOK_PRIO_DEFAULT);