summaryrefslogtreecommitdiff
path: root/zephyr/shim/src
diff options
context:
space:
mode:
Diffstat (limited to 'zephyr/shim/src')
-rw-r--r--zephyr/shim/src/CMakeLists.txt48
-rw-r--r--zephyr/shim/src/adc.c83
-rw-r--r--zephyr/shim/src/battery.c69
-rw-r--r--zephyr/shim/src/cbi.c22
-rw-r--r--zephyr/shim/src/console.c353
-rw-r--r--zephyr/shim/src/console_buffer.c128
-rw-r--r--zephyr/shim/src/crc.c21
-rw-r--r--zephyr/shim/src/espi.c563
-rw-r--r--zephyr/shim/src/fan.c380
-rw-r--r--zephyr/shim/src/flash.c150
-rw-r--r--zephyr/shim/src/gpio.c441
-rw-r--r--zephyr/shim/src/gpio_id.c73
-rw-r--r--zephyr/shim/src/hooks.c122
-rw-r--r--zephyr/shim/src/host_command.c16
-rw-r--r--zephyr/shim/src/hwtimer.c29
-rw-r--r--zephyr/shim/src/i2c.c135
-rw-r--r--zephyr/shim/src/keyboard_raw.c77
-rw-r--r--zephyr/shim/src/keyscan.c34
-rw-r--r--zephyr/shim/src/libgcc_arm.S11
-rw-r--r--zephyr/shim/src/mkbp_event.c16
-rw-r--r--zephyr/shim/src/motionsense_driver/bma255-drvinfo.inc44
-rw-r--r--zephyr/shim/src/motionsense_driver/bmi160-drvinfo.inc57
-rw-r--r--zephyr/shim/src/motionsense_driver/bmi260-drvinfo.inc57
-rw-r--r--zephyr/shim/src/motionsense_driver/drvdata-accelgyro.h127
-rw-r--r--zephyr/shim/src/motionsense_driver/kx022-drvinfo.inc44
-rw-r--r--zephyr/shim/src/motionsense_driver/lis2dw12-drvinfo.inc44
-rw-r--r--zephyr/shim/src/motionsense_driver/sensor_drv_list.inc39
-rw-r--r--zephyr/shim/src/motionsense_driver/tcs3400-drvinfo.inc79
-rw-r--r--zephyr/shim/src/motionsense_sensors.c403
-rw-r--r--zephyr/shim/src/panic.c160
-rw-r--r--zephyr/shim/src/pwm.c190
-rw-r--r--zephyr/shim/src/pwm_led.c60
-rw-r--r--zephyr/shim/src/rtc.c235
-rw-r--r--zephyr/shim/src/switchcap_gpio.c47
-rw-r--r--zephyr/shim/src/switchcap_ln9310.c49
-rw-r--r--zephyr/shim/src/system.c378
-rw-r--r--zephyr/shim/src/tasks.c353
-rw-r--r--zephyr/shim/src/temp_sensors.c52
-rw-r--r--zephyr/shim/src/test_util.c20
-rw-r--r--zephyr/shim/src/thermal.c52
-rw-r--r--zephyr/shim/src/watchdog.c78
-rw-r--r--zephyr/shim/src/ztest_system.c69
42 files changed, 0 insertions, 5408 deletions
diff --git a/zephyr/shim/src/CMakeLists.txt b/zephyr/shim/src/CMakeLists.txt
deleted file mode 100644
index e30671c6d6..0000000000
--- a/zephyr/shim/src/CMakeLists.txt
+++ /dev/null
@@ -1,48 +0,0 @@
-# Copyright 2020 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.
-
-zephyr_library_sources(console.c)
-zephyr_library_sources(crc.c)
-zephyr_library_sources(gpio.c)
-zephyr_library_sources(gpio_id.c)
-
-if (DEFINED CONFIG_ARCH_POSIX)
- zephyr_library_sources(ztest_system.c)
-else()
- zephyr_library_sources(system.c)
- zephyr_library_sources("${PLATFORM_EC}/common/system.c")
-endif()
-zephyr_library_sources_ifdef(no_libgcc libgcc_${ARCH}.S)
-
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_ADC adc.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_BATTERY_FUEL_GAUGE
- battery.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_CBI_EEPROM cbi.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_CBI_GPIO cbi.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_ESPI espi.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_FAN fan.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_FLASH_CROS flash.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_HOOKS hooks.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_HOSTCMD host_command.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_HOSTCMD_CONSOLE
- console_buffer.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_KEYBOARD keyboard_raw.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_KEYBOARD keyscan.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_MKBP_EVENT mkbp_event.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_MOTIONSENSE
- motionsense_sensors.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_PANIC panic.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_PWM pwm.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_LED_COMMON pwm_led.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_RTC rtc.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_SWITCHCAP_GPIO
- switchcap_gpio.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_SWITCHCAP_LN9310
- switchcap_ln9310.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_TEMP_SENSOR temp_sensors.c
- thermal.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_TIMER hwtimer.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_I2C i2c.c)
-zephyr_library_sources_ifdef(CONFIG_SHIMMED_TASKS tasks.c)
-zephyr_library_sources_ifdef(CONFIG_PLATFORM_EC_WATCHDOG watchdog.c)
diff --git a/zephyr/shim/src/adc.c b/zephyr/shim/src/adc.c
deleted file mode 100644
index 4f66774466..0000000000
--- a/zephyr/shim/src/adc.c
+++ /dev/null
@@ -1,83 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <drivers/adc.h>
-#include <logging/log.h>
-#include "adc.h"
-#include "zephyr_adc.h"
-
-LOG_MODULE_REGISTER(shim_adc, LOG_LEVEL_ERR);
-
-#define ADC_NODE DT_NODELABEL(adc0)
-const struct device *adc_dev;
-
-#define HAS_NAMED_ADC_CHANNELS DT_NODE_EXISTS(DT_INST(0, named_adc_channels))
-
-#if HAS_NAMED_ADC_CHANNELS
-#define ADC_CHANNEL_COMMA(node_id) \
- [ZSHIM_ADC_ID(node_id)] = { \
- .name = DT_LABEL(node_id), \
- .input_ch = DT_PROP(node_id, channel), \
- .factor_mul = DT_PROP(node_id, mul), \
- .factor_div = DT_PROP(node_id, div), \
- .channel_cfg = { \
- .channel_id = DT_PROP(node_id, channel), \
- .gain = DT_STRING_TOKEN(node_id, gain), \
- .reference = DT_STRING_TOKEN(node_id, reference), \
- .acquisition_time = \
- DT_PROP(node_id, acquisition_time), \
- .differential = DT_PROP(node_id, differential), \
- }, \
- },
-#ifdef CONFIG_ADC_CHANNELS_RUNTIME_CONFIG
-struct adc_t adc_channels[] = { DT_FOREACH_CHILD(
- DT_INST(0, named_adc_channels), ADC_CHANNEL_COMMA) };
-#else
-const struct adc_t adc_channels[] = { DT_FOREACH_CHILD(
- DT_INST(0, named_adc_channels), ADC_CHANNEL_COMMA) };
-#endif
-#endif /* named_adc_channels */
-
-static int init_device_bindings(const struct device *device)
-{
- ARG_UNUSED(device);
- adc_dev = DEVICE_DT_GET(ADC_NODE);
-
- if (!device_is_ready(adc_dev)) {
- LOG_ERR("Error: device %s is not ready", adc_dev->name);
- return -1;
- }
-
-#if HAS_NAMED_ADC_CHANNELS
- for (int i = 0; i < ARRAY_SIZE(adc_channels); i++)
- adc_channel_setup(adc_dev, &adc_channels[i].channel_cfg);
-#endif
-
- return 0;
-}
-SYS_INIT(init_device_bindings, POST_KERNEL, 51);
-
-int adc_read_channel(enum adc_channel ch)
-{
- int ret = 0, rv;
- struct adc_sequence seq = {
- .options = NULL,
- .channels = BIT(adc_channels[ch].input_ch),
- .buffer = &ret,
- .buffer_size = sizeof(ret),
- .resolution = CONFIG_PLATFORM_EC_ADC_RESOLUTION,
- .oversampling = CONFIG_PLATFORM_EC_ADC_OVERSAMPLING,
- .calibrate = false,
- };
-
- rv = adc_read(adc_dev, &seq);
- if (rv)
- return rv;
-
- adc_raw_to_millivolts(adc_ref_internal(adc_dev), ADC_GAIN_1,
- CONFIG_PLATFORM_EC_ADC_RESOLUTION, &ret);
- ret = (ret * adc_channels[ch].factor_mul) / adc_channels[ch].factor_div;
- return ret;
-}
diff --git a/zephyr/shim/src/battery.c b/zephyr/shim/src/battery.c
deleted file mode 100644
index 6c4f211eda..0000000000
--- a/zephyr/shim/src/battery.c
+++ /dev/null
@@ -1,69 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include<devicetree.h>
-#include"battery_fuel_gauge.h"
-
-#if DT_NODE_EXISTS(DT_PATH(batteries))
-
-#define NODE_FUEL_GAUGE(node) \
-{ \
- .manuf_name = DT_PROP(node, manuf_name), \
- .device_name = DT_PROP(node, device_name), \
- .ship_mode = { \
- .wb_support = DT_PROP_OR(node, ship_mode_wb_support, 0), \
- .reg_addr = DT_PROP(node, ship_mode_reg_addr), \
- .reg_data = DT_PROP(node, ship_mode_reg_data), \
- }, \
- .sleep_mode = { \
- .sleep_supported = DT_PROP_OR(node, sleep_mode_supported, 0), \
- .reg_addr = DT_PROP_OR(node, sleep_mode_reg_addr, 0), \
- .reg_data = DT_PROP_OR(node, sleep_mode_reg_data, 0), \
- }, \
- .fet = { \
- .mfgacc_support = DT_PROP_OR(node, fet_mgfacc_support, 0), \
- .reg_addr = DT_PROP_OR(node, fet_reg_addr, 0), \
- .reg_mask = DT_PROP(node, fet_reg_mask), \
- .disconnect_val = DT_PROP(node, fet_disconnect_val), \
- .cfet_mask = DT_PROP_OR(node, fet_cfet_mask, 0), \
- .cfet_off_val = DT_PROP_OR(node, fet_cfet_off_val, 0), \
- }, \
- COND_CODE_1(UTIL_AND(IS_ENABLED(CONFIG_BATTERY_MEASURE_IMBALANCE), \
- DT_NODE_HAS_PROP(node, imbalance_mv)), \
- (.imbalance_mv = DT_STRING_TOKEN(node, imbalance_mv),), ()) \
-},
-
-#define NODE_BATT_INFO(node) \
-{ \
- .voltage_max = DT_PROP(node, voltage_max), \
- .voltage_normal = DT_PROP(node, voltage_normal), \
- .voltage_min = DT_PROP(node, voltage_min), \
- .precharge_voltage = DT_PROP_OR(node, precharge_voltage, 0), \
- .precharge_current = DT_PROP_OR(node, precharge_current, 0), \
- .start_charging_min_c = DT_PROP(node, start_charging_min_c), \
- .start_charging_max_c = DT_PROP(node, start_charging_max_c), \
- .charging_min_c = DT_PROP(node, charging_min_c), \
- .charging_max_c = DT_PROP(node, charging_max_c), \
- .discharging_min_c = DT_PROP(node, discharging_min_c), \
- .discharging_max_c = DT_PROP(node, discharging_max_c), \
-},
-
-#define NODE_BATT_PARAMS(node) \
-{ \
- .fuel_gauge = NODE_FUEL_GAUGE(node) \
- .batt_info = NODE_BATT_INFO(node) \
-},
-
-const struct board_batt_params board_battery_info[] = {
- DT_FOREACH_CHILD(DT_PATH(batteries), NODE_BATT_PARAMS)
-};
-
-#if DT_NODE_EXISTS(DT_NODELABEL(default_battery))
-#define BAT_ENUM(node) DT_CAT(BATTERY_, node)
-const enum battery_type DEFAULT_BATTERY_TYPE =
- BATTERY_TYPE(DT_NODELABEL(default_battery));
-#endif
-
-#endif /* DT_NODE_EXISTS(DT_PATH(batteries)) */
diff --git a/zephyr/shim/src/cbi.c b/zephyr/shim/src/cbi.c
deleted file mode 100644
index e9d85b6088..0000000000
--- a/zephyr/shim/src/cbi.c
+++ /dev/null
@@ -1,22 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <drivers/cros_cbi.h>
-#include <logging/log.h>
-#include "hooks.h"
-
-LOG_MODULE_REGISTER(shim_cbi, LOG_LEVEL_ERR);
-
-static void cbi_dev_init(void)
-{
- const struct device *dev = device_get_binding(CROS_CBI_LABEL);
-
- if (!dev)
- LOG_ERR("Fail to find %s", CROS_CBI_LABEL);
-
- cros_cbi_init(dev);
-}
-
-DECLARE_HOOK(HOOK_INIT, cbi_dev_init, HOOK_PRIO_FIRST);
diff --git a/zephyr/shim/src/console.c b/zephyr/shim/src/console.c
deleted file mode 100644
index 3fc3896ec2..0000000000
--- a/zephyr/shim/src/console.c
+++ /dev/null
@@ -1,353 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <device.h>
-#include <drivers/uart.h>
-#include <shell/shell.h>
-#include <shell/shell_uart.h>
-#include <stdbool.h>
-#include <string.h>
-#include <sys/printk.h>
-#include <sys/ring_buffer.h>
-#include <zephyr.h>
-#include <logging/log.h>
-
-#include "console.h"
-#include "printf.h"
-#include "uart.h"
-#include "usb_console.h"
-#include "zephyr_console_shim.h"
-
-LOG_MODULE_REGISTER(shim_console, LOG_LEVEL_ERR);
-
-static const struct device *uart_shell_dev =
- DEVICE_DT_GET(DT_CHOSEN(zephyr_shell_uart));
-static const struct shell *shell_zephyr;
-static struct k_poll_signal shell_uninit_signal;
-static struct k_poll_signal shell_init_signal;
-RING_BUF_DECLARE(rx_buffer, CONFIG_UART_RX_BUF_SIZE);
-
-static void uart_rx_handle(const struct device *dev)
-{
- static uint8_t scratch;
- static uint8_t *data;
- static uint32_t len, rd_len;
-
- do {
- /* Get some bytes on the ring buffer */
- len = ring_buf_put_claim(&rx_buffer, &data, rx_buffer.size);
- if (len > 0) {
- /* Read from the FIFO up to `len` bytes */
- rd_len = uart_fifo_read(dev, data, len);
-
- /* Put `rd_len` bytes on the ring buffer */
- ring_buf_put_finish(&rx_buffer, rd_len);
- } else {
- /*
- * There's no room on the ring buffer, throw away 1
- * byte.
- */
- rd_len = uart_fifo_read(dev, &scratch, 1);
- }
- } while (rd_len != 0 && rd_len == len);
-}
-
-static void uart_callback(const struct device *dev, void *user_data)
-{
- uart_irq_update(dev);
-
- if (uart_irq_rx_ready(dev))
- uart_rx_handle(dev);
-}
-
-static void shell_uninit_callback(const struct shell *shell, int res)
-{
- if (!res) {
- /* Set the new callback */
- uart_irq_callback_user_data_set(uart_shell_dev, uart_callback,
- NULL);
-
- /*
- * Disable TX interrupts. We don't actually use TX but for some
- * reason none of this works without this line.
- */
- uart_irq_tx_disable(uart_shell_dev);
-
- /* Enable RX interrupts */
- uart_irq_rx_enable(uart_shell_dev);
- }
-
- /* Notify the uninit signal that we finished */
- k_poll_signal_raise(&shell_uninit_signal, res);
-}
-
-int uart_shell_stop(void)
-{
- struct k_poll_event event = K_POLL_EVENT_INITIALIZER(
- K_POLL_TYPE_SIGNAL, K_POLL_MODE_NOTIFY_ONLY,
- &shell_uninit_signal);
-
- /* Clear all pending input */
- uart_clear_input();
-
- /* Disable RX and TX interrupts */
- uart_irq_rx_disable(uart_shell_dev);
- uart_irq_tx_disable(uart_shell_dev);
-
- /* Initialize the uninit signal */
- k_poll_signal_init(&shell_uninit_signal);
-
- /* Stop the shell */
- shell_uninit(shell_backend_uart_get_ptr(), shell_uninit_callback);
-
- /* Wait for the shell to be turned off, the signal will wake us */
- k_poll(&event, 1, K_FOREVER);
-
- /* Event was signaled, return the result */
- return event.signal->result;
-}
-
-static void shell_init_from_work(struct k_work *work)
-{
- bool log_backend = CONFIG_SHELL_BACKEND_SERIAL_LOG_LEVEL > 0;
- uint32_t level;
- ARG_UNUSED(work);
-
- if (CONFIG_SHELL_BACKEND_SERIAL_LOG_LEVEL > LOG_LEVEL_DBG) {
- level = CONFIG_LOG_MAX_LEVEL;
- } else {
- level = CONFIG_SHELL_BACKEND_SERIAL_LOG_LEVEL;
- }
-
- /* Initialize the shell and re-enable both RX and TX */
- shell_init(shell_backend_uart_get_ptr(), uart_shell_dev, false,
- log_backend, level);
- uart_irq_rx_enable(uart_shell_dev);
- uart_irq_tx_enable(uart_shell_dev);
-
- /* Notify the init signal that initialization is complete */
- k_poll_signal_raise(&shell_init_signal, 0);
-}
-
-void uart_shell_start(void)
-{
- static struct k_work shell_init_work;
- struct k_poll_event event = K_POLL_EVENT_INITIALIZER(
- K_POLL_TYPE_SIGNAL, K_POLL_MODE_NOTIFY_ONLY,
- &shell_init_signal);
-
- /* Disable RX and TX interrupts */
- uart_irq_rx_disable(uart_shell_dev);
- uart_irq_tx_disable(uart_shell_dev);
-
- /* Initialize k_work to call shell init (this makes it thread safe) */
- k_work_init(&shell_init_work, shell_init_from_work);
-
- /* Initialize the init signal to make sure we're read to listen */
- k_poll_signal_init(&shell_init_signal);
-
- /* Submit the work to be run by the kernel */
- k_work_submit(&shell_init_work);
-
- /* Wait for initialization to be run, the signal will wake us */
- k_poll(&event, 1, K_FOREVER);
-}
-
-int zshim_run_ec_console_command(const struct zephyr_console_command *command,
- size_t argc, char **argv)
-{
- /*
- * The Zephyr shell only displays the help string and not
- * the argument descriptor when passing "-h" or "--help". Mimic the
- * cros-ec behavior by displaying both the user types "<command> help",
- */
-#ifdef CONFIG_SHELL_HELP
- for (int i = 1; i < argc; i++) {
- if (!command->help && !command->argdesc)
- break;
- if (!strcmp(argv[i], "help")) {
- if (command->help)
- printk("%s\n", command->help);
- if (command->argdesc)
- printk("Usage: %s\n", command->argdesc);
- return 0;
- }
- }
-#endif
-
- return command->handler(argc, argv);
-}
-
-#if defined(CONFIG_CONSOLE_CHANNEL) && DT_NODE_EXISTS(DT_PATH(ec_console))
-#define EC_CONSOLE DT_PATH(ec_console)
-
-static const char * const disabled_channels[] = DT_PROP(EC_CONSOLE, disabled);
-static const size_t disabled_channel_count = DT_PROP_LEN(EC_CONSOLE, disabled);
-static int init_ec_console(const struct device *unused)
-{
- for (size_t i = 0; i < disabled_channel_count; i++)
- console_channel_disable(disabled_channels[i]);
-
- return 0;
-} SYS_INIT(init_ec_console, PRE_KERNEL_1, 50);
-#endif /* CONFIG_CONSOLE_CHANNEL && DT_NODE_EXISTS(DT_PATH(ec_console)) */
-
-static int init_ec_shell(const struct device *unused)
-{
- shell_zephyr = shell_backend_uart_get_ptr();
- return 0;
-} SYS_INIT(init_ec_shell, PRE_KERNEL_1, 50);
-
-void uart_tx_start(void)
-{
-}
-
-int uart_tx_ready(void)
-{
- return 1;
-}
-
-int uart_tx_char_raw(void *context, int c)
-{
- uart_write_char(c);
- return 0;
-}
-
-void uart_write_char(char c)
-{
- printk("%c", c);
-
- if (IS_ENABLED(CONFIG_PLATFORM_EC_HOSTCMD_CONSOLE))
- console_buf_notify_chars(&c, 1);
-}
-
-void uart_flush_output(void)
-{
- shell_process(shell_zephyr);
- uart_tx_flush();
-}
-
-void uart_tx_flush(void)
-{
- while (!uart_irq_tx_complete(uart_shell_dev))
- ;
-}
-
-int uart_getc(void)
-{
- uint8_t c;
-
- if (ring_buf_get(&rx_buffer, &c, 1)) {
- return c;
- }
- return -1;
-}
-
-void uart_clear_input(void)
-{
- /* Clear any remaining shell processing. */
- shell_process(shell_zephyr);
- ring_buf_reset(&rx_buffer);
-}
-
-static void handle_sprintf_rv(int rv, size_t *len)
-{
- if (rv < 0) {
- LOG_ERR("Print buffer is too small");
- *len = CONFIG_SHELL_PRINTF_BUFF_SIZE;
- } else {
- *len += rv;
- }
-}
-
-static void zephyr_print(const char *buff, size_t size)
-{
- /*
- * shell_* functions can not be used in ISRs so use printk instead.
- * Also, console_buf_notify_chars uses a mutex, which may not be
- * locked in ISRs.
- */
- if (k_is_in_isr() || shell_zephyr->ctx->state != SHELL_STATE_ACTIVE) {
- printk("%s", buff);
- } else {
- /*
- * On some platforms, shell_* functions are not as fast
- * as printk and they need the added speed to avoid
- * timeouts.
- */
- if (IS_ENABLED(CONFIG_PLATFORM_EC_CONSOLE_USES_PRINTK))
- printk("%s", buff);
- else
- shell_fprintf(shell_zephyr, SHELL_NORMAL, "%s", buff);
- if (IS_ENABLED(CONFIG_PLATFORM_EC_HOSTCMD_CONSOLE))
- console_buf_notify_chars(buff, size);
- }
-}
-
-#if defined(CONFIG_USB_CONSOLE) || defined(CONFIG_USB_CONSOLE_STREAM)
-BUILD_ASSERT(0, "USB console is not supported with Zephyr");
-#endif /* defined(CONFIG_USB_CONSOLE) || defined(CONFIG_USB_CONSOLE_STREAM) */
-
-int cputs(enum console_channel channel, const char *outstr)
-{
- /* Filter out inactive channels */
- if (console_channel_is_disabled(channel))
- return EC_SUCCESS;
-
- zephyr_print(outstr, strlen(outstr));
-
- return 0;
-}
-
-int cprintf(enum console_channel channel, const char *format, ...)
-{
- int rv;
- va_list args;
- size_t len = 0;
- char buff[CONFIG_SHELL_PRINTF_BUFF_SIZE];
-
- /* Filter out inactive channels */
- if (console_channel_is_disabled(channel))
- return EC_SUCCESS;
-
- va_start(args, format);
- rv = crec_vsnprintf(buff, CONFIG_SHELL_PRINTF_BUFF_SIZE, format, args);
- va_end(args);
- handle_sprintf_rv(rv, &len);
-
- zephyr_print(buff, len);
-
- return rv > 0 ? EC_SUCCESS : rv;
-}
-
-int cprints(enum console_channel channel, const char *format, ...)
-{
- int rv;
- va_list args;
- char buff[CONFIG_SHELL_PRINTF_BUFF_SIZE];
- size_t len = 0;
-
- /* Filter out inactive channels */
- if (console_channel_is_disabled(channel))
- return EC_SUCCESS;
-
- rv = crec_snprintf(buff, CONFIG_SHELL_PRINTF_BUFF_SIZE, "[%pT ",
- PRINTF_TIMESTAMP_NOW);
- handle_sprintf_rv(rv, &len);
-
- va_start(args, format);
- rv = crec_vsnprintf(buff + len, CONFIG_SHELL_PRINTF_BUFF_SIZE - len,
- format, args);
- va_end(args);
- handle_sprintf_rv(rv, &len);
-
- rv = crec_snprintf(buff + len, CONFIG_SHELL_PRINTF_BUFF_SIZE - len,
- "]\n");
- handle_sprintf_rv(rv, &len);
-
- zephyr_print(buff, len);
-
- return rv > 0 ? EC_SUCCESS : rv;
-}
diff --git a/zephyr/shim/src/console_buffer.c b/zephyr/shim/src/console_buffer.c
deleted file mode 100644
index 427ae47768..0000000000
--- a/zephyr/shim/src/console_buffer.c
+++ /dev/null
@@ -1,128 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <kernel.h>
-#include <zephyr.h>
-
-#include "common.h"
-#include "console.h"
-#include "ec_commands.h"
-
-static char console_buf[CONFIG_PLATFORM_EC_HOSTCMD_CONSOLE_BUF_SIZE];
-static uint32_t previous_snapshot_idx;
-static uint32_t current_snapshot_idx;
-static uint32_t tail_idx;
-
-static inline uint32_t next_idx(uint32_t cur_idx)
-{
- return (cur_idx + 1) % ARRAY_SIZE(console_buf);
-}
-
-K_MUTEX_DEFINE(console_write_lock);
-
-void console_buf_notify_chars(const char *s, size_t len)
-{
- /*
- * This is just notifying of console characters for debugging
- * output, so if we are unable to lock the mutex immediately,
- * then just drop the string.
- */
- if (k_mutex_lock(&console_write_lock, K_NO_WAIT))
- return;
- /* We got the mutex. */
- while (len--) {
- /* Don't copy null byte into buffer */
- if (!(*s))
- continue;
-
- uint32_t new_tail = next_idx(tail_idx);
-
- /* Check if we are starting to overwrite our snapshot
- * heads
- */
- if (new_tail == previous_snapshot_idx)
- previous_snapshot_idx =
- next_idx(previous_snapshot_idx);
- if (new_tail == current_snapshot_idx)
- current_snapshot_idx =
- next_idx(current_snapshot_idx);
-
- console_buf[new_tail] = *s++;
- tail_idx = new_tail;
- }
- k_mutex_unlock(&console_write_lock);
-}
-
-enum ec_status uart_console_read_buffer_init(void)
-{
- if (k_mutex_lock(&console_write_lock, K_MSEC(100)))
- /* Failed to acquire console buffer mutex */
- return EC_RES_TIMEOUT;
-
- previous_snapshot_idx = current_snapshot_idx;
- current_snapshot_idx = tail_idx;
-
- k_mutex_unlock(&console_write_lock);
-
- return EC_RES_SUCCESS;
-}
-
-int uart_console_read_buffer(uint8_t type, char *dest, uint16_t dest_size,
- uint16_t *write_count_out)
-{
- uint32_t *head;
- uint16_t write_count = 0;
-
- switch (type) {
- case CONSOLE_READ_NEXT:
- /* Start from beginning of latest snapshot */
- head = &current_snapshot_idx;
- break;
- case CONSOLE_READ_RECENT:
- /* Start from end of previous snapshot */
- head = &previous_snapshot_idx;
- break;
- default:
- return EC_RES_INVALID_PARAM;
- }
-
- /* We need to make sure we have room for at least the null byte */
- if (dest_size == 0)
- return EC_RES_INVALID_PARAM;
-
- if (k_mutex_lock(&console_write_lock, K_MSEC(100)))
- /* Failed to acquire console buffer mutex */
- return EC_RES_TIMEOUT;
-
- if (*head == tail_idx) {
- /* No new data, return empty response */
- k_mutex_unlock(&console_write_lock);
- return EC_RES_SUCCESS;
- }
-
- do {
- if (write_count >= dest_size - 1)
- /* Buffer is full, minus the space for a null byte */
- break;
-
- dest[write_count] = console_buf[*head];
- write_count++;
- *head = next_idx(*head);
- } while (*head != tail_idx);
-
- dest[write_count] = '\0';
- write_count++;
-
- *write_count_out = write_count;
- k_mutex_unlock(&console_write_lock);
-
- return EC_RES_SUCCESS;
-}
-
-/* ECOS uart buffer, putc is blocking instead. */
-int uart_buffer_full(void)
-{
- return false;
-}
diff --git a/zephyr/shim/src/crc.c b/zephyr/shim/src/crc.c
deleted file mode 100644
index 5c726619ee..0000000000
--- a/zephyr/shim/src/crc.c
+++ /dev/null
@@ -1,21 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <sys/crc.h>
-
-#include "crc8.h"
-
-/* Polynomial representation for x^8 + x^2 + x + 1 is 0x07 */
-#define SMBUS_POLYNOMIAL 0x07
-
-inline uint8_t cros_crc8(const uint8_t *data, int len)
-{
- return crc8(data, len, SMBUS_POLYNOMIAL, 0, false);
-}
-
-uint8_t cros_crc8_arg(const uint8_t *data, int len, uint8_t previous_crc)
-{
- return crc8(data, len, SMBUS_POLYNOMIAL, previous_crc, false);
-}
diff --git a/zephyr/shim/src/espi.c b/zephyr/shim/src/espi.c
deleted file mode 100644
index c064bd6157..0000000000
--- a/zephyr/shim/src/espi.c
+++ /dev/null
@@ -1,563 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <atomic.h>
-#include <device.h>
-#include <drivers/espi.h>
-#include <logging/log.h>
-#include <kernel.h>
-#include <stdint.h>
-#include <zephyr.h>
-
-#include "acpi.h"
-#include "chipset.h"
-#include "common.h"
-#include "espi.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i8042_protocol.h"
-#include "keyboard_protocol.h"
-#include "lpc.h"
-#include "port80.h"
-#include "power.h"
-#include "task.h"
-#include "timer.h"
-#include "zephyr_espi_shim.h"
-
-#define VWIRE_PULSE_TRIGGER_TIME 65
-
-LOG_MODULE_REGISTER(espi_shim, CONFIG_ESPI_LOG_LEVEL);
-
-/* host command packet handler structure */
-static struct host_packet lpc_packet;
-/*
- * For the eSPI host command, request & response use the same share memory.
- * This is for input request temp buffer.
- */
-static uint8_t params_copy[EC_LPC_HOST_PACKET_SIZE] __aligned(4);
-static bool init_done;
-
-/*
- * A mapping of platform/ec signals to Zephyr virtual wires.
- *
- * This should be a macro which takes a parameter M, and does a
- * functional application of M to 2-tuples of (platform/ec signal,
- * zephyr vwire).
- */
-#define VW_SIGNAL_TRANSLATION_LIST(M) \
- M(VW_SLP_S3_L, ESPI_VWIRE_SIGNAL_SLP_S3) \
- M(VW_SLP_S4_L, ESPI_VWIRE_SIGNAL_SLP_S4) \
- M(VW_SLP_S5_L, ESPI_VWIRE_SIGNAL_SLP_S5) \
- M(VW_SUS_STAT_L, ESPI_VWIRE_SIGNAL_SUS_STAT) \
- M(VW_PLTRST_L, ESPI_VWIRE_SIGNAL_PLTRST) \
- M(VW_OOB_RST_WARN, ESPI_VWIRE_SIGNAL_OOB_RST_WARN) \
- M(VW_OOB_RST_ACK, ESPI_VWIRE_SIGNAL_OOB_RST_ACK) \
- M(VW_WAKE_L, ESPI_VWIRE_SIGNAL_WAKE) \
- M(VW_PME_L, ESPI_VWIRE_SIGNAL_PME) \
- M(VW_ERROR_FATAL, ESPI_VWIRE_SIGNAL_ERR_FATAL) \
- M(VW_ERROR_NON_FATAL, ESPI_VWIRE_SIGNAL_ERR_NON_FATAL) \
- M(VW_PERIPHERAL_BTLD_STATUS_DONE, ESPI_VWIRE_SIGNAL_SLV_BOOT_DONE) \
- M(VW_SCI_L, ESPI_VWIRE_SIGNAL_SCI) \
- M(VW_SMI_L, ESPI_VWIRE_SIGNAL_SMI) \
- M(VW_HOST_RST_ACK, ESPI_VWIRE_SIGNAL_HOST_RST_ACK) \
- M(VW_HOST_RST_WARN, ESPI_VWIRE_SIGNAL_HOST_RST_WARN) \
- M(VW_SUS_ACK, ESPI_VWIRE_SIGNAL_SUS_ACK) \
- M(VW_SUS_WARN_L, ESPI_VWIRE_SIGNAL_SUS_WARN) \
- M(VW_SUS_PWRDN_ACK_L, ESPI_VWIRE_SIGNAL_SUS_PWRDN_ACK) \
- M(VW_SLP_A_L, ESPI_VWIRE_SIGNAL_SLP_A) \
- M(VW_SLP_LAN, ESPI_VWIRE_SIGNAL_SLP_LAN) \
- M(VW_SLP_WLAN, ESPI_VWIRE_SIGNAL_SLP_WLAN)
-
-/*
- * These two macros are intended to be used as as the M parameter to
- * the list above, generating case statements returning the
- * translation for the first parameter to the second, and the second
- * to the first, respectively.
- */
-#define CASE_CROS_TO_ZEPHYR(A, B) \
- case A: \
- return B;
-#define CASE_ZEPHYR_TO_CROS(A, B) CASE_CROS_TO_ZEPHYR(B, A)
-
-/* Translate a platform/ec signal to a Zephyr signal */
-static enum espi_vwire_signal signal_to_zephyr_vwire(enum espi_vw_signal signal)
-{
- switch (signal) {
- VW_SIGNAL_TRANSLATION_LIST(CASE_CROS_TO_ZEPHYR);
- default:
- LOG_ERR("Invalid virtual wire signal (%d)", signal);
- return -1;
- }
-}
-
-/* Translate a Zephyr vwire to a platform/ec signal */
-static enum espi_vw_signal zephyr_vwire_to_signal(enum espi_vwire_signal vwire)
-{
- switch (vwire) {
- VW_SIGNAL_TRANSLATION_LIST(CASE_ZEPHYR_TO_CROS);
- default:
- LOG_ERR("Invalid zephyr vwire (%d)", vwire);
- return -1;
- }
-}
-
-/*
- * Bit field for each signal which can have an interrupt enabled.
- * Note the interrupt is always enabled, it just depends whether we
- * route it to the power_signal_interrupt handler or not.
- */
-static atomic_t signal_interrupt_enabled;
-
-/* To be used with VW_SIGNAL_TRASLATION_LIST */
-#define CASE_CROS_TO_BIT(A, _) CASE_CROS_TO_ZEPHYR(A, BIT(A - VW_SIGNAL_START))
-
-/* Convert from an EC signal to the corresponding interrupt enabled bit. */
-static uint32_t signal_to_interrupt_bit(enum espi_vw_signal signal)
-{
- switch (signal) {
- VW_SIGNAL_TRANSLATION_LIST(CASE_CROS_TO_BIT);
- default:
- return 0;
- }
-}
-
-/* Callback for vwire received */
-static void espi_vwire_handler(const struct device *dev,
- struct espi_callback *cb,
- struct espi_event event)
-{
- int ec_signal = zephyr_vwire_to_signal(event.evt_details);
-
- if (IS_ENABLED(CONFIG_PLATFORM_EC_POWERSEQ) &&
- (signal_interrupt_enabled & signal_to_interrupt_bit(ec_signal))) {
- power_signal_interrupt(ec_signal);
- }
-}
-
-#ifdef CONFIG_PLATFORM_EC_CHIPSET_RESET_HOOK
-static void espi_chipset_reset(void)
-{
- hook_notify(HOOK_CHIPSET_RESET);
-}
-DECLARE_DEFERRED(espi_chipset_reset);
-
-/* Callback for reset */
-static void espi_reset_handler(const struct device *dev,
- struct espi_callback *cb,
- struct espi_event event)
-{
- hook_call_deferred(&espi_chipset_reset_data, MSEC);
-
-}
-#endif /* CONFIG_PLATFORM_EC_CHIPSET_RESET_HOOK */
-
-#define ESPI_NODE DT_NODELABEL(espi0)
-static const struct device *espi_dev;
-
-
-int espi_vw_set_wire(enum espi_vw_signal signal, uint8_t level)
-{
- int ret = espi_send_vwire(espi_dev, signal_to_zephyr_vwire(signal),
- level);
-
- if (ret != 0)
- LOG_ERR("Encountered error sending virtual wire signal");
-
- return ret;
-}
-
-int espi_vw_get_wire(enum espi_vw_signal signal)
-{
- uint8_t level;
-
- if (espi_receive_vwire(espi_dev, signal_to_zephyr_vwire(signal),
- &level) < 0) {
- LOG_ERR("Encountered error receiving virtual wire signal");
- return 0;
- }
-
- return level;
-}
-
-int espi_vw_enable_wire_int(enum espi_vw_signal signal)
-{
- atomic_or(&signal_interrupt_enabled, signal_to_interrupt_bit(signal));
- return 0;
-}
-
-int espi_vw_disable_wire_int(enum espi_vw_signal signal)
-{
- atomic_and(&signal_interrupt_enabled, ~signal_to_interrupt_bit(signal));
- return 0;
-}
-
-uint8_t *lpc_get_memmap_range(void)
-{
- uint32_t lpc_memmap = 0;
- int result = espi_read_lpc_request(espi_dev, EACPI_GET_SHARED_MEMORY,
- &lpc_memmap);
-
- if (result != EC_SUCCESS)
- LOG_ERR("Get lpc_memmap failed (%d)!\n", result);
-
- return (uint8_t *)lpc_memmap;
-}
-
-/**
- * Update the level-sensitive wake signal to the AP.
- *
- * @param wake_events Currently asserted wake events
- */
-static void lpc_update_wake(host_event_t wake_events)
-{
- /*
- * Mask off power button event, since the AP gets that through a
- * separate dedicated GPIO.
- */
- wake_events &= ~EC_HOST_EVENT_MASK(EC_HOST_EVENT_POWER_BUTTON);
-
- /* Signal is asserted low when wake events is non-zero */
- gpio_set_level(GPIO_EC_PCH_WAKE_ODL, !wake_events);
-}
-
-static void lpc_generate_smi(void)
-{
- /* Enforce signal-high for long enough to debounce high */
- espi_vw_set_wire(VW_SMI_L, 1);
- udelay(VWIRE_PULSE_TRIGGER_TIME);
- espi_vw_set_wire(VW_SMI_L, 0);
- udelay(VWIRE_PULSE_TRIGGER_TIME);
- espi_vw_set_wire(VW_SMI_L, 1);
-}
-
-static void lpc_generate_sci(void)
-{
- /* Enforce signal-high for long enough to debounce high */
- espi_vw_set_wire(VW_SCI_L, 1);
- udelay(VWIRE_PULSE_TRIGGER_TIME);
- espi_vw_set_wire(VW_SCI_L, 0);
- udelay(VWIRE_PULSE_TRIGGER_TIME);
- espi_vw_set_wire(VW_SCI_L, 1);
-}
-
-void lpc_update_host_event_status(void)
-{
- uint32_t enable;
- uint32_t status;
- int need_sci = 0;
- int need_smi = 0;
-
- if (!init_done)
- return;
-
- /* Disable PMC1 interrupt while updating status register */
- enable = 0;
- espi_write_lpc_request(espi_dev, ECUSTOM_HOST_SUBS_INTERRUPT_EN,
- &enable);
-
- espi_read_lpc_request(espi_dev, EACPI_READ_STS, &status);
- if (lpc_get_host_events_by_type(LPC_HOST_EVENT_SMI)) {
- /* Only generate SMI for first event */
- if (!(status & EC_LPC_STATUS_SMI_PENDING))
- need_smi = 1;
-
- status |= EC_LPC_STATUS_SMI_PENDING;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
- } else {
- status &= ~EC_LPC_STATUS_SMI_PENDING;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
- }
-
- espi_read_lpc_request(espi_dev, EACPI_READ_STS, &status);
- if (lpc_get_host_events_by_type(LPC_HOST_EVENT_SCI)) {
- /* Generate SCI for every event */
- need_sci = 1;
-
- status |= EC_LPC_STATUS_SCI_PENDING;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
- } else {
- status &= ~EC_LPC_STATUS_SCI_PENDING;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
- }
-
- *(host_event_t *)host_get_memmap(EC_MEMMAP_HOST_EVENTS) =
- lpc_get_host_events();
-
- enable = 1;
- espi_write_lpc_request(espi_dev, ECUSTOM_HOST_SUBS_INTERRUPT_EN,
- &enable);
-
- /* Process the wake events. */
- lpc_update_wake(lpc_get_host_events_by_type(LPC_HOST_EVENT_WAKE));
-
- /* Send pulse on SMI signal if needed */
- if (need_smi)
- lpc_generate_smi();
-
- /* ACPI 5.0-12.6.1: Generate SCI for SCI_EVT=1. */
- if (need_sci)
- lpc_generate_sci();
-}
-
-static void host_command_init(void)
-{
- /* We support LPC args and version 3 protocol */
- *(lpc_get_memmap_range() + EC_MEMMAP_HOST_CMD_FLAGS) =
- EC_HOST_CMD_FLAG_LPC_ARGS_SUPPORTED |
- EC_HOST_CMD_FLAG_VERSION_3;
-
- /* Sufficiently initialized */
- init_done = 1;
-
- lpc_update_host_event_status();
-}
-
-DECLARE_HOOK(HOOK_INIT, host_command_init, HOOK_PRIO_INIT_LPC);
-
-static void handle_acpi_write(uint32_t data)
-{
- uint8_t value, result;
- uint8_t is_cmd = is_acpi_command(data);
- uint32_t status;
-
- value = get_acpi_value(data);
-
- /* Handle whatever this was. */
- if (acpi_ap_to_ec(is_cmd, value, &result)) {
- data = result;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_CHAR, &data);
- }
-
- /* Clear processing flag */
- espi_read_lpc_request(espi_dev, EACPI_READ_STS, &status);
- status &= ~EC_LPC_STATUS_PROCESSING;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
-
- /*
- * ACPI 5.0-12.6.1: Generate SCI for Input Buffer Empty / Output Buffer
- * Full condition on the kernel channel.
- */
- lpc_generate_sci();
-}
-
-static void lpc_send_response_packet(struct host_packet *pkt)
-{
- uint32_t data;
-
- /* TODO(b/176523211): check whether add EC_RES_IN_PROGRESS handle */
-
- /* Write result to the data byte. This sets the TOH status bit. */
- data = pkt->driver_result;
- espi_write_lpc_request(espi_dev, ECUSTOM_HOST_CMD_SEND_RESULT, &data);
-}
-
-static void handle_host_write(uint32_t data)
-{
- uint32_t shm_mem_host_cmd;
-
- if (EC_COMMAND_PROTOCOL_3 != (data & 0xff)) {
- LOG_ERR("Don't support this version of the host command");
- /* TODO:(b/175217186): error response for other versions */
- return;
- }
-
- espi_read_lpc_request(espi_dev, ECUSTOM_HOST_CMD_GET_PARAM_MEMORY,
- &shm_mem_host_cmd);
-
- lpc_packet.send_response = lpc_send_response_packet;
-
- lpc_packet.request = (const void *)shm_mem_host_cmd;
- lpc_packet.request_temp = params_copy;
- lpc_packet.request_max = sizeof(params_copy);
- /* Don't know the request size so pass in the entire buffer */
- lpc_packet.request_size = EC_LPC_HOST_PACKET_SIZE;
-
- lpc_packet.response = (void *)shm_mem_host_cmd;
- lpc_packet.response_max = EC_LPC_HOST_PACKET_SIZE;
- lpc_packet.response_size = 0;
-
- lpc_packet.driver_result = EC_RES_SUCCESS;
-
- host_packet_receive(&lpc_packet);
- return;
-}
-
-void lpc_set_acpi_status_mask(uint8_t mask)
-{
- uint32_t status;
- espi_read_lpc_request(espi_dev, EACPI_READ_STS, &status);
- status |= mask;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
-}
-
-void lpc_clear_acpi_status_mask(uint8_t mask)
-{
- uint32_t status;
- espi_read_lpc_request(espi_dev, EACPI_READ_STS, &status);
- status &= ~mask;
- espi_write_lpc_request(espi_dev, EACPI_WRITE_STS, &status);
-}
-
-/* Get protocol information */
-static enum ec_status lpc_get_protocol_info(struct host_cmd_handler_args *args)
-{
- struct ec_response_get_protocol_info *r = args->response;
-
- memset(r, 0, sizeof(*r));
- r->protocol_versions = BIT(3);
- r->max_request_packet_size = EC_LPC_HOST_PACKET_SIZE;
- r->max_response_packet_size = EC_LPC_HOST_PACKET_SIZE;
- r->flags = 0;
-
- args->response_size = sizeof(*r);
-
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_GET_PROTOCOL_INFO, lpc_get_protocol_info,
- EC_VER_MASK(0));
-
-/*
- * This function is needed only for the obsolete platform which uses the GPIO
- * for KBC's IRQ.
- */
-void lpc_keyboard_resume_irq(void) {}
-
-void lpc_keyboard_clear_buffer(void)
-{
- /* Clear OBF flag in host STATUS and HIKMST regs */
- espi_write_lpc_request(espi_dev, E8042_CLEAR_OBF, 0);
-}
-int lpc_keyboard_has_char(void)
-{
- uint32_t status;
-
- /* if OBF bit is '1', that mean still have a data in DBBOUT */
- espi_read_lpc_request(espi_dev, E8042_OBF_HAS_CHAR, &status);
- return status;
-}
-
-void lpc_keyboard_put_char(uint8_t chr, int send_irq)
-{
- uint32_t kb_char = chr;
-
- espi_write_lpc_request(espi_dev, E8042_WRITE_KB_CHAR, &kb_char);
- LOG_INF("KB put %02x", kb_char);
-}
-
-/* Put an aux char to host buffer by HIMDO and assert status bit 5. */
-void lpc_aux_put_char(uint8_t chr, int send_irq)
-{
- uint32_t kb_char = chr;
- uint32_t status = I8042_AUX_DATA;
-
- espi_write_lpc_request(espi_dev, E8042_SET_FLAG, &status);
- espi_write_lpc_request(espi_dev, E8042_WRITE_KB_CHAR, &kb_char);
- LOG_INF("AUX put %02x", kb_char);
-}
-
-static void kbc_ibf_obe_handler(uint32_t data)
-{
-#ifdef HAS_TASK_KEYPROTO
- uint8_t is_ibf = is_8042_ibf(data);
- uint32_t status = I8042_AUX_DATA;
-
- if (is_ibf) {
- keyboard_host_write(get_8042_data(data),
- get_8042_type(data));
- } else if (IS_ENABLED(CONFIG_8042_AUX)) {
- espi_write_lpc_request(espi_dev, E8042_CLEAR_FLAG, &status);
- }
- task_wake(TASK_ID_KEYPROTO);
-#endif
-}
-
-int lpc_keyboard_input_pending(void)
-{
- uint32_t status;
-
- /* if IBF bit is '1', that mean still have a data in DBBIN */
- espi_read_lpc_request(espi_dev, E8042_IBF_HAS_CHAR, &status);
- return status;
-}
-
-static void espi_peripheral_handler(const struct device *dev,
- struct espi_callback *cb,
- struct espi_event event)
-{
- uint16_t event_type = event.evt_details;
-
- if (IS_ENABLED(CONFIG_PLATFORM_EC_PORT80) &&
- event_type == ESPI_PERIPHERAL_DEBUG_PORT80) {
- port_80_write(event.evt_data);
- }
-
- if (IS_ENABLED(CONFIG_PLATFORM_EC_ACPI) &&
- event_type == ESPI_PERIPHERAL_HOST_IO) {
- handle_acpi_write(event.evt_data);
- }
-
- if (IS_ENABLED(CONFIG_PLATFORM_EC_HOSTCMD) &&
- event_type == ESPI_PERIPHERAL_EC_HOST_CMD) {
- handle_host_write(event.evt_data);
- }
-
- if (IS_ENABLED(CONFIG_ESPI_PERIPHERAL_8042_KBC) &&
- IS_ENABLED(HAS_TASK_KEYPROTO) &&
- event_type == ESPI_PERIPHERAL_8042_KBC) {
- kbc_ibf_obe_handler(event.evt_data);
- }
-}
-
-int zephyr_shim_setup_espi(void)
-{
- static struct {
- struct espi_callback cb;
- espi_callback_handler_t handler;
- enum espi_bus_event event_type;
- } callbacks[] = {
- {
- .handler = espi_vwire_handler,
- .event_type = ESPI_BUS_EVENT_VWIRE_RECEIVED,
- },
- {
- .handler = espi_peripheral_handler,
- .event_type = ESPI_BUS_PERIPHERAL_NOTIFICATION,
- },
-#ifdef CONFIG_PLATFORM_EC_CHIPSET_RESET_HOOK
- {
- .handler = espi_reset_handler,
- .event_type = ESPI_BUS_RESET,
- },
-#endif
- };
-
- struct espi_cfg cfg = {
- .io_caps = ESPI_IO_MODE_SINGLE_LINE,
- .channel_caps = ESPI_CHANNEL_VWIRE | ESPI_CHANNEL_PERIPHERAL |
- ESPI_CHANNEL_OOB,
- .max_freq = 20,
- };
-
- espi_dev = DEVICE_DT_GET(ESPI_NODE);
- if (!device_is_ready(espi_dev)) {
- LOG_ERR("Error: device %s is not ready", espi_dev->name);
- return -1;
- }
-
- /* Configure eSPI */
- if (espi_config(espi_dev, &cfg)) {
- LOG_ERR("Failed to configure eSPI device");
- return -1;
- }
-
- /* Setup callbacks */
- for (size_t i = 0; i < ARRAY_SIZE(callbacks); i++) {
- espi_init_callback(&callbacks[i].cb, callbacks[i].handler,
- callbacks[i].event_type);
- espi_add_callback(espi_dev, &callbacks[i].cb);
- }
-
- return 0;
-}
diff --git a/zephyr/shim/src/fan.c b/zephyr/shim/src/fan.c
deleted file mode 100644
index 932688fc9c..0000000000
--- a/zephyr/shim/src/fan.c
+++ /dev/null
@@ -1,380 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "fan.h"
-#include "pwm.h"
-#include "pwm/pwm.h"
-#include "system.h"
-#include "math_util.h"
-#include "hooks.h"
-#include "gpio_signal.h"
-#include "gpio.h"
-#include <logging/log.h>
-#include <sys/util_macro.h>
-#include <drivers/sensor.h>
-
-LOG_MODULE_REGISTER(fan_shim, LOG_LEVEL_ERR);
-
-#define FAN_CONFIGS(node_id) \
- const struct fan_conf node_id##_conf = { \
- .flags = (COND_CODE_1(DT_PROP(node_id, not_use_rpm_mode), \
- (0), (FAN_USE_RPM_MODE))) | \
- (COND_CODE_1(DT_PROP(node_id, use_fast_start), \
- (FAN_USE_FAST_START), (0))), \
- .ch = node_id, \
- .pgood_gpio = COND_CODE_1( \
- DT_NODE_HAS_PROP(node_id, pgood_gpio), \
- (GPIO_SIGNAL(DT_PHANDLE(node_id, pgood_gpio))), \
- (GPIO_UNIMPLEMENTED)), \
- .enable_gpio = COND_CODE_1( \
- DT_NODE_HAS_PROP(node_id, enable_gpio), \
- (GPIO_SIGNAL(DT_PHANDLE(node_id, enable_gpio))), \
- (GPIO_UNIMPLEMENTED)), \
- }; \
- const struct fan_rpm node_id##_rpm = { \
- .rpm_min = DT_PROP(node_id, rpm_min), \
- .rpm_start = DT_PROP(node_id, rpm_start), \
- .rpm_max = DT_PROP(node_id, rpm_max), \
- };
-
-#define FAN_INST(node_id) \
- [node_id] = { \
- .conf = &node_id##_conf, \
- .rpm = &node_id##_rpm, \
- },
-
-#define FAN_CONTROL_INST(node_id) \
- [node_id] = { \
- .pwm_id = PWM_CHANNEL(DT_PHANDLE(node_id, pwm)), \
- },
-
-#if DT_NODE_EXISTS(DT_INST(0, named_fans))
-DT_FOREACH_CHILD(DT_INST(0, named_fans), FAN_CONFIGS)
-#endif /* named_fan */
-
-const struct fan_t fans[] = {
-#if DT_NODE_EXISTS(DT_INST(0, named_fans))
- DT_FOREACH_CHILD(DT_INST(0, named_fans), FAN_INST)
-#endif /* named_fan */
-};
-
-#define TACHO_DEV_INIT(node_id) { \
- fan_control[node_id].tach = \
- DEVICE_DT_GET(DT_PHANDLE(node_id, tach)); \
- }
-
-/* Rpm deviation (Unit:percent) */
-#ifndef RPM_DEVIATION
-#define RPM_DEVIATION 7
-#endif
-
-/* Margin of target rpm */
-#define RPM_MARGIN(rpm_target) (((rpm_target)*RPM_DEVIATION) / 100)
-
-/* Fan mode */
-enum fan_mode {
- /* FAN rpm mode */
- FAN_RPM = 0,
- /* FAN duty mode */
- FAN_DUTY,
-};
-
-/* Fan status data structure */
-struct fan_status_t {
- /* Fan mode */
- enum fan_mode current_fan_mode;
- /* Actual rpm */
- int rpm_actual;
- /* Target rpm */
- int rpm_target;
- /* Fan config flags */
- unsigned int flags;
- /* Automatic fan status */
- enum fan_status auto_status;
-};
-
-/* Data structure to define tachometer. */
-struct fan_control_t {
- const struct device *tach;
- enum pwm_channel pwm_id;
-};
-
-static struct fan_status_t fan_status[FAN_CH_COUNT];
-static int rpm_pre[FAN_CH_COUNT];
-static struct fan_control_t fan_control[] = {
-#if DT_NODE_EXISTS(DT_INST(0, named_fans))
- DT_FOREACH_CHILD(DT_INST(0, named_fans), FAN_CONTROL_INST)
-#endif /* named_fan */
-};
-
-/**
- * Get fan rpm value
- *
- * @param ch operation channel
- * @return Actual rpm
- */
-static int fan_rpm(int ch)
-{
- struct sensor_value val = { 0 };
-
- sensor_sample_fetch_chan(fan_control[ch].tach, SENSOR_CHAN_RPM);
- sensor_channel_get(fan_control[ch].tach, SENSOR_CHAN_RPM, &val);
- return (int)val.val1;
-}
-
-/**
- * Check all fans are stopped
- *
- * @return 1: all fans are stopped. 0: else.
- */
-static int fan_all_disabled(void)
-{
- int ch;
-
- for (ch = 0; ch < fan_get_count(); ch++)
- if (fan_status[ch].auto_status != FAN_STATUS_STOPPED)
- return 0;
- return 1;
-}
-
-/**
- * Adjust fan duty by difference between target and actual rpm
- *
- * @param ch operation channel
- * @param rpm_diff difference between target and actual rpm
- * @param duty current fan duty
- */
-static void fan_adjust_duty(int ch, int rpm_diff, int duty)
-{
- int duty_step = 0;
-
- /* Find suitable duty step */
- if (ABS(rpm_diff) >= 2000)
- duty_step = 20;
- else if (ABS(rpm_diff) >= 1000)
- duty_step = 10;
- else if (ABS(rpm_diff) >= 500)
- duty_step = 5;
- else if (ABS(rpm_diff) >= 250)
- duty_step = 3;
- else
- duty_step = 1;
-
- /* Adjust fan duty step by step */
- if (rpm_diff > 0)
- duty = MIN(duty + duty_step, 100);
- else
- duty = MAX(duty - duty_step, 1);
-
- fan_set_duty(ch, duty);
-
- LOG_DBG("fan%d: duty %d, rpm_diff %d", ch, duty, rpm_diff);
-}
-
-/**
- * Smart fan control function.
- *
- * The function sets the pwm duty to reach the target rpm
- *
- * @param ch operation channel
- * @param rpm_actual actual operation rpm value
- * @param rpm_target target operation rpm value
- * @return current fan control status
- */
-enum fan_status fan_smart_control(int ch, int rpm_actual, int rpm_target)
-{
- int duty, rpm_diff;
-
- /* wait rpm is stable */
- if (ABS(rpm_actual - rpm_pre[ch]) > RPM_MARGIN(rpm_actual)) {
- rpm_pre[ch] = rpm_actual;
- return FAN_STATUS_CHANGING;
- }
-
- /* Record previous rpm */
- rpm_pre[ch] = rpm_actual;
-
- /* Adjust PWM duty */
- rpm_diff = rpm_target - rpm_actual;
- duty = fan_get_duty(ch);
- if (duty == 0 && rpm_target == 0)
- return FAN_STATUS_STOPPED;
-
- /* Increase PWM duty */
- if (rpm_diff > RPM_MARGIN(rpm_target)) {
- if (duty == 100)
- return FAN_STATUS_FRUSTRATED;
-
- fan_adjust_duty(ch, rpm_diff, duty);
- return FAN_STATUS_CHANGING;
- /* Decrease PWM duty */
- } else if (rpm_diff < -RPM_MARGIN(rpm_target)) {
- if (duty == 1 && rpm_target != 0)
- return FAN_STATUS_FRUSTRATED;
-
- fan_adjust_duty(ch, rpm_diff, duty);
- return FAN_STATUS_CHANGING;
- }
-
- return FAN_STATUS_LOCKED;
-}
-
-void fan_tick_func(void)
-{
- int ch;
-
- for (ch = 0; ch < FAN_CH_COUNT; ch++) {
- volatile struct fan_status_t *p_status = fan_status + ch;
- /* Make sure rpm mode is enabled */
- if (p_status->current_fan_mode != FAN_RPM) {
- /* Fan in duty mode still want rpm_actual being updated.
- */
- if (p_status->flags & FAN_USE_RPM_MODE) {
- p_status->rpm_actual = fan_rpm(ch);
- if (p_status->rpm_actual > 0)
- p_status->auto_status =
- FAN_STATUS_LOCKED;
- else
- p_status->auto_status =
- FAN_STATUS_STOPPED;
- continue;
- } else {
- if (fan_get_duty(ch) > 0)
- p_status->auto_status =
- FAN_STATUS_LOCKED;
- else
- p_status->auto_status =
- FAN_STATUS_STOPPED;
- }
- continue;
- }
- if (!fan_get_enabled(ch))
- continue;
- /* Get actual rpm */
- p_status->rpm_actual = fan_rpm(ch);
- /* Do smart fan stuff */
- p_status->auto_status = fan_smart_control(
- ch, p_status->rpm_actual, p_status->rpm_target);
- }
-}
-DECLARE_HOOK(HOOK_TICK, fan_tick_func, HOOK_PRIO_DEFAULT);
-
-int fan_get_duty(int ch)
-{
- enum pwm_channel pwm_id = fan_control[ch].pwm_id;
-
- /* Return percent */
- return pwm_get_duty(pwm_id);
-}
-
-int fan_get_rpm_mode(int ch)
-{
- return fan_status[ch].current_fan_mode == FAN_RPM ? 1 : 0;
-}
-
-void fan_set_rpm_mode(int ch, int rpm_mode)
-{
- if (rpm_mode && (fan_status[ch].flags & FAN_USE_RPM_MODE))
- fan_status[ch].current_fan_mode = FAN_RPM;
- else
- fan_status[ch].current_fan_mode = FAN_DUTY;
-}
-
-int fan_get_rpm_actual(int ch)
-{
- /* Check PWM is enabled first */
- if (fan_get_duty(ch) == 0)
- return 0;
-
- LOG_DBG("fan %d: get actual rpm = %d", ch, fan_status[ch].rpm_actual);
- return fan_status[ch].rpm_actual;
-}
-
-int fan_get_enabled(int ch)
-{
- enum pwm_channel pwm_id = fan_control[ch].pwm_id;
-
- return pwm_get_enabled(pwm_id);
-}
-
-void fan_set_enabled(int ch, int enabled)
-{
- enum pwm_channel pwm_id = fan_control[ch].pwm_id;
-
- if (!enabled)
- fan_status[ch].auto_status = FAN_STATUS_STOPPED;
- pwm_enable(pwm_id, enabled);
-}
-
-void fan_channel_setup(int ch, unsigned int flags)
-{
- volatile struct fan_status_t *p_status = fan_status + ch;
-
- if (flags & FAN_USE_RPM_MODE) {
- DT_FOREACH_CHILD(DT_INST(0, named_fans), TACHO_DEV_INIT)
- }
-
- p_status->flags = flags;
- /* Set default fan states */
- p_status->current_fan_mode = FAN_DUTY;
- p_status->auto_status = FAN_STATUS_STOPPED;
-}
-
-void fan_set_duty(int ch, int percent)
-{
- enum pwm_channel pwm_id = fan_control[ch].pwm_id;
-
- /* duty is zero */
- if (!percent) {
- fan_status[ch].auto_status = FAN_STATUS_STOPPED;
- if (fan_all_disabled())
- enable_sleep(SLEEP_MASK_FAN);
- } else
- disable_sleep(SLEEP_MASK_FAN);
-
- /* Set the duty cycle of PWM */
- pwm_set_duty(pwm_id, percent);
-}
-
-int fan_get_rpm_target(int ch)
-{
- return fan_status[ch].rpm_target;
-}
-
-enum fan_status fan_get_status(int ch)
-{
- return fan_status[ch].auto_status;
-}
-
-void fan_set_rpm_target(int ch, int rpm)
-{
- if (rpm == 0) {
- /* If rpm = 0, disable PWM immediately. Why?*/
- fan_set_duty(ch, 0);
- } else {
- /* This is the counterpart of disabling PWM above. */
- if (!fan_get_enabled(ch))
- fan_set_enabled(ch, 1);
- if (rpm > fans[ch].rpm->rpm_max)
- rpm = fans[ch].rpm->rpm_max;
- else if (rpm < fans[ch].rpm->rpm_min)
- rpm = fans[ch].rpm->rpm_min;
- }
-
- /* Set target rpm */
- fan_status[ch].rpm_target = rpm;
- LOG_DBG("fan %d: set target rpm = %d", ch, fan_status[ch].rpm_target);
-}
-
-int fan_is_stalled(int ch)
-{
- int is_pgood = 1;
-
- if (gpio_is_implemented(fans[ch].conf->enable_gpio))
- is_pgood = gpio_get_level(fans[ch].conf->enable_gpio);
-
- return fan_get_enabled(ch) && fan_get_duty(ch) &&
- !fan_get_rpm_actual(ch) && is_pgood;
-}
diff --git a/zephyr/shim/src/flash.c b/zephyr/shim/src/flash.c
deleted file mode 100644
index b72d7b5763..0000000000
--- a/zephyr/shim/src/flash.c
+++ /dev/null
@@ -1,150 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <flash.h>
-#include <kernel.h>
-#include <logging/log.h>
-
-#include "console.h"
-#include "drivers/cros_flash.h"
-#include "registers.h"
-#include "task.h"
-#include "util.h"
-
-LOG_MODULE_REGISTER(shim_flash, LOG_LEVEL_ERR);
-
-#define CROS_FLASH_DEV DT_LABEL(DT_NODELABEL(fiu0))
-static const struct device *cros_flash_dev;
-
-K_MUTEX_DEFINE(flash_lock);
-
-/* TODO(b/174873770): Add calls to Zephyr code here */
-#ifdef CONFIG_EXTERNAL_STORAGE
-void crec_flash_lock_mapped_storage(int lock)
-{
- if (lock)
- mutex_lock(&flash_lock);
- else
- mutex_unlock(&flash_lock);
-}
-#endif
-
-int crec_flash_physical_write(int offset, int size, const char *data)
-{
- int rv;
-
- /* Fail if offset, size, and data aren't at least word-aligned */
- if ((offset | size | (uint32_t)(uintptr_t)data) &
- (CONFIG_FLASH_WRITE_SIZE - 1))
- return EC_ERROR_INVAL;
-
- /* Lock physical flash operations */
- crec_flash_lock_mapped_storage(1);
-
- rv = cros_flash_physical_write(cros_flash_dev, offset, size, data);
-
- /* Unlock physical flash operations */
- crec_flash_lock_mapped_storage(0);
-
- return rv;
-}
-
-int crec_flash_physical_erase(int offset, int size)
-{
- int rv;
-
- /* Lock physical flash operations */
- crec_flash_lock_mapped_storage(1);
-
- rv = cros_flash_physical_erase(cros_flash_dev, offset, size);
-
- /* Unlock physical flash operations */
- crec_flash_lock_mapped_storage(0);
-
- return rv;
-}
-
-int crec_flash_physical_get_protect(int bank)
-{
- return cros_flash_physical_get_protect(cros_flash_dev, bank);
-}
-
-uint32_t crec_flash_physical_get_protect_flags(void)
-{
- return cros_flash_physical_get_protect_flags(cros_flash_dev);
-}
-
-int crec_flash_physical_protect_at_boot(uint32_t new_flags)
-{
- return cros_flash_physical_protect_at_boot(cros_flash_dev, new_flags);
-}
-
-int crec_flash_physical_protect_now(int all)
-{
- return cros_flash_physical_protect_now(cros_flash_dev, all);
-}
-
-int crec_flash_physical_read(int offset, int size, char *data)
-{
- int rv;
-
- /* Lock physical flash operations */
- crec_flash_lock_mapped_storage(1);
- rv = cros_flash_physical_read(cros_flash_dev, offset, size, data);
-
- /* Unlock physical flash operations */
- crec_flash_lock_mapped_storage(0);
-
- return rv;
-}
-
-static int flash_dev_init(const struct device *unused)
-{
- ARG_UNUSED(unused);
-
- cros_flash_dev = device_get_binding(CROS_FLASH_DEV);
- if (!cros_flash_dev) {
- LOG_ERR("Fail to find %s", CROS_FLASH_DEV);
- return -ENODEV;
- }
- cros_flash_init(cros_flash_dev);
-
- return 0;
-}
-
-uint32_t crec_flash_physical_get_valid_flags(void)
-{
- return EC_FLASH_PROTECT_RO_AT_BOOT | EC_FLASH_PROTECT_RO_NOW |
- EC_FLASH_PROTECT_ALL_NOW;
-}
-
-uint32_t crec_flash_physical_get_writable_flags(uint32_t cur_flags)
-{
- uint32_t ret = 0;
-
- /* If RO protection isn't enabled, its at-boot state can be changed. */
- if (!(cur_flags & EC_FLASH_PROTECT_RO_NOW))
- ret |= EC_FLASH_PROTECT_RO_AT_BOOT;
-
- /*
- * If entire flash isn't protected at this boot, it can be enabled if
- * the WP GPIO is asserted.
- */
- if (!(cur_flags & EC_FLASH_PROTECT_ALL_NOW) &&
- (cur_flags & EC_FLASH_PROTECT_GPIO_ASSERTED))
- ret |= EC_FLASH_PROTECT_ALL_NOW;
-
- return ret;
-}
-
-/*
- * The priority flash_dev_init should be lower than GPIO initialization because
- * it calls gpio_get_level function.
- */
-#if CONFIG_PLATFORM_EC_FLASH_INIT_PRIORITY <= \
- CONFIG_PLATFORM_EC_GPIO_INIT_PRIORITY
-#error "Flash must be initialized after GPIOs"
-#endif
-SYS_INIT(flash_dev_init, POST_KERNEL, CONFIG_PLATFORM_EC_FLASH_INIT_PRIORITY);
diff --git a/zephyr/shim/src/gpio.c b/zephyr/shim/src/gpio.c
deleted file mode 100644
index 2bae272361..0000000000
--- a/zephyr/shim/src/gpio.c
+++ /dev/null
@@ -1,441 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <device.h>
-#include <init.h>
-#include <kernel.h>
-#include <logging/log.h>
-
-#include "gpio.h"
-#include "gpio/gpio.h"
-#include "sysjump.h"
-#include "cros_version.h"
-
-LOG_MODULE_REGISTER(gpio_shim, LOG_LEVEL_ERR);
-
-/*
- * Static information about each GPIO that is configured in the named_gpios
- * device tree node.
- */
-struct gpio_config {
- /* GPIO net name */
- const char *name;
- /* Set at build time for lookup */
- const struct device *dev;
- /* Bit number of pin within device */
- gpio_pin_t pin;
- /* From DTS, excludes interrupts flags */
- gpio_flags_t init_flags;
-};
-
-#define GPIO_CONFIG(id) \
- COND_CODE_1( \
- DT_NODE_HAS_PROP(id, enum_name), \
- ( \
- { \
- .name = DT_LABEL(id), \
- .dev = DEVICE_DT_GET(DT_PHANDLE(id, gpios)), \
- .pin = DT_GPIO_PIN(id, gpios), \
- .init_flags = DT_GPIO_FLAGS(id, gpios), \
- }, ), \
- ())
-static const struct gpio_config configs[] = {
-#if DT_NODE_EXISTS(DT_PATH(named_gpios))
- DT_FOREACH_CHILD(DT_PATH(named_gpios), GPIO_CONFIG)
-#endif
-};
-
-/* Runtime information for each GPIO that is configured in named_gpios */
-struct gpio_data {
- /* Runtime device for gpio port. Set during in init function */
- const struct device *dev;
-};
-
-#define GPIO_DATA(id) COND_CODE_1(DT_NODE_HAS_PROP(id, enum_name), ({}, ), ())
-static struct gpio_data data[] = {
-#if DT_NODE_EXISTS(DT_PATH(named_gpios))
- DT_FOREACH_CHILD(DT_PATH(named_gpios), GPIO_DATA)
-#endif
-};
-
-/* Maps platform/ec gpio callback information */
-struct gpio_signal_callback {
- /* The platform/ec gpio_signal */
- const enum gpio_signal signal;
- /* IRQ handler from platform/ec code */
- void (*const irq_handler)(enum gpio_signal signal);
- /* Interrupt-related gpio flags */
- const gpio_flags_t flags;
-};
-
-/*
- * Each zephyr project should define EC_CROS_GPIO_INTERRUPTS in their gpio_map.h
- * file if there are any interrupts that should be registered. The
- * corresponding handler will be declared here, which will prevent
- * needing to include headers with complex dependencies in gpio_map.h.
- *
- * EC_CROS_GPIO_INTERRUPTS is a space-separated list of GPIO_INT items.
- */
-
-/*
- * Validate interrupt flags are valid for the Zephyr GPIO driver.
- */
-#define IS_GPIO_INTERRUPT_FLAG(flag, mask) ((flag & mask) == mask)
-#define VALID_GPIO_INTERRUPT_FLAG(flag) \
- (IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_EDGE_RISING) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_EDGE_FALLING) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_EDGE_BOTH) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_LEVEL_LOW) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_LEVEL_HIGH) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_EDGE_TO_INACTIVE) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_EDGE_TO_ACTIVE) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_LEVEL_INACTIVE) || \
- IS_GPIO_INTERRUPT_FLAG(flag, GPIO_INT_LEVEL_ACTIVE))
-
-#define GPIO_INT(sig, f, cb) \
- BUILD_ASSERT(VALID_GPIO_INTERRUPT_FLAG(f), \
- STRINGIFY(sig) " is not using Zephyr interrupt flags");
-#ifdef EC_CROS_GPIO_INTERRUPTS
-EC_CROS_GPIO_INTERRUPTS
-#endif
-#undef GPIO_INT
-
-/*
- * Create unique enum values for each GPIO_INT entry, which also sets
- * the ZEPHYR_GPIO_INT_COUNT value.
- */
-#define ZEPHYR_GPIO_INT_ID(sig) INT_##sig
-#define GPIO_INT(sig, f, cb) ZEPHYR_GPIO_INT_ID(sig),
-enum zephyr_gpio_int_id {
-#ifdef EC_CROS_GPIO_INTERRUPTS
- EC_CROS_GPIO_INTERRUPTS
-#endif
- ZEPHYR_GPIO_INT_COUNT,
-};
-#undef GPIO_INT
-
-/* Create prototypes for each GPIO IRQ handler */
-#define GPIO_INT(sig, f, cb) void cb(enum gpio_signal signal);
-#ifdef EC_CROS_GPIO_INTERRUPTS
-EC_CROS_GPIO_INTERRUPTS
-#endif
-#undef GPIO_INT
-
-/*
- * The Zephyr gpio_callback data needs to be updated at runtime, so allocate
- * into uninitialized data (BSS). The constant data pulled from
- * EC_CROS_GPIO_INTERRUPTS is stored separately in the gpio_interrupts[] array.
- */
-static struct gpio_callback zephyr_gpio_callbacks[ZEPHYR_GPIO_INT_COUNT];
-
-#define ZEPHYR_GPIO_CALLBACK_TO_INDEX(cb) \
- (int)(((int)(cb) - (int)&zephyr_gpio_callbacks) / \
- sizeof(struct gpio_callback))
-
-#define GPIO_INT(sig, f, cb) \
- { \
- .signal = sig, \
- .flags = f, \
- .irq_handler = cb, \
- },
-const static struct gpio_signal_callback
- gpio_interrupts[ZEPHYR_GPIO_INT_COUNT] = {
-#ifdef EC_CROS_GPIO_INTERRUPTS
- EC_CROS_GPIO_INTERRUPTS
-#endif
-#undef GPIO_INT
- };
-
-/* The single zephyr gpio handler that routes to appropriate platform/ec cb */
-static void gpio_handler_shim(const struct device *port,
- struct gpio_callback *cb, gpio_port_pins_t pins)
-{
- int callback_index = ZEPHYR_GPIO_CALLBACK_TO_INDEX(cb);
- const struct gpio_signal_callback *const gpio =
- &gpio_interrupts[callback_index];
-
- /* Call the platform/ec gpio interrupt handler */
- gpio->irq_handler(gpio->signal);
-}
-
-/**
- * get_interrupt_from_signal() - Translate a gpio_signal to the
- * corresponding gpio_signal_callback
- *
- * @signal The signal to convert.
- *
- * Return: A pointer to the corresponding entry in gpio_interrupts, or
- * NULL if one does not exist.
- */
-const static struct gpio_signal_callback *
-get_interrupt_from_signal(enum gpio_signal signal)
-{
- if (!gpio_is_implemented(signal))
- return NULL;
-
- for (size_t i = 0; i < ARRAY_SIZE(gpio_interrupts); i++) {
- if (gpio_interrupts[i].signal == signal)
- return &gpio_interrupts[i];
- }
-
- LOG_ERR("No interrupt defined for GPIO %s", configs[signal].name);
- return NULL;
-}
-
-int gpio_is_implemented(enum gpio_signal signal)
-{
- return signal >= 0 && signal < ARRAY_SIZE(configs);
-}
-
-int gpio_get_level(enum gpio_signal signal)
-{
- if (!gpio_is_implemented(signal))
- return 0;
-
- const int l = gpio_pin_get_raw(data[signal].dev, configs[signal].pin);
-
- if (l < 0) {
- LOG_ERR("Cannot read %s (%d)", configs[signal].name, l);
- return 0;
- }
- return l;
-}
-
-int gpio_get_ternary(enum gpio_signal signal)
-{
- int pd, pu;
- int flags = gpio_get_default_flags(signal);
-
- /* Read GPIO with internal pull-down */
- gpio_set_flags(signal, GPIO_INPUT | GPIO_PULL_DOWN);
- pd = gpio_get_level(signal);
- udelay(100);
-
- /* Read GPIO with internal pull-up */
- gpio_set_flags(signal, GPIO_INPUT | GPIO_PULL_UP);
- pu = gpio_get_level(signal);
- udelay(100);
-
- /* Reset GPIO flags */
- gpio_set_flags(signal, flags);
-
- /* Check PU and PD readings to determine tristate */
- return pu && !pd ? 2 : pd;
-}
-
-const char *gpio_get_name(enum gpio_signal signal)
-{
- if (!gpio_is_implemented(signal))
- return "UNIMPLEMENTED";
-
- return configs[signal].name;
-}
-
-void gpio_set_level(enum gpio_signal signal, int value)
-{
- if (!gpio_is_implemented(signal))
- return;
-
- int rv = gpio_pin_set_raw(data[signal].dev, configs[signal].pin, value);
-
- if (rv < 0) {
- LOG_ERR("Cannot write %s (%d)", configs[signal].name, rv);
- }
-}
-
-void gpio_set_level_verbose(enum console_channel channel,
- enum gpio_signal signal, int value)
-{
- cprints(channel, "Set %s: %d", gpio_get_name(signal), value);
- gpio_set_level(signal, value);
-}
-
-/* GPIO flags which are the same in Zephyr and this codebase */
-#define GPIO_CONVERSION_SAME_BITS \
- (GPIO_OPEN_DRAIN | GPIO_PULL_UP | GPIO_PULL_DOWN | GPIO_INPUT | \
- GPIO_OUTPUT)
-
-static int convert_from_zephyr_flags(const gpio_flags_t zephyr)
-{
- /* Start out with the bits that are the same. */
- int ec_flags = zephyr & GPIO_CONVERSION_SAME_BITS;
- gpio_flags_t unhandled_flags = zephyr & ~GPIO_CONVERSION_SAME_BITS;
-
- /* TODO(b/173789980): handle conversion of more bits? */
- if (unhandled_flags) {
- LOG_WRN("Unhandled GPIO bits in zephyr->ec conversion: 0x%08X",
- unhandled_flags);
- }
-
- return ec_flags;
-}
-
-static gpio_flags_t convert_to_zephyr_flags(int ec_flags)
-{
- /* Start out with the bits that are the same. */
- gpio_flags_t zephyr_flags = ec_flags & GPIO_CONVERSION_SAME_BITS;
- int unhandled_flags = ec_flags & ~GPIO_CONVERSION_SAME_BITS;
-
- /* TODO(b/173789980): handle conversion of more bits? */
- if (unhandled_flags) {
- LOG_WRN("Unhandled GPIO bits in ec->zephyr conversion: 0x%08X",
- unhandled_flags);
- }
-
- return zephyr_flags;
-}
-
-int gpio_get_default_flags(enum gpio_signal signal)
-{
- if (!gpio_is_implemented(signal))
- return 0;
-
- return convert_from_zephyr_flags(configs[signal].init_flags);
-}
-
-static int init_gpios(const struct device *unused)
-{
- gpio_flags_t flags;
- struct jump_data *jdata;
- bool is_sys_jumped;
-
- ARG_UNUSED(unused);
-
- jdata = get_jump_data();
-
- if (jdata && jdata->magic == JUMP_DATA_MAGIC)
- is_sys_jumped = true;
- else
- is_sys_jumped = false;
-
- /* Loop through all GPIOs in device tree to set initial configuration */
- for (size_t i = 0; i < ARRAY_SIZE(configs); ++i) {
- data[i].dev = configs[i].dev;
- int rv;
-
- if (!device_is_ready(data[i].dev))
- LOG_ERR("Not found (%s)", configs[i].name);
-
- /*
- * The configs[i].init_flags variable is read-only, so the
- * following assignment is needed because the flags need
- * adjusting on a warm reboot.
- */
- flags = configs[i].init_flags;
-
- if (is_sys_jumped) {
- flags &=
- ~(GPIO_OUTPUT_INIT_LOW | GPIO_OUTPUT_INIT_HIGH);
- }
-
- rv = gpio_pin_configure(data[i].dev, configs[i].pin, flags);
- if (rv < 0) {
- LOG_ERR("Config failed %s (%d)", configs[i].name, rv);
- }
- }
-
- /*
- * Loop through all interrupt pins and set their callback.
- */
- for (size_t i = 0; i < ARRAY_SIZE(gpio_interrupts); ++i) {
- const enum gpio_signal signal = gpio_interrupts[i].signal;
- int rv;
-
- if (signal == GPIO_UNIMPLEMENTED)
- continue;
-
- gpio_init_callback(&zephyr_gpio_callbacks[i], gpio_handler_shim,
- BIT(configs[signal].pin));
- rv = gpio_add_callback(data[signal].dev,
- &zephyr_gpio_callbacks[i]);
-
- if (rv < 0) {
- LOG_ERR("Callback reg failed %s (%d)",
- configs[signal].name, rv);
- continue;
- }
- }
-
- /* Configure unused pins in chip driver for better power consumption */
- if (gpio_config_unused_pins) {
- int rv;
-
- rv = gpio_config_unused_pins();
- if (rv < 0) {
- return rv;
- }
- }
-
- return 0;
-}
-#if CONFIG_PLATFORM_EC_GPIO_INIT_PRIORITY <= CONFIG_KERNEL_INIT_PRIORITY_DEFAULT
-#error "GPIOs must initialize after the kernel default initialization"
-#endif
-SYS_INIT(init_gpios, POST_KERNEL, CONFIG_PLATFORM_EC_GPIO_INIT_PRIORITY);
-
-int gpio_enable_interrupt(enum gpio_signal signal)
-{
- int rv;
- const struct gpio_signal_callback *interrupt;
-
- interrupt = get_interrupt_from_signal(signal);
-
- if (!interrupt)
- return -1;
-
- /*
- * Config interrupt flags (e.g. INT_EDGE_BOTH) & enable interrupt
- * together.
- */
- rv = gpio_pin_interrupt_configure(data[signal].dev, configs[signal].pin,
- (interrupt->flags | GPIO_INT_ENABLE) &
- ~GPIO_INT_DISABLE);
- if (rv < 0) {
- LOG_ERR("Failed to enable interrupt on %s (%d)",
- configs[signal].name, rv);
- }
-
- return rv;
-}
-
-int gpio_disable_interrupt(enum gpio_signal signal)
-{
- int rv;
-
- if (!gpio_is_implemented(signal))
- return -1;
-
- rv = gpio_pin_interrupt_configure(data[signal].dev, configs[signal].pin,
- GPIO_INT_DISABLE);
- if (rv < 0) {
- LOG_ERR("Failed to disable interrupt on %s (%d)",
- configs[signal].name, rv);
- }
-
- return rv;
-}
-
-void gpio_reset(enum gpio_signal signal)
-{
- if (!gpio_is_implemented(signal))
- return;
-
- gpio_pin_configure(data[signal].dev, configs[signal].pin,
- configs[signal].init_flags);
-}
-
-void gpio_set_flags(enum gpio_signal signal, int flags)
-{
- if (!gpio_is_implemented(signal))
- return;
-
- gpio_pin_configure(data[signal].dev, configs[signal].pin,
- convert_to_zephyr_flags(flags));
-}
-
-int signal_is_gpio(int signal)
-{
- return true;
-}
diff --git a/zephyr/shim/src/gpio_id.c b/zephyr/shim/src/gpio_id.c
deleted file mode 100644
index 1dddac2c88..0000000000
--- a/zephyr/shim/src/gpio_id.c
+++ /dev/null
@@ -1,73 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <devicetree.h>
-#include "gpio.h"
-#include "util.h"
-
-#define IS_BOARD_COMPATIBLE \
- DT_NODE_HAS_COMPAT(DT_PATH(board), cros_ec_gpio_id)
-#define IS_SKU_COMPATIBLE \
- DT_NODE_HAS_COMPAT(DT_PATH(sku), cros_ec_gpio_id)
-
-#define CONVERT_NUMERAL_SYSTEM_EVAL(system, bits, nbits) \
- system##_from_bits(bits, nbits)
-#define CONVERT_NUMERAL_SYSTEM(system, bits, nbits) \
- CONVERT_NUMERAL_SYSTEM_EVAL(system, bits, nbits)
-
-#define READ_PIN_FROM_PHANDLE(node_id, prop, idx) \
- gpio_get_ternary(GPIO_SIGNAL(DT_PHANDLE_BY_IDX(node_id, prop, idx))),
-
-#if DT_NODE_EXISTS(DT_PATH(sku)) && IS_SKU_COMPATIBLE
-
-__override uint32_t board_get_sku_id(void)
-{
- static uint32_t sku_id = (uint32_t)-1;
-
- if (sku_id == (uint32_t)-1) {
- int bits[] = {
- DT_FOREACH_PROP_ELEM(DT_PATH(sku),
- bits,
- READ_PIN_FROM_PHANDLE)
- };
-
- if (sizeof(bits) == 0)
- return (uint32_t)-1;
-
- sku_id = CONVERT_NUMERAL_SYSTEM(DT_STRING_TOKEN(DT_PATH(sku),
- system),
- bits, ARRAY_SIZE(bits));
- }
-
- return sku_id;
-}
-
-#endif
-
-#if DT_NODE_EXISTS(DT_PATH(board)) && IS_BOARD_COMPATIBLE
-
-__override int board_get_version(void)
-{
- static int board_version = -1;
-
- if (board_version == -1) {
- int bits[] = {
- DT_FOREACH_PROP_ELEM(DT_PATH(board),
- bits,
- READ_PIN_FROM_PHANDLE)
- };
-
- if (sizeof(bits) == 0)
- return -1;
-
- board_version = CONVERT_NUMERAL_SYSTEM(
- DT_STRING_TOKEN(DT_PATH(board), system), bits,
- ARRAY_SIZE(bits));
- }
-
- return board_version;
-}
-
-#endif
diff --git a/zephyr/shim/src/hooks.c b/zephyr/shim/src/hooks.c
deleted file mode 100644
index 79a611812f..0000000000
--- a/zephyr/shim/src/hooks.c
+++ /dev/null
@@ -1,122 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <kernel.h>
-#include <zephyr.h>
-
-#include "common.h"
-#include "console.h"
-#include "ec_tasks.h"
-#include "hooks.h"
-#include "task.h"
-#include "timer.h"
-
-int hook_call_deferred(const struct deferred_data *data, int us)
-{
- struct k_work_delayable *work = data->work;
- int rv = 0;
-
- if (us == -1) {
- k_work_cancel_delayable(work);
- } else if (us >= 0) {
- rv = k_work_reschedule(work, K_USEC(us));
- if (rv == -EINVAL) {
- /* Already processing or completed. */
- return 0;
- } else if (rv < 0) {
- cprints(CC_HOOK,
- "Warning: deferred call not submitted, "
- "deferred_data=0x%pP, err=%d",
- data, rv);
- }
- } else {
- return EC_ERROR_PARAM2;
- }
-
- return rv;
-}
-
-static struct zephyr_shim_hook_list *hook_registry[HOOK_TYPE_COUNT];
-
-static int zephyr_shim_setup_hooks(const struct device *unused)
-{
- STRUCT_SECTION_FOREACH(zephyr_shim_hook_list, entry) {
- struct zephyr_shim_hook_list **loc = &hook_registry[entry->type];
-
- /* Find the correct place to put the entry in the registry. */
- while (*loc && (*loc)->priority < entry->priority)
- loc = &((*loc)->next);
-
- entry->next = *loc;
-
- /* Insert the entry. */
- *loc = entry;
- }
-
- return 0;
-}
-
-SYS_INIT(zephyr_shim_setup_hooks, APPLICATION, 1);
-
-void hook_notify(enum hook_type type)
-{
- struct zephyr_shim_hook_list *p;
-
- for (p = hook_registry[type]; p; p = p->next)
- p->routine();
-}
-
-static void check_hook_task_priority(k_tid_t thread)
-{
- /*
- * Numerically lower priorities take precedence, so verify the hook
- * related threads cannot preempt any of the shimmed tasks.
- */
- if (k_thread_priority_get(thread) < (TASK_ID_COUNT - 1))
- cprintf(CC_HOOK,
- "ERROR: %s has priority %d but must be >= %d\n",
- k_thread_name_get(thread),
- k_thread_priority_get(thread), (TASK_ID_COUNT - 1));
-}
-
-void hook_task(void *u)
-{
- /* Periodic hooks will be called first time through the loop */
- static uint64_t last_second = -SECOND;
- static uint64_t last_tick = -HOOK_TICK_INTERVAL;
-
- /*
- * Verify deferred routines are run at the lowest priority.
- */
- check_hook_task_priority(&k_sys_work_q.thread);
- check_hook_task_priority(k_current_get());
-
- while (1) {
- uint64_t t = get_time().val;
- int next = 0;
-
- if (t - last_tick >= HOOK_TICK_INTERVAL) {
- hook_notify(HOOK_TICK);
- last_tick = t;
- }
-
- if (t - last_second >= SECOND) {
- hook_notify(HOOK_SECOND);
- last_second = t;
- }
-
- /* Calculate when next tick needs to occur */
- t = get_time().val;
- if (last_tick + HOOK_TICK_INTERVAL > t)
- next = last_tick + HOOK_TICK_INTERVAL - t;
-
- /*
- * Sleep until next tick, unless we've already exceeded
- * HOOK_TICK_INTERVAL.
- */
- if (next > 0)
- task_wait_event(next);
- }
-}
diff --git a/zephyr/shim/src/host_command.c b/zephyr/shim/src/host_command.c
deleted file mode 100644
index bf863b48de..0000000000
--- a/zephyr/shim/src/host_command.c
+++ /dev/null
@@ -1,16 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "host_command.h"
-
-struct host_command *zephyr_find_host_command(int command)
-{
- STRUCT_SECTION_FOREACH(host_command, cmd) {
- if (cmd->command == command)
- return cmd;
- }
-
- return NULL;
-}
diff --git a/zephyr/shim/src/hwtimer.c b/zephyr/shim/src/hwtimer.c
deleted file mode 100644
index 85c72c5c59..0000000000
--- a/zephyr/shim/src/hwtimer.c
+++ /dev/null
@@ -1,29 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <kernel.h>
-#include <stdint.h>
-#include <zephyr.h>
-
-#include "hwtimer.h"
-
-uint64_t __hw_clock_source_read64(void)
-{
- return k_ticks_to_us_floor64(k_uptime_ticks());
-}
-
-uint32_t __hw_clock_event_get(void)
-{
- /*
- * CrOS EC event deadlines don't quite make sense in Zephyr
- * terms. Evaluate what to do about this later...
- */
- return 0;
-}
-
-void udelay(unsigned us)
-{
- k_busy_wait(us);
-}
diff --git a/zephyr/shim/src/i2c.c b/zephyr/shim/src/i2c.c
deleted file mode 100644
index 3dba7cde38..0000000000
--- a/zephyr/shim/src/i2c.c
+++ /dev/null
@@ -1,135 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <sys/util.h>
-
-#include "console.h"
-#include "i2c.h"
-#include "i2c/i2c.h"
-
-/*
- * The named-i2c-ports node is required by the I2C shim
- */
-#if !DT_NODE_EXISTS(DT_PATH(named_i2c_ports))
-#error I2C shim requires the named-i2c-ports node to be defined.
-#endif
-
-/*
- * Initialize device bindings in i2c_devices.
- * This macro should be called from within DT_FOREACH_CHILD.
- */
-#define INIT_DEV_BINDING(id) \
- [I2C_PORT(id)] = DEVICE_DT_GET(DT_PHANDLE(id, i2c_port)),
-
-#define INIT_REMOTE_PORTS(id) \
- [I2C_PORT(id)] = DT_PROP_OR(id, remote_port, -1),
-
-#define I2C_PORT_INIT(id) \
- { \
- .name = DT_LABEL(id), \
- .port = I2C_PORT(id), \
- },
-/*
- * Long term we will not need these, for now they're needed to get things to
- * build since these extern symbols are usually defined in
- * board/${BOARD}/board.c.
- *
- * Since all the ports will eventually be handled by device tree. This will
- * be removed at that point.
- */
-const struct i2c_port_t i2c_ports[] = {
- DT_FOREACH_CHILD(DT_PATH(named_i2c_ports), I2C_PORT_INIT)
-};
-const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
-static const int i2c_remote_ports[I2C_PORT_COUNT] = {
- DT_FOREACH_CHILD(DT_PATH(named_i2c_ports), INIT_REMOTE_PORTS)
-};
-static int i2c_physical_ports[I2C_PORT_COUNT];
-
-static const struct device *i2c_devices[I2C_PORT_COUNT] = {
- DT_FOREACH_CHILD(DT_PATH(named_i2c_ports), INIT_DEV_BINDING)
-};
-
-static int init_device_bindings(const struct device *device)
-{
- ARG_UNUSED(device);
-
- /*
- * The EC application may lock the I2C bus for more than a single
- * I2C transaction. Initialize the i2c_physical_ports[] array to map
- * each named-i2c-ports child to the physical bus assignment.
- *
- * TODO(b/199918263): zephyr: Optimize I2C mutexes
- * Modify the port_mutex[] array defined by i2c_controller.c
- * so that only mutexes for unique physical ports are created to
- * save space.
- */
- i2c_physical_ports[0] = 0;
- for (int child = 1; child < I2C_PORT_COUNT; child++) {
- for (int phys_port = 0; phys_port < I2C_PORT_COUNT;
- phys_port++) {
- if (i2c_devices[child] == i2c_devices[phys_port]) {
- i2c_physical_ports[child] = phys_port;
- break;
- }
- }
- }
- return 0;
-}
-SYS_INIT(init_device_bindings, POST_KERNEL, 51);
-
-const struct device *i2c_get_device_for_port(const int port)
-{
- if (port < 0 || port >= I2C_PORT_COUNT)
- return NULL;
- return i2c_devices[port];
-}
-
-int i2c_get_port_from_remote_port(int remote_port)
-{
- for (int port = 0; port < I2C_PORT_COUNT; port++) {
- if (i2c_remote_ports[port] == remote_port)
- return port;
- }
-
- /*
- * Remote port is not defined, return 1:1 mapping to support TCPC
- * firmware updates, which always query the EC for the correct I2C
- * port number.
- */
- return remote_port;
-}
-
-int i2c_get_physical_port(int enum_port)
-{
- int i2c_port = i2c_physical_ports[enum_port];
-
- /*
- * Return -1 for caller if physical port is not defined or the
- * port number is out of port_mutex space.
- * Please ensure the caller won't change anything if -1 received.
- */
- return (i2c_port < I2C_PORT_COUNT) ? i2c_port : -1;
-}
-
-#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_I2C_PORTMAP
-static int command_i2c_portmap(int argc, char **argv)
-{
- int i;
-
- ccprintf("Zephyr physical I2C ports (%d):\n", I2C_PORT_COUNT);
- for (i = 0; i < I2C_PORT_COUNT; i++) {
- ccprintf(" %d : %d\n", i, i2c_physical_ports[i]);
- }
- ccprintf("Zephyr remote I2C ports (%d):\n", I2C_PORT_COUNT);
- for (i = 0; i < I2C_PORT_COUNT; i++) {
- ccprintf(" %d : %d\n", i, i2c_remote_ports[i]);
- }
-
- return EC_RES_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(i2c_portmap, command_i2c_portmap, NULL,
- "Show I2C port mapping");
-#endif /* CONFIG_PLATFORM_EC_CONSOLE_CMD_I2C_PORTMAP */
diff --git a/zephyr/shim/src/keyboard_raw.c b/zephyr/shim/src/keyboard_raw.c
deleted file mode 100644
index 8de585a78f..0000000000
--- a/zephyr/shim/src/keyboard_raw.c
+++ /dev/null
@@ -1,77 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/* Functions needed by keyboard scanner module for Chrome EC */
-
-#include <device.h>
-#include <logging/log.h>
-#include <soc.h>
-#include <zephyr.h>
-
-#include "drivers/cros_kb_raw.h"
-#include "keyboard_raw.h"
-
-LOG_MODULE_REGISTER(shim_cros_kb_raw, LOG_LEVEL_ERR);
-
-#define CROS_KB_RAW_NODE DT_NODELABEL(cros_kb_raw)
-static const struct device *cros_kb_raw_dev;
-
-/**
- * Initialize the raw keyboard interface.
- */
-void keyboard_raw_init(void)
-{
- cros_kb_raw_dev = DEVICE_DT_GET(CROS_KB_RAW_NODE);
- if (!device_is_ready(cros_kb_raw_dev)) {
- LOG_ERR("Error: device %s is not ready", cros_kb_raw_dev->name);
- return;
- }
-
- LOG_INF("%s", __func__);
- cros_kb_raw_init(cros_kb_raw_dev);
-}
-
-/**
- * Finish initialization after task scheduling has started.
- */
-void keyboard_raw_task_start(void)
-{
- keyboard_raw_enable_interrupt(1);
-}
-
-/**
- * Drive the specified column low.
- */
-test_mockable void keyboard_raw_drive_column(int col)
-{
- if (cros_kb_raw_dev)
- cros_kb_raw_drive_column(cros_kb_raw_dev, col);
- else
- LOG_ERR("%s: no cros_kb_raw device!", __func__);
-}
-
-/**
- * Read raw row state.
- * Bits are 1 if signal is present, 0 if not present.
- */
-test_mockable int keyboard_raw_read_rows(void)
-{
- if (cros_kb_raw_dev)
- return cros_kb_raw_read_rows(cros_kb_raw_dev);
-
- LOG_ERR("%s: no cros_kb_raw device!", __func__);
- return -EIO;
-}
-
-/**
- * Enable or disable keyboard interrupts.
- */
-void keyboard_raw_enable_interrupt(int enable)
-{
- if (cros_kb_raw_dev)
- cros_kb_raw_enable_interrupt(cros_kb_raw_dev, enable);
- else
- LOG_ERR("%s: no cros_kb_raw device!", __func__);
-}
diff --git a/zephyr/shim/src/keyscan.c b/zephyr/shim/src/keyscan.c
deleted file mode 100644
index fa8fb11dd2..0000000000
--- a/zephyr/shim/src/keyscan.c
+++ /dev/null
@@ -1,34 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#define DT_DRV_COMPAT cros_keyscan
-
-#include <assert.h>
-#include <kernel.h>
-#include <soc.h>
-
-#include "keyboard_scan.h"
-
-#if DT_NODE_EXISTS(DT_INST(0, cros_keyscan))
-
-/* The keyboard matrix should have at least enough columns for the
- * standard keyboard with no keypad.
- */
-BUILD_ASSERT(DT_INST_PROP_LEN(0, actual_key_mask) >= KEYBOARD_COLS_NO_KEYPAD);
-
-/*
- * Override the default keyscan_config if the board defines a
- * cros-kb-raw-keyscan node.
- */
-__override struct keyboard_scan_config keyscan_config = {
- .output_settle_us = DT_INST_PROP(0, output_settle),
- .debounce_down_us = DT_INST_PROP(0, debounce_down),
- .debounce_up_us = DT_INST_PROP(0, debounce_up),
- .scan_period_us = DT_INST_PROP(0, scan_period),
- .min_post_scan_delay_us = DT_INST_PROP(0, min_post_scan_delay),
- .poll_timeout_us = DT_INST_PROP(0, poll_timeout),
- .actual_key_mask = DT_INST_PROP(0, actual_key_mask),
-};
-#endif
diff --git a/zephyr/shim/src/libgcc_arm.S b/zephyr/shim/src/libgcc_arm.S
deleted file mode 100644
index ffdbefc675..0000000000
--- a/zephyr/shim/src/libgcc_arm.S
+++ /dev/null
@@ -1,11 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "../../third_party/libaeabi-cortexm0/core/cortex-m/ldivmod.S"
-#include "../../third_party/libaeabi-cortexm0/core/cortex-m/uldivmod.S"
-
-exception_panic:
- mov r0, #3 @ K_ERR_KERNEL_OOPS
- b z_fatal_error
diff --git a/zephyr/shim/src/mkbp_event.c b/zephyr/shim/src/mkbp_event.c
deleted file mode 100644
index 39bcb001b8..0000000000
--- a/zephyr/shim/src/mkbp_event.c
+++ /dev/null
@@ -1,16 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "mkbp_event.h"
-
-const struct mkbp_event_source *zephyr_find_mkbp_event_source(uint8_t type)
-{
- STRUCT_SECTION_FOREACH(mkbp_event_source, evtsrc) {
- if (evtsrc->event_type == type)
- return evtsrc;
- }
-
- return NULL;
-}
diff --git a/zephyr/shim/src/motionsense_driver/bma255-drvinfo.inc b/zephyr/shim/src/motionsense_driver/bma255-drvinfo.inc
deleted file mode 100644
index 7db46811ad..0000000000
--- a/zephyr/shim/src/motionsense_driver/bma255-drvinfo.inc
+++ /dev/null
@@ -1,44 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "driver/accel_bma2x2_public.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensors.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/*
- * Create driver data for each BMI260 drvinfo instance in device tree.
- * (compatible = "cros-ec,drvdata-bma255")
- */
-/* Declare BMA255 driver data */
-#define CREATE_SENSOR_DATA_BMA255(id, drvdata_name) \
- static struct accelgyro_saved_data_t drvdata_name;
-
-CREATE_SENSOR_DATA(cros_ec_drvdata_bma255, CREATE_SENSOR_DATA_BMA255)
-
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensors.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Create a motion_sensor_t entry for each BMA255
- * instance(compatible = "cros-ec,bma255") in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_bma255, MOTIONSENSE_CHIP_BMA255, \
- MOTIONSENSE_TYPE_ACCEL, bma2x2_accel_drv, \
- BMA255_ACCEL_MIN_FREQ, BMA255_ACCEL_MAX_FREQ)
diff --git a/zephyr/shim/src/motionsense_driver/bmi160-drvinfo.inc b/zephyr/shim/src/motionsense_driver/bmi160-drvinfo.inc
deleted file mode 100644
index dd7b21641b..0000000000
--- a/zephyr/shim/src/motionsense_driver/bmi160-drvinfo.inc
+++ /dev/null
@@ -1,57 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "driver/accelgyro_bmi_common_public.h"
-#include "driver/accelgyro_bmi160_public.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensros.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/*
- * Create driver data. It can be shared among the entries in
- * motion_sensors array which are using the same bmi160 driver.
- */
-#define CREATE_SENSOR_DATA_BMI160(id, drvdata_name) \
- static struct bmi_drv_data_t drvdata_name;
-
-/*
- * Create driver data for each BMI160 drvinfo instance in device tree.
- * (compatible = "cros-ec,drvdata-bmi160")
- */
-CREATE_SENSOR_DATA(cros_ec_drvdata_bmi160, CREATE_SENSOR_DATA_BMI160)
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensors.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each BMI160_accel instance(compatible = "cros-ec,bmi160-accel")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_bmi160_accel, MOTIONSENSE_CHIP_BMI160, \
- MOTIONSENSE_TYPE_ACCEL, bmi160_drv, \
- BMI_ACCEL_MIN_FREQ, BMI_ACCEL_MAX_FREQ)
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each BMI260_gyro instance (compatible = "cros-ec,bmi160-gyro")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_bmi160_gyro, MOTIONSENSE_CHIP_BMI160, \
- MOTIONSENSE_TYPE_GYRO, bmi160_drv, \
- BMI_GYRO_MIN_FREQ, BMI_GYRO_MAX_FREQ)
diff --git a/zephyr/shim/src/motionsense_driver/bmi260-drvinfo.inc b/zephyr/shim/src/motionsense_driver/bmi260-drvinfo.inc
deleted file mode 100644
index 2457fca31a..0000000000
--- a/zephyr/shim/src/motionsense_driver/bmi260-drvinfo.inc
+++ /dev/null
@@ -1,57 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "driver/accelgyro_bmi_common_public.h"
-#include "driver/accelgyro_bmi260_public.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensros.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/*
- * Create driver data. It can be shared among the entries in
- * motion_sensors array which are using the same bmi260 driver.
- */
-#define CREATE_SENSOR_DATA_BMI260(id, drvdata_name) \
- static struct bmi_drv_data_t drvdata_name;
-
-/*
- * Create driver data for each BMI260 drvinfo instance in device tree.
- * (compatible = "cros-ec,drvdata-bmi260")
- */
-CREATE_SENSOR_DATA(cros_ec_drvdata_bmi260, CREATE_SENSOR_DATA_BMI260)
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensros.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each BMI260_accel instance(compatible = "cros-ec,bmi260-accel")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_bmi260_accel, MOTIONSENSE_CHIP_BMI260, \
- MOTIONSENSE_TYPE_ACCEL, bmi260_drv, \
- BMI_ACCEL_MIN_FREQ, BMI_ACCEL_MAX_FREQ)
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each BMI260_gyro instance (compatible = "cros-ec,bmi260-gyro")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_bmi260_gyro, MOTIONSENSE_CHIP_BMI260, \
- MOTIONSENSE_TYPE_GYRO, bmi260_drv, \
- BMI_GYRO_MIN_FREQ, BMI_GYRO_MAX_FREQ)
diff --git a/zephyr/shim/src/motionsense_driver/drvdata-accelgyro.h b/zephyr/shim/src/motionsense_driver/drvdata-accelgyro.h
deleted file mode 100644
index 069587f90f..0000000000
--- a/zephyr/shim/src/motionsense_driver/drvdata-accelgyro.h
+++ /dev/null
@@ -1,127 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/*
- * Macros are to help creating driver data. A driver data that uses
- * any data structures defined in accelgyro.h should use the macros here
- * to utilize the information in device tree.
- *
- */
-#ifndef __ZEPHYR_SHIM_SRC_MOTIONSENSE_DRIVER_DRVDATA_ACCELGYRO_H
-#define __ZEPHYR_SHIM_SRC_MOTIONSENSE_DRIVER_DRVDATA_ACCELGYRO_H
-
-/*
- * compatible = "cros-ec,accelgyro-als-channel-scale"
- * als_channel_scale_t in accelgyro.h
- *
- * e.g) The following is the example in DT for als_channel_scale_t
- * als-channel-scale {
- * compatible = "cros-ec,accelgyro-als-channel-scale";
- * k-channel-scale = <1>;
- * cover-scale = <1>;
- * };
- */
-#define ACCELGYRO_ALS_CHANNEL_SCALE(id) \
- { \
- .k_channel_scale = \
- ALS_CHANNEL_SCALE(DT_PROP(id, k_channel_scale)),\
- .cover_scale = \
- ALS_CHANNEL_SCALE(DT_PROP(id, cover_scale)), \
- }
-
-#define ALS_CALIBRATION_CHANNEL_SCALE(id) \
- .als_cal.channel_scale = ACCELGYRO_ALS_CHANNEL_SCALE(id),
-
-#define ALS_CALIBRATION_SET(id) \
- .als_cal.scale = DT_PROP(id, scale), \
- .als_cal.uscale = DT_PROP(id, uscale), \
- .als_cal.offset = DT_PROP(id, offset), \
- ALS_CALIBRATION_CHANNEL_SCALE(DT_CHILD(id, als_channel_scale))
-
-/*
- * compatible = "cros-ec,accelgyro-als-drv-data"
- * als_drv_data_t in accelgyro.h
- *
- * e.g) The following is the example in DT for als_drv_data_t
- * als-drv-data {
- * compatible = "cros-ec,accelgyro-als-drv-data";
- * als-cal {
- * scale = <1>;
- * uscale = <0>;
- * offset = <0>;
- * als-channel-scale {
- * compatible = "cros-ec,accelgyro-als-channel-scale";
- * k-channel-scale = <1>;
- * cover-scale = <1>;
- * };
- * };
- * };
- */
-#define ACCELGYRO_ALS_DRV_DATA(id) \
- { \
- ALS_CALIBRATION_SET(DT_CHILD(id, als_cal)) \
- }
-
-#define RGB_CAL_RGB_SET_SCALE(id) \
- .scale = ACCELGYRO_ALS_CHANNEL_SCALE(id),
-
-#define RGB_CAL_RGB_SET_ONE(id, suffix) \
- .rgb_cal[suffix] = { \
- .offset = DT_PROP(id, offset), \
- .coeff[0] = FLOAT_TO_FP(DT_PROP_BY_IDX(id, coeff, 0)), \
- .coeff[1] = FLOAT_TO_FP(DT_PROP_BY_IDX(id, coeff, 1)), \
- .coeff[2] = FLOAT_TO_FP(DT_PROP_BY_IDX(id, coeff, 2)), \
- .coeff[3] = FLOAT_TO_FP(DT_PROP_BY_IDX(id, coeff, 3)), \
- RGB_CAL_RGB_SET_SCALE(DT_CHILD(id, als_channel_scale)) \
- },
-
-/*
- * compatible = "cros-ec,accelgyro-rgb-calibration"
- * rgb_calibration_t in accelgyro.h
- *
- * e.g) The following is the example in DT for rgb_calibration_t
- * rgb_calibration {
- * compatible = "cros-ec,accelgyro-rgb-calibration";
- *
- * irt = <1>;
- *
- * rgb-cal-x {
- * offset = <0>;
- * coeff = <0 0 0 0>;
- * als-channel-scale {
- * compatible = "cros-ec,accelgyro-als-channel-scale";
- * k-channel-scale = <1>;
- * cover-scale = <1>;
- * };
- * };
- * rgb-cal-y {
- * offset = <0>;
- * coeff = <0 0 0 0>;
- * als-channel-scale {
- * compatible = "cros-ec,accelgyro-als-channel-scale";
- * k-channel-scale = <1>;
- * cover-scale = <1>;
- * };
- * };
- * rgb-cal-z {
- * offset = <0>;
- * coeff = <0 0 0 0>;
- * als-channel-scale {
- * compatible = "cros-ec,accelgyro-als-channel-scale";
- * k-channel-scale = <1>;
- * cover-scale = <1>;
- * };
- * };
- * };
- */
-#define ACCELGYRO_RGB_CALIBRATION(id) \
- { \
- RGB_CAL_RGB_SET_ONE(DT_CHILD(id, rgb_cal_x), X) \
- RGB_CAL_RGB_SET_ONE(DT_CHILD(id, rgb_cal_y), Y) \
- RGB_CAL_RGB_SET_ONE(DT_CHILD(id, rgb_cal_z), Z) \
- .irt = INT_TO_FP(DT_PROP(id, irt)), \
- }
-
-#endif /* __ZEPHYR_SHIM_SRC_MOTIONSENSE_DRIVER_DRVDATA_ACCELGYRO_H */
diff --git a/zephyr/shim/src/motionsense_driver/kx022-drvinfo.inc b/zephyr/shim/src/motionsense_driver/kx022-drvinfo.inc
deleted file mode 100644
index 800a9a1543..0000000000
--- a/zephyr/shim/src/motionsense_driver/kx022-drvinfo.inc
+++ /dev/null
@@ -1,44 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "driver/accel_kionix.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensors.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/*
- * Create driver data for each Kionix drvinfo instance in device tree.
- * (compatible = "cros-ec,drvdata-kionix")
- */
-/* Declare Kionix driver data */
-#define CREATE_SENSOR_DATA_KIONIX(id, drvdata_name) \
- static struct kionix_accel_data drvdata_name;
-
-CREATE_SENSOR_DATA(cros_ec_drvdata_kionix, CREATE_SENSOR_DATA_KIONIX)
-
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensors.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Create a motion_sensor_t entry for each KX022
- * instance(compatible = "cros-ec,kx022") in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_kx022, MOTIONSENSE_CHIP_KX022, \
- MOTIONSENSE_TYPE_ACCEL, kionix_accel_drv, \
- KX022_ACCEL_MIN_FREQ, KX022_ACCEL_MAX_FREQ)
diff --git a/zephyr/shim/src/motionsense_driver/lis2dw12-drvinfo.inc b/zephyr/shim/src/motionsense_driver/lis2dw12-drvinfo.inc
deleted file mode 100644
index 433a9d4192..0000000000
--- a/zephyr/shim/src/motionsense_driver/lis2dw12-drvinfo.inc
+++ /dev/null
@@ -1,44 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "accel_lis2dw12_public.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensors.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/*
- * Create driver data for each Kionix drvinfo instance in device tree.
- * (compatible = "cros-ec,drvdata-lis2dw12")
- */
-/* Declare LIS2DW12 driver data */
-#define CREATE_SENSOR_DATA_LIS2DW12(id, drvdata_name) \
- static struct motion_sensor_t drvdata_name;
-
-CREATE_SENSOR_DATA(cros_ec_drvdata_lis2dw12, CREATE_SENSOR_DATA_LIS2DW12)
-
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensors.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Create a motion_sensor_t entry for each LIS2DW12
- * instance(compatible = "cros-ec,lis2dw12") in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_lis2dw12, MOTIONSENSE_CHIP_LIS2DW12, \
- MOTIONSENSE_TYPE_ACCEL, lis2dw12_drv, \
- LIS2DW12_ODR_MIN_VAL, LIS2DW12_ODR_MAX_VAL)
diff --git a/zephyr/shim/src/motionsense_driver/sensor_drv_list.inc b/zephyr/shim/src/motionsense_driver/sensor_drv_list.inc
deleted file mode 100644
index f8fa4b7e53..0000000000
--- a/zephyr/shim/src/motionsense_driver/sensor_drv_list.inc
+++ /dev/null
@@ -1,39 +0,0 @@
-/* Copyright 2021 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.
- */
-
-/*
- * A driver should create <chip>-drvinfo.inc to create
- * driver-specific data and an motion sensor entry in
- * motion_sensors array that are used by motion sense task.
- *
- * This file includes the .inc file and is used by motionsense_sensrs.c to
- * create the sensor driver data and the entries in mostion_sensors array.
- *
- * e.g) bma255-drvinfo.inc is provided for BMA255 chip
- *
- * #ifdef CONFIG_ACCEL_BMA255
- * #include "bma255-drvinfo.inc"
- * #endif
- */
-
-/* supported sensor driver list */
-#ifdef CONFIG_PLATFORM_EC_ACCEL_BMA255
-#include "bma255-drvinfo.inc"
-#endif
-#ifdef CONFIG_PLATFORM_EC_ACCEL_KX022
-#include "kx022-drvinfo.inc"
-#endif
-#ifdef CONFIG_PLATFORM_EC_ACCEL_LIS2DW12
-#include "lis2dw12-drvinfo.inc"
-#endif
-#ifdef CONFIG_PLATFORM_EC_ACCELGYRO_BMI160
-#include "bmi160-drvinfo.inc"
-#endif
-#ifdef CONFIG_PLATFORM_EC_ACCELGYRO_BMI260
-#include "bmi260-drvinfo.inc"
-#endif
-#ifdef CONFIG_PLATFORM_EC_ALS_TCS3400
-#include "tcs3400-drvinfo.inc"
-#endif
diff --git a/zephyr/shim/src/motionsense_driver/tcs3400-drvinfo.inc b/zephyr/shim/src/motionsense_driver/tcs3400-drvinfo.inc
deleted file mode 100644
index 346688d646..0000000000
--- a/zephyr/shim/src/motionsense_driver/tcs3400-drvinfo.inc
+++ /dev/null
@@ -1,79 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "driver/als_tcs3400_public.h"
-
-/*
- * CREATE_SENSOR_DATA which is defined in motionsense_sensros.c is
- * the helper to create sensor driver specific data.
- *
- * CREATE_SENSOR_DATA gets two arguments. One is the compatible
- * property value specified in device tree and the other one is the macro
- * that actually creates sensor driver specific data. The macro gets
- * node id and the name to be used for the sensor driver data.
- */
-
-/* include macros for common data strutures from accelgyro.h */
-#include "drvdata-accelgyro.h"
-
-/* Create driver data for tcs3400 driver. */
-#define CREATE_SENSOR_DATA_TCS3400_CLEAR(id, drvdata_name) \
- static struct als_drv_data_t drvdata_name = \
- ACCELGYRO_ALS_DRV_DATA(DT_CHILD(id, als_drv_data));
-
-/*
- * Create driver data for each TCS3400-clear drvdata instance in device tree.
- * (compatible = "cros-ec,drvdata-tcs3400-clear")
- */
-CREATE_SENSOR_DATA(cros_ec_drvdata_tcs3400_clear, \
- CREATE_SENSOR_DATA_TCS3400_CLEAR)
-
-/* driver data for tcs3400 rgb */
-#define TCS3400_RGB_SATRURATION(id) \
- COND_CODE_1(DT_NODE_HAS_PROP(id, again), \
- (.saturation.again = DT_PROP(id, again),), \
- (.saturation.again = TCS_DEFAULT_AGAIN,)) \
- COND_CODE_1(DT_NODE_HAS_PROP(id, atime), \
- (.saturation.again = DT_PROP(id, atime),), \
- (.saturation.again = TCS_DEFAULT_ATIME,))
-
-#define CREATE_SENSOR_DATA_TCS3400_RGB(id, drvdata_name) \
- static struct tcs3400_rgb_drv_data_t drvdata_name = { \
- .calibration = ACCELGYRO_RGB_CALIBRATION( \
- DT_CHILD(id, rgb_calibration)), \
- TCS3400_RGB_SATRURATION(DT_CHILD(id, saturation)) \
- };
-
-/*
- * Create driver data for each TCS3400-rgb drvdata instance in device tree.
- * (compatible = "cros-ec,drvdata-tcs3400-rgb")
- */
-CREATE_SENSOR_DATA(cros_ec_drvdata_tcs3400_rgb, CREATE_SENSOR_DATA_TCS3400_RGB)
-/*
- * CREATE_MOTION_SENSOR which is defined in motionsense_sensros.c is
- * the macro to create an entry in motion_sensors array.
- * The macro gets value of compatible property of
- * the sensor in device tree and sensor specific values like chip ID,
- * type of sensor, name of driver, default min/max frequency.
- * Then using the values, it creates the corresponding motion_sense_t entry
- * in motion_sensors array.
- */
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each TCS3400 clear instance (compatible = "cros-ec,tcs3400-clear")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_tcs3400_clear, MOTIONSENSE_CHIP_TCS3400, \
- MOTIONSENSE_TYPE_LIGHT, tcs3400_drv, \
- TCS3400_LIGHT_MIN_FREQ, TCS3400_LIGHT_MAX_FREQ)
-
-/*
- * Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * for each TCS3400 RGB instance (compatible = "cros-ec,tcs3400-rgb")
- * in device tree.
- */
-CREATE_MOTION_SENSOR(cros_ec_tcs3400_rgb, MOTIONSENSE_CHIP_TCS3400, \
- MOTIONSENSE_TYPE_LIGHT_RGB, tcs3400_rgb_drv, 0, 0)
diff --git a/zephyr/shim/src/motionsense_sensors.c b/zephyr/shim/src/motionsense_sensors.c
deleted file mode 100644
index 0c54160e2e..0000000000
--- a/zephyr/shim/src/motionsense_sensors.c
+++ /dev/null
@@ -1,403 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "common.h"
-#include "accelgyro.h"
-#include "hooks.h"
-#include "drivers/cros_cbi.h"
-
-#define SENSOR_MUTEX_NODE DT_PATH(motionsense_mutex)
-#define SENSOR_MUTEX_NAME(id) DT_CAT(MUTEX_, id)
-
-#if DT_NODE_EXISTS(SENSOR_MUTEX_NODE)
-#define DECLARE_SENSOR_MUTEX(id) K_MUTEX_DEFINE(SENSOR_MUTEX_NAME(id));
-
-/*
- * Declare mutex for
- * each child node of "/motionsense-mutex" node in DT.
- *
- * A mutex can be shared among the motion sensors.
- */
-DT_FOREACH_CHILD(SENSOR_MUTEX_NODE, DECLARE_SENSOR_MUTEX)
-#endif /* DT_NODE_EXISTS(SENSOR_MUTEX_NODE) */
-
-#define SENSOR_ROT_REF_NODE DT_PATH(motionsense_rotation_ref)
-#define SENSOR_ROT_STD_REF_NAME(id) DT_CAT(ROT_REF_, id)
-#define MAT_ITEM(i, id) FLOAT_TO_FP((int32_t)(DT_PROP_BY_IDX(id, mat33, i)))
-#define DECLARE_SENSOR_ROT_REF(id) \
- static const mat33_fp_t SENSOR_ROT_STD_REF_NAME(id) = { \
- { \
- FOR_EACH_FIXED_ARG(MAT_ITEM, (,), id, 0, 1, 2) \
- }, \
- { \
- FOR_EACH_FIXED_ARG(MAT_ITEM, (,), id, 3, 4, 5) \
- }, \
- { \
- FOR_EACH_FIXED_ARG(MAT_ITEM, (,), id, 6, 7, 8) \
- }, \
- };
-
-/*
- * Declare 3x3 rotation matrix for
- * each child node of "/motionsense-rotation-ref" node in DT.
- *
- * A rotation matrix can be shared among the motion sensors.
- */
-#if DT_NODE_EXISTS(SENSOR_ROT_REF_NODE)
-DT_FOREACH_CHILD(SENSOR_ROT_REF_NODE, DECLARE_SENSOR_ROT_REF)
-#endif
-
-/*
- * Declare sensor driver data for
- * each child node with status = "okay" of
- * "/motionsense-sensor-data" node in DT.
- *
- * A driver data can be shared among the motion sensors.
- */
-#define SENSOR_DATA_NAME(id) DT_CAT(SENSOR_DAT_, id)
-#define SENSOR_DATA_NODE DT_PATH(motionsense_sensor_data)
-
-#define SENSOR_DATA(inst, compat, create_data_macro) \
- create_data_macro(DT_INST(inst, compat), \
- SENSOR_DATA_NAME(DT_INST(inst, compat)))
-
-/*
- * CREATE_SENSOR_DATA is a helper macro that gets
- * compat and create_data_macro as parameters.
- *
- * For each node with compatible = "compat",
- * CREATE_SENSOR_DATA expands "create_data_macro" macro with the node id and
- * the designated name for the sensor driver data to be created. The
- * "create_datda_macro" macro is responsible for creating the sensor driver
- * data with the name.
- *
- * Sensor drivers should provide <chip>-drvinfo.inc file and, in the file,
- * it should have the macro that creates its sensor driver data using device
- * tree and pass the macro via CREATE_SENSOR_DATA.
- *
- * e.g) The below is contents of tcs3400-drvinfo.inc file. The file has
- * CREATE_SENSOR_DATA_TCS3400_CLEAR that creates the static instance of
- * "struct als_drv_data_t" with the given name and initializes it
- * with device tree. Then use CREATE_SENSOR_DATA.
- *
- * ----------- bma255-drvinfo.inc -----------
- * #define CREATE_SENSOR_DATA_TCS3400_CLEAR(id, drvdata_name) \
- * static struct als_drv_data_t drvdata_name = \
- * ACCELGYRO_ALS_DRV_DATA(DT_CHILD(id, als_drv_data));
- *
- * CREATE_SENSOR_DATA(cros_ec_drvdata_tcs3400_clear, \
- * CREATE_SENSOR_DATA_TCS3400_CLEAR)
- */
-#define CREATE_SENSOR_DATA(compat, create_data_macro) \
- UTIL_LISTIFY(DT_NUM_INST_STATUS_OKAY(compat), SENSOR_DATA, \
- compat, create_data_macro)
-
-/*
- * sensor_drv_list.inc is included three times in this file. This is the first
- * time and it is for creating sensor driver-specific data. So we ignore
- * CREATE_MOTION_SENSOR() that creates motion sensor at this time.
- */
-#define CREATE_MOTION_SENSOR(s_compat, s_chip, s_type, s_drv, \
- s_min_freq, s_max_freq)
-
-/*
- * Here, we declare all sensor driver data. How to create the data is
- * defined in <chip>-drvinfo.inc file and ,in turn, the file is included
- * in sensor_drv_list.inc.
- */
-#if DT_NODE_EXISTS(SENSOR_DATA_NODE)
-#include "motionsense_driver/sensor_drv_list.inc"
-#endif
-
-/*
- * Get the address of the mutex which is referred by phandle.
- * See motionsense-sensor-base.yaml and cros-ec,motionsense-mutex.yaml
- * for DT example and details.
- */
-#define SENSOR_MUTEX(id) \
- IF_ENABLED(DT_NODE_HAS_PROP(id, mutex), \
- (.mutex = &SENSOR_MUTEX_NAME(DT_PHANDLE(id, mutex)),))
-
-/*
- * Get I2C port number which is referred by phandle.
- * See motionsense-sensor-base.yaml for DT example and details.
- */
-#define SENSOR_I2C_PORT(id) \
- IF_ENABLED(DT_NODE_HAS_PROP(id, port), \
- (.port = I2C_PORT(DT_PHANDLE(id, port)),))
-
-/*
- * Get I2C or SPI address.
- * See motionsense-sensor-base.yaml for DT example and details.
- */
-#define SENSOR_I2C_SPI_ADDR_FLAGS(id) \
- IF_ENABLED(DT_NODE_HAS_PROP(id, i2c_spi_addr_flags), \
- (.i2c_spi_addr_flags = \
- DT_STRING_TOKEN(id, i2c_spi_addr_flags), ))
-
-/*
- * Get the address of rotation matrix which is referred by phandle.
- * See motionsense-sensor-base.yaml and cros-ec,motionsense-rotation-ref.yaml
- * for DT example and details.
- */
-#define SENSOR_ROT_STD_REF(id) \
- IF_ENABLED(DT_NODE_HAS_PROP(id, rot_standard_ref), \
- (.rot_standard_ref = \
- &SENSOR_ROT_STD_REF_NAME(DT_PHANDLE(id, rot_standard_ref)),))
-
-/*
- * Get the address of driver-specific data which is referred by phandle.
- * See motionsense-sensor-base.yaml for DT example and details.
- */
-#define SENSOR_DRV_DATA(id) \
- IF_ENABLED(DT_NODE_HAS_PROP(id, drv_data), \
- (.drv_data = &SENSOR_DATA_NAME(DT_PHANDLE(id, drv_data)),))
-
-/*
- * Get odr and ec_rate for the motion sensor.
- * See motionsense-sensor-base.yaml and cros-ec,motionsense-sensor-config.yaml
- * for DT example and details.
- */
-#define SET_CONFIG_EC(cfg_id, cfg_suffix) \
- [SENSOR_CONFIG_##cfg_suffix] = { \
- IF_ENABLED(DT_NODE_HAS_PROP(cfg_id, odr), \
- (.odr = DT_PROP(cfg_id, odr),)) \
- IF_ENABLED(DT_NODE_HAS_PROP(cfg_id, ec_rate), \
- (.ec_rate = DT_PROP(cfg_id, ec_rate),)) \
- }
-
-/* Get configs */
-#define CREATE_SENSOR_CONFIG(cfgs_id) \
- .config = { \
- IF_ENABLED(DT_NODE_EXISTS(DT_CHILD(cfgs_id, ap)), \
- (SET_CONFIG_EC(DT_CHILD(cfgs_id, ap), AP),)) \
- IF_ENABLED(DT_NODE_EXISTS(DT_CHILD(cfgs_id, ec_s0)), \
- (SET_CONFIG_EC(DT_CHILD(cfgs_id, ec_s0), EC_S0),)) \
- IF_ENABLED(DT_NODE_EXISTS(DT_CHILD(cfgs_id, ec_s3)), \
- (SET_CONFIG_EC(DT_CHILD(cfgs_id, ec_s3), EC_S3),)) \
- IF_ENABLED(DT_NODE_EXISTS(DT_CHILD(cfgs_id, ec_s5)), \
- (SET_CONFIG_EC(DT_CHILD(cfgs_id, ec_s5), EC_S5),)) \
- }
-
-#define SENSOR_CONFIG(id) \
- IF_ENABLED(DT_NODE_EXISTS(DT_CHILD(id, configs)), \
- (CREATE_SENSOR_CONFIG(DT_CHILD(id, configs)),))
-
-/* Get and assign the basic information for a motion sensor */
-#define SENSOR_BASIC_INFO(id) \
- .name = DT_LABEL(id), \
- .active_mask = DT_STRING_TOKEN(id, active_mask), \
- .location = DT_STRING_TOKEN(id, location), \
- .default_range = DT_PROP(id, default_range), \
- SENSOR_I2C_SPI_ADDR_FLAGS(id) \
- SENSOR_MUTEX(id) \
- SENSOR_I2C_PORT(id) \
- SENSOR_ROT_STD_REF(id) \
- SENSOR_DRV_DATA(id) \
- SENSOR_CONFIG(id)
-
-/* Create motion sensor node with node ID */
-#define DO_MK_SENSOR_ENTRY( \
- id, s_chip, s_type, s_drv, s_min_freq, s_max_freq) \
- [SENSOR_ID(id)] = { \
- SENSOR_BASIC_INFO(id) \
- .chip = s_chip, \
- .type = s_type, \
- .drv = &s_drv, \
- .min_frequency = s_min_freq, \
- .max_frequency = s_max_freq \
- },
-
-/* Construct an entry iff the alternate_for property is missing. */
-#define MK_SENSOR_ENTRY(inst, s_compat, s_chip, s_type, s_drv, s_min_freq, \
- s_max_freq) \
- COND_CODE_0(DT_NODE_HAS_PROP(DT_INST(inst, s_compat), alternate_for), \
- (DO_MK_SENSOR_ENTRY(DT_INST(inst, s_compat), s_chip, \
- s_type, s_drv, s_min_freq, \
- s_max_freq)), \
- ())
-
-/* Construct an entry iff the alternate_for property exists. */
-#define MK_SENSOR_ALT_ENTRY(inst, s_compat, s_chip, s_type, s_drv, s_min_freq, \
- s_max_freq) \
- COND_CODE_1(DT_NODE_HAS_PROP(DT_INST(inst, s_compat), alternate_for), \
- (DO_MK_SENSOR_ENTRY(DT_INST(inst, s_compat), s_chip, \
- s_type, s_drv, s_min_freq, \
- s_max_freq)), \
- ())
-
-#undef CREATE_SENSOR_DATA
-/*
- * Sensor driver-specific data creation stage is already done. So this
- * time we ignore CREATE_SENSOR_DATA().
- */
-#define CREATE_SENSOR_DATA(compat, create_data_macro)
-#undef CREATE_MOTION_SENSOR
-
-/*
- * CREATE_MOTION_SENSOR is a help macro that read the sensor information from
- * device tree and creates an entry in motion_sensors array which is used
- * by motion sense task. The help macro gets compatible value of the
- * sensor node and several driver specific information like CHIP_ID,
- * SENSOR_TYPE, driver instance name, and min/max frequency.
- *
- * <chip>-drvinfo.inc file which is provided by sensor driver should use
- * CREATE_MOTION_SENSOR to provide driver specific information.
- *
- * e.g) The below is contents of tcs3400-drvinfo.inc file. The file has
- * CREATE_MOTION_SENSOR like below to create the sensor entry. The file uses
- * the help macro two times since the chip supports two functions
- * ALS clear and ALS RGB.
-
- * ------------- tcs3400-drvinfo.inc -------------
- * // Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * // for each TCS3400 clear instance (compatible = "cros-ec,tcs3400-clear")
- * // in device tree.
- * CREATE_MOTION_SENSOR(cros_ec_tcs3400_clear, MOTIONSENSE_CHIP_TCS3400, \
- * MOTIONSENSE_TYPE_LIGHT, tcs3400_drv, \
- * TCS3400_LIGHT_MIN_FREQ, TCS3400_LIGHT_MAX_FREQ)
-
- *
- * // Here, we call CREATE_MOTION_SENSOR to create a motion_sensor_t entry
- * // for each TCS3400 RGB instance (compatible = "cros-ec,tcs3400-rgb")
- * // in device tree.
- *
- * CREATE_MOTION_SENSOR(cros_ec_tcs3400_rgb, MOTIONSENSE_CHIP_TCS3400, \
- * MOTIONSENSE_TYPE_LIGHT_RGB, tcs3400_rgb_drv, 0, 0)
- * -----------------------------------------------
- */
-#define CREATE_MOTION_SENSOR(s_compat, s_chip, s_type, s_drv, \
- s_min_freq, s_max_freq) \
- UTIL_LISTIFY(DT_NUM_INST_STATUS_OKAY(s_compat), MK_SENSOR_ENTRY,\
- s_compat, s_chip, s_type, s_drv, s_min_freq, s_max_freq)
-
-/*
- * Here, we include sensor_drv_list.inc AGAIN but this time it only
- * uses CREATE_MOTION_SENSOR to create the motion sensor entries.
- */
-struct motion_sensor_t motion_sensors[] = {
-#if DT_NODE_EXISTS(SENSOR_NODE)
-#include "motionsense_driver/sensor_drv_list.inc"
-#endif
-};
-
-/*
- * Remap the CREATE_MOTION_SENSOR to call MK_SENSOR_ALT_ENTRY to create a list
- * of alternate sensors that will be used at runtime.
- */
-#undef CREATE_MOTION_SENSOR
-#define CREATE_MOTION_SENSOR(s_compat, s_chip, s_type, s_drv, s_min_freq, \
- s_max_freq) \
- UTIL_LISTIFY(DT_NUM_INST_STATUS_OKAY(s_compat), MK_SENSOR_ALT_ENTRY, \
- s_compat, s_chip, s_type, s_drv, s_min_freq, s_max_freq)
-
-/*
- * The list of alternate motion sensors that may be used at runtime to replace
- * an entry in the motion_sensors array.
- */
-__maybe_unused struct motion_sensor_t motion_sensors_alt[] = {
-#if DT_NODE_EXISTS(SENSOR_ALT_NODE)
-#include "motionsense_driver/sensor_drv_list.inc"
-#endif
-};
-
-#ifdef CONFIG_DYNAMIC_MOTION_SENSOR_COUNT
-unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
-#else
-const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
-#endif
-
-/*
- * Create a list of ALS sensors needed by motion sense
- *
- * The following example adds tcs3400 als sensor to motion_als_sensors array
- *
- * motionsense-sensors {
- * lid_accel: bma255 {
- * :
- * };
- * :
- * :
- * als_clear: tcs3400 {
- * :
- * };
- * };
- *
- * motionsense-sensor-info {
- * compatible = "cros-ec,motionsense-sensor-info";
- *
- * // list of entries for motion_als_sensors
- * als-sensors = <&als_clear>;
- * :
- * :
- * };
- */
-#if DT_NODE_HAS_PROP(SENSOR_INFO_NODE, als_sensors)
-#define ALS_SENSOR_ENTRY_WITH_COMMA(i, id) \
- &motion_sensors[SENSOR_ID(DT_PHANDLE_BY_IDX(id, als_sensors, i))],
-const struct motion_sensor_t *motion_als_sensors[] = {
- UTIL_LISTIFY(DT_PROP_LEN(SENSOR_INFO_NODE, als_sensors),
- ALS_SENSOR_ENTRY_WITH_COMMA, SENSOR_INFO_NODE)
-};
-BUILD_ASSERT(ARRAY_SIZE(motion_als_sensors) == ALS_COUNT);
-#endif
-
-/*
- * Enable interrupts for motion sensors
- *
- * e.g) list of named-gpio nodes
- * motionsense-sensor-info {
- * compatible = "cros-ec,motionsense-sensor-info";
- *
- * // list of GPIO interrupts that have to
- * // be enabled at initial stage
- * sensor-irqs = <&gpio_ec_imu_int_l &gpio_ec_als_rgb_int_l>;
- * };
- */
-#if DT_NODE_HAS_PROP(SENSOR_INFO_NODE, sensor_irqs)
-#define SENSOR_GPIO_ENABLE_INTERRUPT(i, id) \
- gpio_enable_interrupt( \
- GPIO_SIGNAL(DT_PHANDLE_BY_IDX(id, sensor_irqs, i)));
-static void sensor_enable_irqs(void)
-{
- UTIL_LISTIFY(DT_PROP_LEN(SENSOR_INFO_NODE, sensor_irqs),
- SENSOR_GPIO_ENABLE_INTERRUPT, SENSOR_INFO_NODE)
-}
-DECLARE_HOOK(HOOK_INIT, sensor_enable_irqs, HOOK_PRIO_DEFAULT);
-#endif
-
-/* Handle the alternative motion sensors */
-#define REPLACE_ALT_MOTION_SENSOR(new_id, old_id) \
- motion_sensors[SENSOR_ID(old_id)] = \
- motion_sensors_alt[SENSOR_ID(new_id)];
-
-#define CHECK_AND_REPLACE_ALT_MOTION_SENSOR(id) \
- do { \
- if (cros_cbi_ssfc_check_match( \
- dev, CBI_SSFC_VALUE_ID(DT_PHANDLE( \
- id, alternate_indicator)))) { \
- REPLACE_ALT_MOTION_SENSOR( \
- id, DT_PHANDLE(id, alternate_for)) \
- } \
- } while (0);
-
-#define ALT_MOTION_SENSOR_INIT_ID(id) \
- COND_CODE_1(UTIL_AND(DT_NODE_HAS_PROP(id, alternate_for), \
- DT_NODE_HAS_PROP(id, alternate_indicator)), \
- (CHECK_AND_REPLACE_ALT_MOTION_SENSOR(id)), ())
-
-void motion_sensors_init_alt(void)
-{
- const struct device *dev = device_get_binding("cros_cbi");
-
- if (dev == NULL)
- return;
-
-#if DT_NODE_EXISTS(SENSOR_ALT_NODE)
- DT_FOREACH_CHILD(SENSOR_ALT_NODE, ALT_MOTION_SENSOR_INIT_ID)
-#endif
-}
-
-DECLARE_HOOK(HOOK_INIT, motion_sensors_init_alt, HOOK_PRIO_INIT_I2C + 1);
diff --git a/zephyr/shim/src/panic.c b/zephyr/shim/src/panic.c
deleted file mode 100644
index 22322cc4ee..0000000000
--- a/zephyr/shim/src/panic.c
+++ /dev/null
@@ -1,160 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <arch/cpu.h>
-#include <fatal.h>
-#include <logging/log.h>
-#include <logging/log_ctrl.h>
-#include <zephyr.h>
-
-#include "common.h"
-#include "panic.h"
-
-/*
- * Arch-specific configuration
- *
- * For each architecture, define:
- * - PANIC_ARCH, which should be the corresponding arch field of the
- * panic_data struct.
- * - PANIC_REG_LIST, which is a macro that takes a parameter M, and
- * applies M to 3-tuples of:
- * - zephyr esf field name
- * - panic_data struct field name
- * - human readable name
- */
-
-#if defined(CONFIG_ARM)
-#define PANIC_ARCH PANIC_ARCH_CORTEX_M
-#define PANIC_REG_LIST(M) \
- M(basic.r0, cm.frame[0], a1) \
- M(basic.r1, cm.frame[1], a2) \
- M(basic.r2, cm.frame[2], a3) \
- M(basic.r3, cm.frame[3], a4) \
- M(basic.r12, cm.frame[4], ip) \
- M(basic.lr, cm.frame[5], lr) \
- M(basic.pc, cm.frame[6], pc) \
- M(basic.xpsr, cm.frame[7], xpsr)
-#define PANIC_REG_EXCEPTION(pdata) pdata->cm.regs[1]
-#define PANIC_REG_REASON(pdata) pdata->cm.regs[3]
-#define PANIC_REG_INFO(pdata) pdata->cm.regs[4]
-#elif defined(CONFIG_RISCV) && !defined(CONFIG_64BIT)
-#define PANIC_ARCH PANIC_ARCH_RISCV_RV32I
-#define PANIC_REG_LIST(M) \
- M(ra, riscv.regs[1], ra) \
- M(tp, riscv.regs[3], tp) \
- M(a0, riscv.regs[4], a0) \
- M(a1, riscv.regs[5], a1) \
- M(a2, riscv.regs[6], a2) \
- M(a3, riscv.regs[7], a3) \
- M(a4, riscv.regs[8], a4) \
- M(a5, riscv.regs[9], a5) \
- M(a6, riscv.regs[10], a6) \
- M(a7, riscv.regs[11], a7) \
- M(t0, riscv.regs[12], t0) \
- M(t1, riscv.regs[13], t1) \
- M(t2, riscv.regs[14], t2) \
- M(t3, riscv.regs[15], t3) \
- M(t4, riscv.regs[16], t4) \
- M(t5, riscv.regs[17], t5) \
- M(t6, riscv.regs[18], t6) \
- M(mepc, riscv.mepc, mepc) \
- M(mstatus, riscv.mcause, mstatus)
-#define PANIC_REG_EXCEPTION(pdata) (pdata->riscv.mcause)
-#define PANIC_REG_REASON(pdata) (pdata->riscv.regs[11])
-#define PANIC_REG_INFO(pdata) (pdata->riscv.regs[10])
-#else
-/* Not implemented for this arch */
-#define PANIC_ARCH 0
-#define PANIC_REG_LIST(M)
-#ifdef CONFIG_PLATFORM_EC_SOFTWARE_PANIC
-static uint8_t placeholder_exception_reg;
-static uint32_t placeholder_reason_reg;
-static uint32_t placeholder_info_reg;
-#define PANIC_REG_EXCEPTION(unused) placeholder_exception_reg
-#define PANIC_REG_REASON(unused) placeholder_reason_reg
-#define PANIC_REG_INFO(unused) placeholder_info_reg
-#endif /* CONFIG_PLATFORM_EC_SOFTWARE_PANIC */
-#endif
-
-/* Macros to be applied to PANIC_REG_LIST as M */
-#define PANIC_COPY_REGS(esf_field, pdata_field, human_name) \
- pdata->pdata_field = esf->esf_field;
-#define PANIC_PRINT_REGS(esf_field, pdata_field, human_name) \
- panic_printf(" %-8s = 0x%08X\n", #human_name, pdata->pdata_field);
-
-void panic_data_print(const struct panic_data *pdata)
-{
- PANIC_REG_LIST(PANIC_PRINT_REGS);
-}
-
-#ifndef CONFIG_LOG
-static void copy_esf_to_panic_data(const z_arch_esf_t *esf,
- struct panic_data *pdata)
-{
- pdata->arch = PANIC_ARCH;
- pdata->struct_version = 2;
- pdata->flags = 0;
- pdata->reserved = 0;
- pdata->struct_size = sizeof(*pdata);
- pdata->magic = PANIC_DATA_MAGIC;
-
- PANIC_REG_LIST(PANIC_COPY_REGS);
-}
-
-void k_sys_fatal_error_handler(unsigned int reason, const z_arch_esf_t *esf)
-{
- panic_printf("Fatal error: %u\n", reason);
-
- if (PANIC_ARCH && esf) {
- copy_esf_to_panic_data(esf, get_panic_data_write());
- panic_data_print(panic_get_data());
- }
-
- LOG_PANIC();
- k_fatal_halt(reason);
- CODE_UNREACHABLE;
-}
-#endif /* CONFIG_LOG */
-
-#ifdef CONFIG_PLATFORM_EC_SOFTWARE_PANIC
-void panic_set_reason(uint32_t reason, uint32_t info, uint8_t exception)
-{
- struct panic_data * const pdata = get_panic_data_write();
-
- /* Setup panic data structure */
- memset(pdata, 0, CONFIG_PANIC_DATA_SIZE);
- pdata->magic = PANIC_DATA_MAGIC;
- pdata->struct_size = CONFIG_PANIC_DATA_SIZE;
- pdata->struct_version = 2;
- pdata->arch = PANIC_ARCH;
-
- /* Log panic cause */
- PANIC_REG_EXCEPTION(pdata) = exception;
- PANIC_REG_REASON(pdata) = reason;
- PANIC_REG_INFO(pdata) = info;
-
- /* Allow architecture specific logic */
- arch_panic_set_reason(reason, info, exception);
-}
-
-void panic_get_reason(uint32_t *reason, uint32_t *info, uint8_t *exception)
-{
- struct panic_data * const pdata = panic_get_data();
-
- if (pdata && pdata->struct_version == 2) {
- *exception = PANIC_REG_EXCEPTION(pdata);
- *reason = PANIC_REG_REASON(pdata);
- *info = PANIC_REG_INFO(pdata);
- } else {
- *exception = *reason = *info = 0;
- }
-}
-
-__overridable void arch_panic_set_reason(uint32_t reason, uint32_t info,
- uint8_t exception)
-{
- /* Default implementation, do nothing. */
-}
-#endif /* CONFIG_PLATFORM_EC_SOFTWARE_PANIC */
diff --git a/zephyr/shim/src/pwm.c b/zephyr/shim/src/pwm.c
deleted file mode 100644
index 39fd72007e..0000000000
--- a/zephyr/shim/src/pwm.c
+++ /dev/null
@@ -1,190 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <device.h>
-#include <devicetree.h>
-#include <drivers/pwm.h>
-#include <logging/log.h>
-
-#include "common.h"
-#include "console.h"
-#include "ec_commands.h"
-#include "pwm.h"
-#include "util.h"
-
-#include "pwm/pwm.h"
-
-LOG_MODULE_REGISTER(pwm_shim, LOG_LEVEL_ERR);
-
-#define USECS_PER_SEC 1000000
-
-/*
- * Initialize the device bindings in pwm_channels.
- * This macro is called from within DT_FOREACH_CHILD
- */
-#define INIT_DEV_BINDING(id) { \
- pwm_configs[PWM_CHANNEL(id)].name = DT_LABEL(id); \
- pwm_configs[PWM_CHANNEL(id)].dev = DEVICE_DT_GET( \
- DT_PHANDLE(id, pwms)); \
- pwm_configs[PWM_CHANNEL(id)].pin = DT_PWMS_CHANNEL(id); \
- pwm_configs[PWM_CHANNEL(id)].flags = DT_PWMS_FLAGS(id); \
- pwm_configs[PWM_CHANNEL(id)].freq = DT_PROP(id, frequency); \
- }
-
-struct pwm_config {
- /* Name */
- const char *name;
- /* PWM pin */
- uint32_t pin;
- /* PWM channel flags. See dt-bindings/pwm/pwm.h */
- pwm_flags_t flags;
- /* PWM operating frequency. Configured by the devicetree */
- uint32_t freq;
-
- /* PWM period in microseconds. Automatically set to 1/frequency */
- uint32_t period_us;
- /* PWM pulse in microseconds. Set by pwm_set_raw_duty */
- uint32_t pulse_us;
- /* Saves whether the PWM channel is currently enabled */
- bool enabled;
-
- /* Runtime device for PWM */
- const struct device *dev;
-};
-
-static struct pwm_config pwm_configs[PWM_CH_COUNT];
-
-static int init_pwms(const struct device *unused)
-{
- struct pwm_config *pwm;
- int rv = 0;
-
- ARG_UNUSED(unused);
-
- /* Initialize PWM data from the device tree */
- DT_FOREACH_CHILD(DT_PATH(named_pwms), INIT_DEV_BINDING)
-
- /* Read the PWM operating frequency, set by the chip driver */
- for (size_t i = 0; i < PWM_CH_COUNT; ++i) {
- pwm = &pwm_configs[i];
-
- if (pwm->dev == NULL) {
- LOG_ERR("Not found (%s)", pwm->name);
- rv = -ENODEV;
- continue;
- }
-
- /*
- * TODO - check that devicetree frequency is less than 1/2
- * max frequency from the chip driver.
- */
- pwm->period_us = USECS_PER_SEC / pwm->freq;
- }
-
- return rv;
-}
-#if CONFIG_PLATFORM_EC_PWM_INIT_PRIORITY <= CONFIG_KERNEL_INIT_PRIORITY_DEVICE
-#error "PWM init priority must be > KERNEL_INIT_PRIORITY_DEVICE"
-#endif
-SYS_INIT(init_pwms, PRE_KERNEL_1, CONFIG_PLATFORM_EC_PWM_INIT_PRIORITY);
-
-static struct pwm_config* pwm_lookup(enum pwm_channel ch)
-{
- __ASSERT(ch < ARRAY_SIZE(pwm_configs), "Invalid PWM channel %d", ch);
-
- return &pwm_configs[ch];
-}
-
-void pwm_enable(enum pwm_channel ch, int enabled)
-{
- struct pwm_config *pwm;
- uint32_t pulse_us;
- int rv;
-
- pwm = pwm_lookup(ch);
- pwm->enabled = enabled;
-
- /*
- * The Zephyr API doesn't provide explicit enable and disable
- * commands. However, setting the pulse width to zero disables
- * the PWM.
- */
- if (enabled)
- pulse_us = pwm->pulse_us;
- else
- pulse_us = 0;
-
- rv = pwm_pin_set_usec(pwm->dev, pwm->pin, pwm->period_us, pulse_us,
- pwm->flags);
-
- if (rv)
- LOG_ERR("pwm_pin_set_usec() failed %s (%d)", pwm->name, rv);
-}
-
-int pwm_get_enabled(enum pwm_channel ch)
-{
- struct pwm_config *pwm;
-
- pwm = pwm_lookup(ch);
- return pwm->enabled;
-}
-
-void pwm_set_raw_duty(enum pwm_channel ch, uint16_t duty)
-{
- struct pwm_config *pwm;
- int rv;
-
- pwm = pwm_lookup(ch);
-
- pwm->pulse_us =
- DIV_ROUND_NEAREST(pwm->period_us * duty, EC_PWM_MAX_DUTY);
-
- LOG_DBG("PWM %s set raw duty (0x%04x), pulse %d", pwm->name, duty,
- pwm->pulse_us);
-
- rv = pwm_pin_set_usec(pwm->dev, pwm->pin, pwm->period_us, pwm->pulse_us,
- pwm->flags);
-
- if (rv)
- LOG_ERR("pwm_pin_set_usec() failed %s (%d)", pwm->name, rv);
-}
-
-uint16_t pwm_get_raw_duty(enum pwm_channel ch)
-{
- struct pwm_config *pwm;
-
- pwm = pwm_lookup(ch);
-
- return DIV_ROUND_NEAREST(pwm->pulse_us * EC_PWM_MAX_DUTY,
- pwm->period_us);
-}
-
-void pwm_set_duty(enum pwm_channel ch, int percent)
-{
- struct pwm_config *pwm;
- int rv;
-
- pwm = pwm_lookup(ch);
-
- pwm->pulse_us = DIV_ROUND_NEAREST(pwm->period_us * percent, 100);
-
- LOG_DBG("PWM %s set percent (%d), pulse %d", pwm->name, percent,
- pwm->pulse_us);
-
- rv = pwm_pin_set_usec(pwm->dev, pwm->pin, pwm->period_us, pwm->pulse_us,
- pwm->flags);
-
- if (rv)
- LOG_ERR("pwm_pin_set_usec() failed %s (%d)", pwm->name, rv);
-}
-
-int pwm_get_duty(enum pwm_channel ch)
-{
- struct pwm_config *pwm;
-
- pwm = pwm_lookup(ch);
-
- return DIV_ROUND_NEAREST(pwm->pulse_us * 100, pwm->period_us);
-}
diff --git a/zephyr/shim/src/pwm_led.c b/zephyr/shim/src/pwm_led.c
deleted file mode 100644
index 48565d2e56..0000000000
--- a/zephyr/shim/src/pwm_led.c
+++ /dev/null
@@ -1,60 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#define DT_DRV_COMPAT cros_ec_pwm_leds
-
-#include <string.h>
-#include <devicetree.h>
-
-#if DT_HAS_COMPAT_STATUS_OKAY(DT_DRV_COMPAT)
-
-#include "led_pwm.h"
-#include "pwm.h"
-
-BUILD_ASSERT(DT_NUM_INST_STATUS_OKAY(cros_ec_pwm_leds) <= 1,
- "Multiple CrOS EC PWM LED instances defined");
-BUILD_ASSERT(DT_INST_PROP_LEN(0, leds) <= 2,
- "Unsupported number of LEDs defined");
-
-#define PWM_CHANNEL_BY_IDX(node_id, prop, idx, led_ch) \
- PWM_CHANNEL(DT_PWMS_CTLR_BY_IDX( \
- DT_PHANDLE_BY_IDX(node_id, prop, idx), led_ch))
-
-#define PWM_LED_INIT(node_id, prop, idx) \
- [PWM_LED##idx] = { \
- .ch0 = PWM_CHANNEL_BY_IDX(node_id, prop, idx, 0), \
- .ch1 = PWM_CHANNEL_BY_IDX(node_id, prop, idx, 1), \
- .ch2 = PWM_CHANNEL_BY_IDX(node_id, prop, idx, 2), \
- .enable = &pwm_enable, \
- .set_duty = &pwm_set_duty, \
- },
-
-struct pwm_led pwm_leds[] = {
- DT_INST_FOREACH_PROP_ELEM(0, leds, PWM_LED_INIT)
-};
-
-struct pwm_led_color_map led_color_map[EC_LED_COLOR_COUNT] = {
- [EC_LED_COLOR_RED] = DT_INST_PROP(0, color_map_red),
- [EC_LED_COLOR_GREEN] = DT_INST_PROP(0, color_map_green),
- [EC_LED_COLOR_BLUE] = DT_INST_PROP(0, color_map_blue),
- [EC_LED_COLOR_YELLOW] = DT_INST_PROP(0, color_map_yellow),
- [EC_LED_COLOR_WHITE] = DT_INST_PROP(0, color_map_white),
- [EC_LED_COLOR_AMBER] = DT_INST_PROP(0, color_map_amber),
-};
-
-BUILD_ASSERT(DT_INST_PROP_LEN(0, brightness_range) == EC_LED_COLOR_COUNT,
- "brightness_range must have exactly EC_LED_COLOR_COUNT values");
-
-static const uint8_t dt_brigthness_range[EC_LED_COLOR_COUNT] = DT_INST_PROP(
- 0, brightness_range);
-
-void led_get_brightness_range(enum ec_led_id led_id, uint8_t *brightness_range)
-{
- /* led_id is ignored, same ranges for all LEDs */
- memcpy(brightness_range, dt_brigthness_range,
- sizeof(dt_brigthness_range));
-}
-
-#endif /* DT_HAS_COMPAT_STATUS_OKAY */
diff --git a/zephyr/shim/src/rtc.c b/zephyr/shim/src/rtc.c
deleted file mode 100644
index 002e60148d..0000000000
--- a/zephyr/shim/src/rtc.c
+++ /dev/null
@@ -1,235 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <logging/log.h>
-#include <kernel.h>
-#include <zephyr.h>
-
-#include "console.h"
-#include "drivers/cros_rtc.h"
-#include "hooks.h"
-#include "host_command.h"
-#include "util.h"
-
-LOG_MODULE_REGISTER(shim_cros_rtc, LOG_LEVEL_ERR);
-
-#define CROS_RTC_NODE DT_CHOSEN(cros_rtc)
-static const struct device *cros_rtc_dev;
-
-#ifdef CONFIG_HOSTCMD_EVENTS
-static void set_rtc_host_event(void)
-{
- host_set_single_event(EC_HOST_EVENT_RTC);
-}
-DECLARE_DEFERRED(set_rtc_host_event);
-#endif
-
-void rtc_callback(const struct device *dev)
-{
- ARG_UNUSED(dev);
-
- if (IS_ENABLED(CONFIG_HOSTCMD_EVENTS)) {
- hook_call_deferred(&set_rtc_host_event_data, 0);
- }
-}
-
-/** Initialize the rtc. */
-static int system_init_rtc(const struct device *unused)
-{
- ARG_UNUSED(unused);
-
- cros_rtc_dev = DEVICE_DT_GET(CROS_RTC_NODE);
- if (!cros_rtc_dev) {
- LOG_ERR("Error: device %s is not ready", cros_rtc_dev->name);
- return -ENODEV;
- }
-
- /* set the RTC callback */
- cros_rtc_configure(cros_rtc_dev, rtc_callback);
-
- return 0;
-}
-SYS_INIT(system_init_rtc, APPLICATION, 1);
-
-uint32_t system_get_rtc_sec(void)
-{
- uint32_t seconds;
-
- cros_rtc_get_value(cros_rtc_dev, &seconds);
-
- return seconds;
-}
-
-void system_set_rtc(uint32_t seconds)
-{
- cros_rtc_set_value(cros_rtc_dev, seconds);
-}
-
-void system_reset_rtc_alarm(void)
-{
- if (!cros_rtc_dev) {
- /* TODO(b/183115086): check the error handler for NULL device */
- LOG_ERR("rtc_dev hasn't initialized.");
- return;
- }
-
- cros_rtc_reset_alarm(cros_rtc_dev);
-}
-
-/*
- * For NPCX series, The alarm counter only stores wakeup time in seconds.
- * Microseconds will be ignored.
- */
-void system_set_rtc_alarm(uint32_t seconds, uint32_t microseconds)
-{
- if (!cros_rtc_dev) {
- LOG_ERR("rtc_dev hasn't initialized.");
- return;
- }
-
- /* If time = 0, clear the current alarm */
- if (seconds == EC_RTC_ALARM_CLEAR && microseconds == 0) {
- system_reset_rtc_alarm();
- return;
- }
-
- seconds += system_get_rtc_sec();
-
- cros_rtc_set_alarm(cros_rtc_dev, seconds, microseconds);
-}
-
-/*
- * Return the seconds remaining before the RTC alarm goes off.
- * Returns 0 if alarm is not set.
- */
-uint32_t system_get_rtc_alarm(void)
-{
- uint32_t seconds, microseconds;
-
- cros_rtc_get_alarm(cros_rtc_dev, &seconds, &microseconds);
-
- /*
- * Return 0:
- * 1. If alarm is not set to go off, OR
- * 2. If alarm is set and has already gone off
- */
- if (seconds == 0) {
- return 0;
- }
-
- return seconds - system_get_rtc_sec();
-}
-
-/* Console commands */
-void print_system_rtc(enum console_channel ch)
-{
- uint32_t sec = system_get_rtc_sec();
-
- cprintf(ch, "RTC: 0x%08x (%d.00 s)\n", sec, sec);
-}
-
-/*
- * TODO(b/179055201): This is similar to the same function in some of the
- * chip-specific code. We should factor out the common parts.
- */
-#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_RTC
-static int command_system_rtc(int argc, char **argv)
-{
- if (argc == 3 && !strcasecmp(argv[1], "set")) {
- char *e;
- unsigned int t = strtoi(argv[2], &e, 0);
-
- if (*e)
- return EC_ERROR_PARAM2;
-
- system_set_rtc(t);
- } else if (argc > 1) {
- return EC_ERROR_INVAL;
- }
-
- print_system_rtc(CC_COMMAND);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(rtc, command_system_rtc, "[set <seconds>]",
- "Get/set real-time clock");
-
-#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_RTC_ALARM
-/**
- * Test the RTC alarm by setting an interrupt on RTC match.
- */
-static int command_rtc_alarm_test(int argc, char **argv)
-{
- int s = 1, us = 0;
- char *e;
-
- if (argc > 1) {
- s = strtoi(argv[1], &e, 10);
- if (*e)
- return EC_ERROR_PARAM1;
- }
- if (argc > 2) {
- us = strtoi(argv[2], &e, 10);
- if (*e)
- return EC_ERROR_PARAM2;
- }
-
- ccprintf("Setting RTC alarm\n");
-
- system_set_rtc_alarm(s, us);
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(rtc_alarm, command_rtc_alarm_test,
- "[seconds [microseconds]]", "Test alarm");
-#endif /* CONFIG_PLATFORM_EC_CONSOLE_CMD_RTC_ALARM */
-#endif /* CONFIG_PLATFORM_EC_CONSOLE_CMD_RTC */
-
-#ifdef CONFIG_PLATFORM_EC_HOSTCMD_RTC
-static enum ec_status system_rtc_get_value(struct host_cmd_handler_args *args)
-{
- struct ec_response_rtc *r = args->response;
-
- r->time = system_get_rtc_sec();
- args->response_size = sizeof(*r);
-
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_GET_VALUE, system_rtc_get_value,
- EC_VER_MASK(0));
-
-static enum ec_status system_rtc_set_value(struct host_cmd_handler_args *args)
-{
- const struct ec_params_rtc *p = args->params;
-
- system_set_rtc(p->time);
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_SET_VALUE, system_rtc_set_value,
- EC_VER_MASK(0));
-
-static enum ec_status system_rtc_set_alarm(struct host_cmd_handler_args *args)
-{
- const struct ec_params_rtc *p = args->params;
-
- system_set_rtc_alarm(p->time, 0);
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_SET_ALARM, system_rtc_set_alarm,
- EC_VER_MASK(0));
-
-static enum ec_status system_rtc_get_alarm(struct host_cmd_handler_args *args)
-{
- struct ec_response_rtc *r = args->response;
-
- r->time = system_get_rtc_alarm();
- args->response_size = sizeof(*r);
-
- return EC_RES_SUCCESS;
-}
-DECLARE_HOST_COMMAND(EC_CMD_RTC_GET_ALARM, system_rtc_get_alarm,
- EC_VER_MASK(0));
-
-#endif /* CONFIG_PLATFORM_EC_HOSTCMD_RTC */
diff --git a/zephyr/shim/src/switchcap_gpio.c b/zephyr/shim/src/switchcap_gpio.c
deleted file mode 100644
index c635978b8b..0000000000
--- a/zephyr/shim/src/switchcap_gpio.c
+++ /dev/null
@@ -1,47 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <devicetree.h>
-#include "common.h"
-#include "gpio.h"
-
-#if DT_NODE_EXISTS(DT_PATH(switchcap))
-
-#if !DT_NODE_HAS_COMPAT(DT_PATH(switchcap), switchcap_gpio)
-#error "Invalid /switchcap node in device tree"
-#endif
-
-#define SC_PIN_ENABLE_PHANDLE \
- DT_PHANDLE_BY_IDX(DT_PATH(switchcap), enable_pin, 0)
-#define SC_PIN_ENABLE \
- GPIO_SIGNAL(SC_PIN_ENABLE_PHANDLE)
-
-#define SC_PIN_POWER_GOOD_PHANDLE \
- DT_PHANDLE_BY_IDX(DT_PATH(switchcap), power_good_pin, 0)
-#define SC_PIN_POWER_GOOD_EXISTS \
- DT_NODE_EXISTS(SC_PIN_POWER_GOOD_PHANDLE)
-#define SC_PIN_POWER_GOOD \
- GPIO_SIGNAL(SC_PIN_POWER_GOOD_PHANDLE)
-
-void board_set_switchcap_power(int enable)
-{
- gpio_set_level(SC_PIN_ENABLE, enable);
-}
-
-int board_is_switchcap_enabled(void)
-{
- return gpio_get_level(SC_PIN_ENABLE);
-}
-
-int board_is_switchcap_power_good(void)
-{
-#if SC_PIN_POWER_GOOD_EXISTS
- return gpio_get_level(SC_PIN_POWER_GOOD);
-#else
- return 1;
-#endif
-}
-
-#endif
diff --git a/zephyr/shim/src/switchcap_ln9310.c b/zephyr/shim/src/switchcap_ln9310.c
deleted file mode 100644
index 0647c2d9ae..0000000000
--- a/zephyr/shim/src/switchcap_ln9310.c
+++ /dev/null
@@ -1,49 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <devicetree.h>
-#include "common.h"
-#include "gpio.h"
-#include "ln9310.h"
-
-#if DT_NODE_EXISTS(DT_PATH(switchcap))
-
-#if !DT_NODE_HAS_COMPAT(DT_PATH(switchcap), switchcap_ln9310)
-#error "Invalid /switchcap node in device tree"
-#endif
-
-#define SC_PIN_ENABLE_L_PHANDLE \
- DT_PHANDLE_BY_IDX(DT_PATH(switchcap), enable_l_pin, 0)
-#define SC_PIN_ENABLE_L \
- GPIO_SIGNAL(SC_PIN_ENABLE_L_PHANDLE)
-
-#define SC_PORT_PHANDLE \
- DT_PHANDLE(DT_PATH(switchcap), port)
-#define SC_PORT DT_STRING_UPPER_TOKEN(SC_PORT_PHANDLE, enum_name)
-
-#define SC_ADDR_FLAGS DT_STRING_UPPER_TOKEN(DT_PATH(switchcap), addr_flags)
-
-void board_set_switchcap_power(int enable)
-{
- gpio_set_level(SC_PIN_ENABLE_L, !enable);
- ln9310_software_enable(enable);
-}
-
-int board_is_switchcap_enabled(void)
-{
- return !gpio_get_level(SC_PIN_ENABLE_L);
-}
-
-int board_is_switchcap_power_good(void)
-{
- return ln9310_power_good();
-}
-
-const struct ln9310_config_t ln9310_config = {
- .i2c_port = SC_PORT,
- .i2c_addr_flags = SC_ADDR_FLAGS,
-};
-
-#endif
diff --git a/zephyr/shim/src/system.c b/zephyr/shim/src/system.c
deleted file mode 100644
index 8db8ba437a..0000000000
--- a/zephyr/shim/src/system.c
+++ /dev/null
@@ -1,378 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <device.h>
-#include <drivers/bbram.h>
-#include <drivers/cros_system.h>
-#include <logging/log.h>
-
-#include "bbram.h"
-#include "common.h"
-#include "console.h"
-#include "cros_version.h"
-#include "system.h"
-#include "watchdog.h"
-
-#define BBRAM_REGION_PD0 DT_PATH(named_bbram_regions, pd0)
-#define BBRAM_REGION_PD1 DT_PATH(named_bbram_regions, pd1)
-#define BBRAM_REGION_PD2 DT_PATH(named_bbram_regions, pd2)
-#define BBRAM_REGION_TRY_SLOT DT_PATH(named_bbram_regions, try_slot)
-
-#define GET_BBRAM_OFFSET(node) \
- DT_PROP(DT_PATH(named_bbram_regions, node), offset)
-#define GET_BBRAM_SIZE(node) DT_PROP(DT_PATH(named_bbram_regions, node), size)
-
-/* 2 second delay for waiting the H1 reset */
-#define WAIT_RESET_TIME \
- (CONFIG_PLATFORM_EC_PREINIT_HW_CYCLES_PER_SEC * 2 / \
- CONFIG_PLATFORM_EC_WAIT_RESET_CYCLES_PER_ITERATION)
-
-LOG_MODULE_REGISTER(shim_system, LOG_LEVEL_ERR);
-
-STATIC_IF_NOT(CONFIG_ZTEST) const struct device *bbram_dev;
-static const struct device *sys_dev;
-
-/* Map idx to a bbram offset/size, or return -1 on invalid idx */
-static int bbram_lookup(enum system_bbram_idx idx, int *offset_out,
- int *size_out)
-{
- switch (idx) {
- case SYSTEM_BBRAM_IDX_PD0:
- *offset_out = DT_PROP(BBRAM_REGION_PD0, offset);
- *size_out = DT_PROP(BBRAM_REGION_PD0, size);
- break;
- case SYSTEM_BBRAM_IDX_PD1:
- *offset_out = DT_PROP(BBRAM_REGION_PD1, offset);
- *size_out = DT_PROP(BBRAM_REGION_PD1, size);
- break;
- case SYSTEM_BBRAM_IDX_PD2:
- *offset_out = DT_PROP(BBRAM_REGION_PD2, offset);
- *size_out = DT_PROP(BBRAM_REGION_PD2, size);
- break;
- case SYSTEM_BBRAM_IDX_TRY_SLOT:
- *offset_out = DT_PROP(BBRAM_REGION_TRY_SLOT, offset);
- *size_out = DT_PROP(BBRAM_REGION_TRY_SLOT, size);
- break;
- default:
- return EC_ERROR_INVAL;
- }
- return EC_SUCCESS;
-}
-
-int system_get_bbram(enum system_bbram_idx idx, uint8_t *value)
-{
- int offset, size, rc;
-
- if (bbram_dev == NULL)
- return EC_ERROR_INVAL;
-
- rc = bbram_lookup(idx, &offset, &size);
- if (rc)
- return rc;
-
- rc = bbram_read(bbram_dev, offset, size, value);
-
- return rc ? EC_ERROR_INVAL : EC_SUCCESS;
-}
-
-void chip_save_reset_flags(uint32_t flags)
-{
- if (bbram_dev == NULL) {
- LOG_ERR("bbram_dev doesn't binding");
- return;
- }
-
- bbram_write(bbram_dev, GET_BBRAM_OFFSET(saved_reset_flags),
- GET_BBRAM_SIZE(saved_reset_flags), (uint8_t *)&flags);
-}
-
-uint32_t chip_read_reset_flags(void)
-{
- uint32_t flags;
-
- if (bbram_dev == NULL) {
- LOG_ERR("bbram_dev doesn't binding");
- return 0;
- }
-
- bbram_read(bbram_dev, GET_BBRAM_OFFSET(saved_reset_flags),
- GET_BBRAM_SIZE(saved_reset_flags), (uint8_t *)&flags);
-
- return flags;
-}
-
-int system_set_scratchpad(uint32_t value)
-{
- if (bbram_dev == NULL) {
- LOG_ERR("bbram_dev doesn't binding");
- return -EC_ERROR_INVAL;
- }
-
- return bbram_write(bbram_dev, GET_BBRAM_OFFSET(scratchpad),
- GET_BBRAM_SIZE(scratchpad), (uint8_t *)&value);
-}
-
-int system_get_scratchpad(uint32_t *value)
-{
- if (bbram_dev == NULL) {
- LOG_ERR("bbram_dev doesn't binding");
- return -EC_ERROR_INVAL;
- }
-
- if (bbram_read(bbram_dev, GET_BBRAM_OFFSET(scratchpad),
- GET_BBRAM_SIZE(scratchpad), (uint8_t *)value)) {
- return -EC_ERROR_INVAL;
- }
-
- return 0;
-}
-
-void system_hibernate(uint32_t seconds, uint32_t microseconds)
-{
- const struct device *sys_dev = device_get_binding("CROS_SYSTEM");
- int err;
-
- /* Flush console before hibernating */
- cflush();
-
- if (board_hibernate)
- board_hibernate();
-
- /* Save 'wake-up from hibernate' reset flag */
- chip_save_reset_flags(chip_read_reset_flags() |
- EC_RESET_FLAG_HIBERNATE);
-
- err = cros_system_hibernate(sys_dev, seconds, microseconds);
- if (err < 0) {
- LOG_ERR("hibernate failed %d", err);
- return;
- }
-
- /* should never reach this point */
- while (1)
- continue;
-}
-
-#ifdef CONFIG_PM
-/**
- * Print low power idle statistics
- */
-static int command_idle_stats(int argc, char **argv)
-{
- const struct device *sys_dev = device_get_binding("CROS_SYSTEM");
-
- timestamp_t ts = get_time();
- uint64_t deep_sleep_ticks = cros_system_deep_sleep_ticks(sys_dev);
-
- ccprintf("Time spent in deep-sleep: %.6llds\n",
- k_ticks_to_us_near64(deep_sleep_ticks));
- ccprintf("Total time on: %.6llds\n", ts.val);
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(idlestats, command_idle_stats,
- "",
- "Print last idle stats");
-#endif
-
-const char *system_get_chip_vendor(void)
-{
- const struct device *sys_dev = device_get_binding("CROS_SYSTEM");
-
- return cros_system_chip_vendor(sys_dev);
-}
-
-const char *system_get_chip_name(void)
-{
- const struct device *sys_dev = device_get_binding("CROS_SYSTEM");
-
- return cros_system_chip_name(sys_dev);
-}
-
-const char *system_get_chip_revision(void)
-{
- const struct device *sys_dev = device_get_binding("CROS_SYSTEM");
-
- return cros_system_chip_revision(sys_dev);
-}
-
-void system_reset(int flags)
-{
- int err;
- uint32_t save_flags;
-
- if (!sys_dev)
- LOG_ERR("sys_dev get binding failed");
-
- /* Disable interrupts to avoid task swaps during reboot */
- interrupt_disable_all();
-
- /* Get flags to be saved in BBRAM */
- system_encode_save_flags(flags, &save_flags);
-
- /* Store flags to battery backed RAM. */
- chip_save_reset_flags(save_flags);
-
- /* If WAIT_EXT is set, then allow 10 seconds for external reset */
- if (flags & SYSTEM_RESET_WAIT_EXT) {
- int i;
-
- /* Wait 10 seconds for external reset */
- for (i = 0; i < 1000; i++) {
- watchdog_reload();
- udelay(10000);
- }
- }
-
- err = cros_system_soc_reset(sys_dev);
-
- if (err < 0)
- LOG_ERR("soc reset failed");
-
- /* should never return */
- while (1)
- continue;
-}
-
-static int check_reset_cause(void)
-{
- uint32_t chip_flags = 0; /* used to write back to the BBRAM */
- uint32_t system_flags = chip_read_reset_flags(); /* system reset flag */
- int chip_reset_cause = 0; /* chip-level reset cause */
-
- chip_reset_cause = cros_system_get_reset_cause(sys_dev);
- if (chip_reset_cause < 0)
- return -1;
-
- /*
- * TODO(b/182876692): Implement CONFIG_POWER_BUTTON_INIT_IDLE &
- * CONFIG_BOARD_FORCE_RESET_PIN.
- */
-
- switch (chip_reset_cause) {
- case POWERUP:
- system_flags |= EC_RESET_FLAG_POWER_ON;
- /*
- * Power-on restart, so set a flag and save it for the next
- * imminent reset. Later code will check for this flag and wait
- * for the second reset. Waking from PSL hibernate is power-on
- * for EC but not for H1, so do not wait for the second reset.
- */
- if (IS_ENABLED(CONFIG_BOARD_RESET_AFTER_POWER_ON) &&
- ((system_flags & EC_RESET_FLAG_HIBERNATE) == 0)) {
- system_flags |= EC_RESET_FLAG_INITIAL_PWR;
- chip_flags |= EC_RESET_FLAG_INITIAL_PWR;
- }
- break;
-
- case VCC1_RST_PIN:
- /*
- * If configured, check the saved flags to see whether the
- * previous restart was a power-on, in which case treat this
- * restart as a power-on as well. This is to workaround the fact
- * that the H1 will reset the EC at power up.
- */
- if (IS_ENABLED(CONFIG_BOARD_RESET_AFTER_POWER_ON)) {
- if (system_flags & EC_RESET_FLAG_INITIAL_PWR) {
- /*
- * The previous restart was a power-on so treat
- * this restart as that, and clear the flag so
- * later code will not wait for the second
- * reset.
- */
- system_flags = (system_flags &
- ~EC_RESET_FLAG_INITIAL_PWR) |
- EC_RESET_FLAG_POWER_ON;
- } else {
- /*
- * No previous reset flag, so this is a
- * subsequent restart i.e any restarts after the
- * second restart caused by the H1.
- */
- system_flags |= EC_RESET_FLAG_RESET_PIN;
- }
- } else {
- system_flags |= EC_RESET_FLAG_RESET_PIN;
- }
- break;
-
- case DEBUG_RST:
- system_flags |= EC_RESET_FLAG_SOFT;
- break;
-
- case WATCHDOG_RST:
- /*
- * Don't set EC_RESET_FLAG_WATCHDOG flag if watchdog is issued
- * by system_reset or hibernate in order to distinguish reset
- * cause is panic reason or not.
- */
- if (!(system_flags & (EC_RESET_FLAG_SOFT | EC_RESET_FLAG_HARD |
- EC_RESET_FLAG_HIBERNATE)))
- system_flags |= EC_RESET_FLAG_WATCHDOG;
- break;
- }
-
- /* Clear & set the reset flags for the following reset. */
- chip_save_reset_flags(chip_flags);
-
- /* Set the system reset flags. */
- system_set_reset_flags(system_flags);
-
- return 0;
-}
-
-static int system_preinitialize(const struct device *unused)
-{
- ARG_UNUSED(unused);
-
-#if DT_NODE_EXISTS(DT_NODELABEL(bbram))
- bbram_dev = DEVICE_DT_GET(DT_NODELABEL(bbram));
- if (!device_is_ready(bbram_dev)) {
- LOG_ERR("Error: device %s is not ready", bbram_dev->name);
- return -1;
- }
-#endif
-
- sys_dev = device_get_binding("CROS_SYSTEM");
- if (!sys_dev) {
- /*
- * TODO(b/183022804): This should not happen in normal
- * operation. Check whether the error check can be change to
- * build-time error, or at least a fatal run-time error.
- */
- LOG_ERR("sys_dev gets binding failed");
- return -1;
- }
-
- /* check the reset cause */
- if (check_reset_cause() != 0) {
- LOG_ERR("check the reset cause failed");
- return -1;
- }
-
- /*
- * For some boards on power-on, the EC is reset by the H1 after
- * power-on, so the EC sees 2 resets. This config enables the EC to save
- * a flag on the first power-up restart, and then wait for the second
- * reset before any other setup is done (such as GPIOs, timers, UART
- * etc.) On the second reset, the saved flag is used to detect the
- * previous power-on, and treat the second reset as a power-on instead
- * of a reset.
- */
-#ifdef CONFIG_BOARD_RESET_AFTER_POWER_ON
- if (system_get_reset_flags() & EC_RESET_FLAG_INITIAL_PWR) {
- /*
- * The current initial stage couldn't use the kernel delay
- * function. Use CPU nop instruction to wait for the external
- * reset from H1.
- */
- for (uint32_t i = WAIT_RESET_TIME; i; i--)
- arch_nop();
- }
-#endif
- return 0;
-}
-
-SYS_INIT(system_preinitialize, PRE_KERNEL_1,
- CONFIG_PLATFORM_EC_SYSTEM_PRE_INIT_PRIORITY);
diff --git a/zephyr/shim/src/tasks.c b/zephyr/shim/src/tasks.c
deleted file mode 100644
index 2f1fec16d6..0000000000
--- a/zephyr/shim/src/tasks.c
+++ /dev/null
@@ -1,353 +0,0 @@
-/* Copyright 2020 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.
- */
-
-#include <kernel.h>
-#include <init.h>
-#include <sys/atomic.h>
-#include <shell/shell.h>
-
-#include "common.h"
-#include "timer.h"
-#include "task.h"
-
-/* We need to ensure that is one lower priority for the deferred task */
-BUILD_ASSERT(CONFIG_NUM_PREEMPT_PRIORITIES + 1 >= TASK_ID_COUNT,
- "Must increase number of available preempt priorities");
-
-/* Declare all task stacks here */
-#define CROS_EC_TASK(name, e, p, size) \
- K_THREAD_STACK_DEFINE(name##_STACK, size);
-#define TASK_TEST(name, e, p, size) CROS_EC_TASK(name, e, p, size)
-CROS_EC_TASK_LIST
-#undef CROS_EC_TASK
-#undef TASK_TEST
-
-/* Forward declare all task entry point functions */
-#define CROS_EC_TASK(name, entry, ...) void entry(void *p);
-#define TASK_TEST(name, entry, ...) CROS_EC_TASK(name, entry)
-CROS_EC_TASK_LIST
-#undef CROS_EC_TASK
-#undef TASK_TEST
-
-/** Context for each CROS EC task that is run in its own zephyr thread */
-struct task_ctx {
-#ifdef CONFIG_THREAD_NAME
- /** Name of thread (for debugging) */
- const char *name;
-#endif
- /** Zephyr thread structure that hosts EC tasks */
- struct k_thread zephyr_thread;
- /** Zephyr thread id for above thread */
- k_tid_t zephyr_tid;
- /** Address of Zephyr thread's stack */
- k_thread_stack_t *stack;
- /** Usabled size in bytes of above thread stack */
- size_t stack_size;
- /** Task (platform/ec) entry point */
- void (*entry)(void *p);
- /** The parameter that is passed into the task entry point */
- intptr_t parameter;
- /** A wait-able event that is raised when a new task event is posted */
- struct k_poll_signal new_event;
- /** The current platform/ec events set for this task/thread */
- uint32_t event_mask;
- /**
- * The timer associated with this task, which can be set using
- * timer_arm().
- */
- struct k_timer timer;
-};
-
-#ifdef CONFIG_THREAD_NAME
-#define CROS_EC_TASK(_name, _entry, _parameter, _size) \
- { \
- .entry = _entry, \
- .parameter = _parameter, \
- .stack = _name##_STACK, \
- .stack_size = _size, \
- .name = #_name, \
- },
-#else
-#define CROS_EC_TASK(_name, _entry, _parameter, _size) \
- { \
- .entry = _entry, \
- .parameter = _parameter, \
- .stack = _name##_STACK, \
- .stack_size = _size, \
- },
-#endif /* CONFIG_THREAD_NAME */
-#define TASK_TEST(_name, _entry, _parameter, _size) \
- CROS_EC_TASK(_name, _entry, _parameter, _size)
-static struct task_ctx shimmed_tasks[] = {
- CROS_EC_TASK_LIST
-#ifdef TEST_BUILD
- [TASK_ID_TEST_RUNNER] = {},
-#endif
-};
-static int tasks_started;
-#undef CROS_EC_TASK
-#undef TASK_TEST
-
-task_id_t task_get_current(void)
-{
- for (size_t i = 0; i < ARRAY_SIZE(shimmed_tasks); ++i) {
- if (shimmed_tasks[i].zephyr_tid == k_current_get()) {
- return i;
- }
- }
-
-#if defined(HAS_TASK_HOOKS)
- /* Hooks ID should be returned for deferred calls */
- if (k_current_get() == &k_sys_work_q.thread) {
- return TASK_ID_HOOKS;
- }
-#endif /* HAS_TASK_HOOKS */
-
- __ASSERT(false, "Task index out of bound");
- return 0;
-}
-
-uint32_t *task_get_event_bitmap(task_id_t cros_task_id)
-{
- struct task_ctx *const ctx = &shimmed_tasks[cros_task_id];
-
- return &ctx->event_mask;
-}
-
-uint32_t task_set_event(task_id_t cros_task_id, uint32_t event)
-{
- struct task_ctx *const ctx = &shimmed_tasks[cros_task_id];
-
- atomic_or(&ctx->event_mask, event);
- k_poll_signal_raise(&ctx->new_event, 0);
-
- return 0;
-}
-
-uint32_t task_wait_event(int timeout_us)
-{
- struct task_ctx *const ctx = &shimmed_tasks[task_get_current()];
- const k_timeout_t timeout = (timeout_us == -1) ? K_FOREVER :
- K_USEC(timeout_us);
- const int64_t tick_deadline =
- k_uptime_ticks() + k_us_to_ticks_near64(timeout_us);
-
- struct k_poll_event poll_events[1] = {
- K_POLL_EVENT_INITIALIZER(K_POLL_TYPE_SIGNAL,
- K_POLL_MODE_NOTIFY_ONLY,
- &ctx->new_event),
- };
-
- /* Wait for signal, then clear it before reading events */
- const int rv = k_poll(poll_events, ARRAY_SIZE(poll_events), timeout);
-
- k_poll_signal_reset(&ctx->new_event);
- uint32_t events = atomic_set(&ctx->event_mask, 0);
-
- if (rv == -EAGAIN) {
- events |= TASK_EVENT_TIMER;
- }
-
- /* If we didn't get an event, we need to wait again. There is a very
- * small change of us reading the event_mask one signaled event too
- * early. In that case, just wait again for the remaining timeout
- */
- if (events == 0) {
- const int64_t ticks_left = tick_deadline - k_uptime_ticks();
-
- if (ticks_left > 0) {
- return task_wait_event(
- k_ticks_to_us_near64(ticks_left));
- }
-
- events |= TASK_EVENT_TIMER;
- }
-
- return events;
-}
-
-uint32_t task_wait_event_mask(uint32_t event_mask, int timeout_us)
-{
- struct task_ctx *const ctx = &shimmed_tasks[task_get_current()];
- uint32_t events = 0;
- const int64_t tick_deadline =
- k_uptime_ticks() + k_us_to_ticks_near64(timeout_us);
-
- /* Need to return timeout flags if it occurs as well */
- event_mask |= TASK_EVENT_TIMER;
-
- while (!(event_mask & events)) {
- const int64_t ticks_left = tick_deadline - k_uptime_ticks();
-
- if (timeout_us != -1 && ticks_left <= 0) {
- events |= TASK_EVENT_TIMER;
- break;
- }
-
- struct k_poll_event poll_events[1] = {
- K_POLL_EVENT_INITIALIZER(K_POLL_TYPE_SIGNAL,
- K_POLL_MODE_NOTIFY_ONLY,
- &ctx->new_event),
- };
-
- /* Ensure to honor the -1 timeout as FOREVER */
- k_poll(poll_events, ARRAY_SIZE(poll_events),
- timeout_us == -1 ? K_FOREVER : K_TICKS(ticks_left));
- k_poll_signal_reset(&ctx->new_event);
- events |= atomic_set(&ctx->event_mask, 0);
- }
-
- /* Replace any events that weren't in the mask */
- if (events & ~event_mask) {
- atomic_or(&ctx->event_mask, events & ~event_mask);
- k_poll_signal_raise(&ctx->new_event, 0);
- }
-
- return events & event_mask;
-}
-
-static void task_entry(void *task_contex, void *unused1, void *unused2)
-{
- ARG_UNUSED(unused1);
- ARG_UNUSED(unused2);
-
- struct task_ctx *const ctx = (struct task_ctx *)task_contex;
-
-#ifdef CONFIG_THREAD_NAME
- /* Name thread for debugging */
- k_thread_name_set(ctx->zephyr_tid, ctx->name);
-#endif
-
- /* Call into task entry point */
- ctx->entry((void *)ctx->parameter);
-}
-
-/*
- * Callback function to use with k_timer_start to set the
- * TASK_EVENT_TIMER event on a task.
- */
-static void timer_expire(struct k_timer *timer_id)
-{
- struct task_ctx *const ctx =
- CONTAINER_OF(timer_id, struct task_ctx, timer);
- task_id_t cros_ec_task_id = ctx - shimmed_tasks;
-
- task_set_event(cros_ec_task_id, TASK_EVENT_TIMER);
-}
-
-int timer_arm(timestamp_t event, task_id_t cros_ec_task_id)
-{
- timestamp_t now = get_time();
- struct task_ctx *const ctx = &shimmed_tasks[cros_ec_task_id];
-
- if (event.val <= now.val) {
- /* Timer requested for now or in the past, fire right away */
- task_set_event(cros_ec_task_id, TASK_EVENT_TIMER);
- return EC_SUCCESS;
- }
-
- /* Check for a running timer */
- if (k_timer_remaining_get(&ctx->timer))
- return EC_ERROR_BUSY;
-
- k_timer_start(&ctx->timer, K_USEC(event.val - now.val), K_NO_WAIT);
- return EC_SUCCESS;
-}
-
-void timer_cancel(task_id_t cros_ec_task_id)
-{
- struct task_ctx *const ctx = &shimmed_tasks[cros_ec_task_id];
-
- k_timer_stop(&ctx->timer);
-}
-
-#ifdef TEST_BUILD
-void set_test_runner_tid(void)
-{
- shimmed_tasks[TASK_ID_TEST_RUNNER].zephyr_tid = k_current_get();
-}
-#endif
-
-void start_ec_tasks(void)
-{
- for (size_t i = 0; i < ARRAY_SIZE(shimmed_tasks); ++i) {
- struct task_ctx *const ctx = &shimmed_tasks[i];
-
- k_timer_init(&ctx->timer, timer_expire, NULL);
-
-#ifdef TEST_BUILD
- /* Do not create thread for test runner; it will be set later */
- if (i == TASK_ID_TEST_RUNNER) {
- ctx->zephyr_tid = NULL;
- continue;
- }
-#endif
- /*
- * TODO(b/172361873): Add K_FP_REGS for FPU tasks. See
- * comment in config.h for CONFIG_TASK_LIST for existing flags
- * implementation.
- */
- ctx->zephyr_tid = k_thread_create(
- &ctx->zephyr_thread, ctx->stack, ctx->stack_size,
- task_entry, ctx, NULL, NULL,
- K_PRIO_PREEMPT(TASK_ID_COUNT - i - 1), 0, K_NO_WAIT);
- }
- tasks_started = 1;
-}
-
-/*
- * Initialize all of the kernel objects before application code starts.
- * This allows us to set events on tasks before they even start, e.g. in
- * INIT_HOOKS.
- */
-int init_signals(const struct device *unused)
-{
- ARG_UNUSED(unused);
-
- for (size_t i = 0; i < ARRAY_SIZE(shimmed_tasks); ++i) {
- struct task_ctx *const ctx = &shimmed_tasks[i];
-
- /* Initialize the new_event structure */
- k_poll_signal_init(&ctx->new_event);
- }
-
- return 0;
-}
-SYS_INIT(init_signals, POST_KERNEL, 50);
-
-int task_start_called(void)
-{
- return tasks_started;
-}
-
-void task_disable_task(task_id_t tskid)
-{
- /* TODO(b/190203712): Implement this */
-}
-
-void task_clear_pending_irq(int irq)
-{
-#if CONFIG_ITE_IT8XXX2_INTC
- ite_intc_isr_clear(irq);
-#endif
-}
-
-void task_enable_irq(int irq)
-{
- arch_irq_enable(irq);
-}
-
-inline int in_interrupt_context(void)
-{
- return k_is_in_isr();
-}
-
-#if IS_ENABLED(CONFIG_KERNEL_SHELL) && IS_ENABLED(CONFIG_THREAD_MONITOR)
-static int taskinfo(const struct shell *shell, size_t argc, char **argv)
-{
- return shell_execute_cmd(shell, "kernel threads");
-}
-SHELL_CMD_REGISTER(taskinfo, NULL, "Threads statistics", taskinfo);
-#endif
diff --git a/zephyr/shim/src/temp_sensors.c b/zephyr/shim/src/temp_sensors.c
deleted file mode 100644
index 4d8be4fa42..0000000000
--- a/zephyr/shim/src/temp_sensors.c
+++ /dev/null
@@ -1,52 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "temp_sensor.h"
-#include "temp_sensor/temp_sensor.h"
-#include "adc.h"
-#include "temp_sensor/thermistor.h"
-
-#if DT_NODE_EXISTS(DT_PATH(named_temp_sensors))
-static int thermistor_get_temp(const struct temp_sensor_t *sensor,
- int *temp_ptr)
-{
- return thermistor_get_temperature(sensor->idx, temp_ptr,
- sensor->thermistor);
-}
-
-#define GET_THERMISTOR_DATUM(node_sample_id) \
- [DT_PROP(node_sample_id, \
- sample_index)] = { .mv = DT_PROP(node_sample_id, milivolt), \
- .temp = DT_PROP(node_sample_id, temp) },
-
-#define DEFINE_THERMISTOR_DATA(node_id) \
- static const struct thermistor_data_pair DT_CAT( \
- node_id, _thermistor_data)[] = { \
- DT_FOREACH_CHILD(node_id, GET_THERMISTOR_DATUM) \
- };
-
-#define GET_THERMISTOR_INFO(node_id) \
- (&(struct thermistor_info){ \
- .scaling_factor = DT_PROP(node_id, scaling_factor), \
- .num_pairs = DT_PROP(node_id, num_pairs), \
- .data = DT_CAT(node_id, _thermistor_data), \
- })
-
-#define TEMP_THERMISTOR(node_id) \
- [ZSHIM_TEMP_SENSOR_ID(node_id)] = { \
- .name = DT_LABEL(node_id), \
- .read = &thermistor_get_temp, \
- .idx = ZSHIM_ADC_ID(DT_PHANDLE(node_id, adc)), \
- .type = TEMP_SENSOR_TYPE_BOARD, \
- .thermistor = \
- GET_THERMISTOR_INFO(DT_PHANDLE(node_id, thermistor)), \
- },
-
-DT_FOREACH_STATUS_OKAY(cros_ec_thermistor, DEFINE_THERMISTOR_DATA)
-
-const struct temp_sensor_t temp_sensors[] = {
- DT_FOREACH_STATUS_OKAY(cros_ec_temp_sensor, TEMP_THERMISTOR)
-};
-#endif /* named_temp_sensors */
diff --git a/zephyr/shim/src/test_util.c b/zephyr/shim/src/test_util.c
deleted file mode 100644
index 28be596043..0000000000
--- a/zephyr/shim/src/test_util.c
+++ /dev/null
@@ -1,20 +0,0 @@
-/* Copyright 2020 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.
- *
- * Test utilities.
- */
-
-#include "test_util.h"
-
-/* Linear congruential pseudo random number generator */
-uint32_t prng(uint32_t seed)
-{
- return 22695477 * seed + 1;
-}
-
-uint32_t prng_no_seed(void)
-{
- static uint32_t seed = 0x1234abcd;
- return seed = prng(seed);
-}
diff --git a/zephyr/shim/src/thermal.c b/zephyr/shim/src/thermal.c
deleted file mode 100644
index c31e2bfcc6..0000000000
--- a/zephyr/shim/src/thermal.c
+++ /dev/null
@@ -1,52 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "temp_sensor.h"
-#include "temp_sensor/temp_sensor.h"
-#include "ec_commands.h"
-
-#define THERMAL_CONFIG(node_id) \
- [ZSHIM_TEMP_SENSOR_ID(node_id)] = { \
- .temp_host = { \
- [EC_TEMP_THRESH_WARN] = \
- C_TO_K(DT_PROP_OR(node_id, \
- temp_host_warn, \
- -273)), \
- [EC_TEMP_THRESH_HIGH] = \
- C_TO_K(DT_PROP_OR(node_id, \
- temp_host_high, \
- -273)), \
- [EC_TEMP_THRESH_HALT] = \
- C_TO_K(DT_PROP_OR(node_id, \
- temp_host_halt, \
- -273)), \
- }, \
- .temp_host_release = { \
- [EC_TEMP_THRESH_WARN] = C_TO_K( \
- DT_PROP_OR(node_id, \
- temp_host_release_warn, \
- -273)), \
- [EC_TEMP_THRESH_HIGH] = C_TO_K( \
- DT_PROP_OR(node_id, \
- temp_host_release_high, \
- -273)), \
- [EC_TEMP_THRESH_HALT] = C_TO_K( \
- DT_PROP_OR(node_id, \
- temp_host_release_halt, \
- -273)), \
- }, \
- .temp_fan_off = C_TO_K(DT_PROP_OR(node_id, \
- temp_fan_off, \
- -273)), \
- .temp_fan_max = C_TO_K(DT_PROP_OR(node_id, \
- temp_fan_max, \
- -273)), \
- },
-
-struct ec_thermal_config thermal_params[] = {
-#if DT_NODE_EXISTS(DT_PATH(named_temp_sensors))
- DT_FOREACH_CHILD(DT_PATH(named_temp_sensors), THERMAL_CONFIG)
-#endif /* named_temp_sensors */
-};
diff --git a/zephyr/shim/src/watchdog.c b/zephyr/shim/src/watchdog.c
deleted file mode 100644
index 4c78ac9b0f..0000000000
--- a/zephyr/shim/src/watchdog.c
+++ /dev/null
@@ -1,78 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include <device.h>
-#include <drivers/watchdog.h>
-#include <logging/log.h>
-#include <zephyr.h>
-
-#include "config.h"
-#include "hooks.h"
-#include "watchdog.h"
-
-LOG_MODULE_REGISTER(watchdog_shim, LOG_LEVEL_ERR);
-
-static void wdt_warning_handler(const struct device *wdt_dev, int channel_id)
-{
- /* TODO(b/176523207): watchdog warning message */
- printk("Watchdog deadline is close!\n");
-}
-
-int watchdog_init(void)
-{
- int err;
- const struct device *wdt;
- struct wdt_timeout_cfg wdt_config;
-
- wdt = DEVICE_DT_GET(DT_NODELABEL(twd0));
- if (!device_is_ready(wdt)) {
- LOG_ERR("Error: device %s is not ready", wdt->name);
- return -1;
- }
-
- /* Reset SoC when watchdog timer expires. */
- wdt_config.flags = WDT_FLAG_RESET_SOC;
-
- /*
- * Set the Warning timer as CONFIG_AUX_TIMER_PERIOD_MS.
- * Then the watchdog reset time = CONFIG_WATCHDOG_PERIOD_MS.
- */
- wdt_config.window.min = 0U;
- wdt_config.window.max = CONFIG_AUX_TIMER_PERIOD_MS;
- wdt_config.callback = wdt_warning_handler;
-
- err = wdt_install_timeout(wdt, &wdt_config);
-
- /* If watchdog is running, reinstall it. */
- if (err == -EBUSY) {
- wdt_disable(wdt);
- err = wdt_install_timeout(wdt, &wdt_config);
- }
-
- if (err < 0) {
- LOG_ERR("Watchdog install error");
- return err;
- }
-
- err = wdt_setup(wdt, 0);
- if (err < 0) {
- LOG_ERR("Watchdog setup error");
- return err;
- }
-
- return EC_SUCCESS;
-}
-
-void watchdog_reload(void)
-{
- const struct device *wdt;
-
- wdt = DEVICE_DT_GET(DT_NODELABEL(twd0));
- if (!device_is_ready(wdt))
- LOG_ERR("Error: device %s is not ready", wdt->name);
-
- wdt_feed(wdt, 0);
-}
-DECLARE_HOOK(HOOK_TICK, watchdog_reload, HOOK_PRIO_DEFAULT);
diff --git a/zephyr/shim/src/ztest_system.c b/zephyr/shim/src/ztest_system.c
deleted file mode 100644
index 14796b5bd5..0000000000
--- a/zephyr/shim/src/ztest_system.c
+++ /dev/null
@@ -1,69 +0,0 @@
-/* Copyright 2021 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.
- */
-
-#include "system.h"
-#include "cros_version.h"
-
-/* Ongoing actions preventing going into deep-sleep mode. */
-uint32_t sleep_mask;
-
-void system_common_pre_init(void)
-{
-}
-
-int system_add_jump_tag(uint16_t tag, int version, int size, const void *data)
-{
- return EC_SUCCESS;
-}
-
-const uint8_t *system_get_jump_tag(uint16_t tag, int *version, int *size)
-{
- return NULL;
-}
-
-int system_jumped_late(void)
-{
- return 0;
-}
-
-enum ec_image system_get_image_copy(void)
-{
- return EC_IMAGE_RW;
-}
-
-int system_is_locked(void)
-{
- return 0;
-}
-
-int system_is_in_rw(void)
-{
- return 1;
-}
-
-uint32_t system_get_reset_flags(void)
-{
- return 0;
-}
-
-void system_print_banner(void)
-{
- printk("Image: %s\n", build_info);
-}
-
-void system_set_reset_flags(uint32_t flags)
-{
-}
-
-struct jump_data *get_jump_data(void)
-{
- return NULL;
-}
-
-__attribute__((weak))
-void system_reset(int flags)
-{
- __builtin_unreachable();
-}