summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorBhanu Prakash Maiya <bhanumaiya@google.com>2021-06-23 00:37:58 -0700
committerChromeos LUCI <chromeos-scoped@luci-project-accounts.iam.gserviceaccount.com>2022-09-03 00:01:43 +0000
commit51af2f83c9c77e1ea302cd16b7738d63c930a228 (patch)
treeb2fadefd5b5ca1ceb33f637638acf5fa25a6e0a2
parente32c8af4f94bb584c65b56d8ec48607e686bac13 (diff)
downloadchrome-ec-51af2f83c9c77e1ea302cd16b7738d63c930a228.tar.gz
driver: bmi3xx: Update support for BMI323 sensor in firmware branch
This is a squash of following CLs that updates BMI323 driver, individual cherry-picking was found to be not preferable at this state crrev/c/2984740 driver: bmi3xx: Add support for BMI323 sensor crrev/c/3027680 driver: bmi3xx: Remove latch settings from interrupt ctrl reg crrev/c/3033778 driver: bmi3xx: Return with error for unsupported MOTIONSENSE_TYPE crrev/c/3033779 driver: bmi3xx: Retain accel conf in register if new write fails crrev/c/3033969 driver: bmi3xx: Fix set data rate when odr is 0 crrev/c/3029015 driver: bmi3xx: Set FIFO watermark to 6 words crrev/c/3029016 driver: bmi3xx: Configure BMI323 config register once at Accel init crrev/c/3029014 driver: bmi3xx: Fix fifo buffer read and rotate data crrev/c/3036651 driver: bmi3xx: Fix perform calibration crrev/c/3150058 bmi3xx: Fix sensor_num in ec_response_motion_sensor_data crrev/c/3172267 Revert "driver: bmi3xx: Set FIFO watermark to 6 words" crrev/c/3170618 driver: bmi3xx: simplify irq handler crrev/c/3255475 driver: bmi3xx: Fix base accelerometer streaming issue crrev/c/3283203 driver: bmi3xx: Fix offset values read/write issue crrev/c/3609355 bmi3xx: Use CONFIG_<driver>_INT_ENABLE crrev/c/3729915 driver/accelgyro_bmi3xx.c: Format with clang-format crrev/c/3750539 bmi3xx: loop querying the written calibrated value BRANCH=trogdor BUG=b:243492849 TEST=emerge-trogdor chromeos-ec Signed-off-by: chaogui@google.com Change-Id: I65f26a863d019084c126011f05f22cebf8b1b779 Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/3868141 Reviewed-by: Tang Qijun <qijun.tang@ecs.corp-partner.google.com> Reviewed-by: Wai-Hong Tam <waihong@google.com> Reviewed-by: Bob Moragues <moragues@chromium.org>
-rw-r--r--common/build.mk1
-rw-r--r--driver/accelgyro_bmi323.h15
-rw-r--r--driver/accelgyro_bmi3xx.c1249
-rw-r--r--driver/accelgyro_bmi3xx.h282
-rw-r--r--driver/accelgyro_bmi_common.c5
-rw-r--r--driver/build.mk1
-rw-r--r--include/config.h2
-rw-r--r--include/ec_commands.h1
-rw-r--r--zephyr/shim/include/config_chip.h675
9 files changed, 2229 insertions, 2 deletions
diff --git a/common/build.mk b/common/build.mk
index 2ed1e8c3e0..901d0fcd01 100644
--- a/common/build.mk
+++ b/common/build.mk
@@ -14,6 +14,7 @@ common-y+=version.o printf.o queue.o queue_policies.o irq_locking.o
common-$(CONFIG_ACCELGYRO_BMI160)+=math_util.o
common-$(CONFIG_ACCELGYRO_BMI260)+=math_util.o
+common-$(CONFIG_ACCELGYRO_BMI3XX)+=math_util.o
common-$(CONFIG_ACCELGYRO_ICM426XX)+=math_util.o
common-$(CONFIG_ACCELGYRO_ICM42607)+=math_util.o
common-$(CONFIG_ACCELGYRO_LSM6DS0)+=math_util.o
diff --git a/driver/accelgyro_bmi323.h b/driver/accelgyro_bmi323.h
new file mode 100644
index 0000000000..a7f6864fdc
--- /dev/null
+++ b/driver/accelgyro_bmi323.h
@@ -0,0 +1,15 @@
+/* Copyright 2022 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.
+ */
+
+/* BMI323 gsensor module for Chrome EC */
+
+#ifndef __CROS_EC_ACCELGYRO_BMI323_H
+#define __CROS_EC_ACCELGYRO_BMI323_H
+
+#include "accelgyro_bmi3xx.h"
+
+#define BMI323_CHIP_ID 0x43
+
+#endif /* __CROS_EC_ACCELGYRO_BMI323_H */
diff --git a/driver/accelgyro_bmi3xx.c b/driver/accelgyro_bmi3xx.c
new file mode 100644
index 0000000000..e66c03d354
--- /dev/null
+++ b/driver/accelgyro_bmi3xx.c
@@ -0,0 +1,1249 @@
+/* Copyright 2022 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.
+ */
+
+/**
+ * BMI3XX accelerometer and gyroscope module for Chrome EC
+ * 3D digital accelerometer & 3D digital gyroscope
+ */
+
+#include "accelgyro.h"
+#include "accelgyro_bmi323.h"
+#include "accelgyro_bmi_common.h"
+#include "console.h"
+#include "hwtimer.h"
+#include "i2c.h"
+#include "init_rom.h"
+#include "math_util.h"
+#include "motion_sense_fifo.h"
+#include "spi.h"
+#include "task.h"
+#include "timer.h"
+#include "util.h"
+#include "watchdog.h"
+
+#ifdef CONFIG_ACCELGYRO_BMI3XX_INT_EVENT
+#define ACCELGYRO_BMI3XX_INT_ENABLE
+#endif
+
+#define CPUTS(outstr) cputs(CC_ACCEL, outstr)
+#define CPRINTF(format, args...) cprintf(CC_ACCEL, format, ##args)
+#define CPRINTS(format, args...) cprints(CC_ACCEL, format, ##args)
+
+#define OFFSET_UPDATE_PER_TRY 10
+
+/* Sensor definition */
+STATIC_IF(CONFIG_BMI_ORIENTATION_SENSOR)
+void irq_set_orientation(struct motion_sensor_t *s);
+
+STATIC_IF(ACCELGYRO_BMI3XX_INT_ENABLE)
+volatile uint32_t last_interrupt_timestamp;
+
+static inline int bmi3_read_n(const struct motion_sensor_t *s, const int reg,
+ uint8_t *data_ptr, const int len)
+{
+ return bmi_read_n(s->port, s->i2c_spi_addr_flags, reg, data_ptr, len);
+}
+
+static inline int bmi3_write_n(const struct motion_sensor_t *s, const int reg,
+ uint8_t *data_ptr, const int len)
+{
+ return bmi_write_n(s->port, s->i2c_spi_addr_flags, reg, data_ptr, len);
+}
+
+#ifdef ACCELGYRO_BMI3XX_INT_ENABLE
+
+#ifdef CONFIG_BMI_ORIENTATION_SENSOR
+
+static void irq_set_orientation(struct motion_sensor_t *s)
+{
+ int ret;
+ uint8_t reg_data[4];
+ uint8_t orient_data;
+
+ enum motionsensor_orientation orientation =
+ MOTIONSENSE_ORIENTATION_UNKNOWN;
+
+ RETURN_ERROR(bmi3_read_n(s, BMI3_FEATURE_EVENT_EXT, reg_data, 4));
+
+ orient_data = reg_data[2] & BMI3_PORTRAIT_LANDSCAPE_MASK;
+
+ if (BMI_GET_DATA(s)->raw_orientation != orient_data) {
+ BMI_GET_DATA(s)->raw_orientation = orient_data;
+
+ switch (orient_data) {
+ case BMI3_ORIENT_PORTRAIT:
+ orientation = MOTIONSENSE_ORIENTATION_PORTRAIT;
+ break;
+ case BMI3_PORTRAIT_INVERT:
+ orientation =
+ MOTIONSENSE_ORIENTATION_UPSIDE_DOWN_PORTRAIT;
+ break;
+ case BMI3_LANDSCAPE:
+ orientation = MOTIONSENSE_ORIENTATION_LANDSCAPE;
+ break;
+ case BMI3_LANDSCAPE_INVERT:
+ orientation =
+ MOTIONSENSE_ORIENTATION_UPSIDE_DOWN_LANDSCAPE;
+ break;
+ default:
+ break;
+ }
+
+ orientation = motion_orientation_remap(s, orientation);
+ *motion_orientation_ptr(s) = orientation;
+ }
+}
+
+#endif /* CONFIG_BMI_ORIENTATION_SENSOR */
+
+/*
+ * bmi3xx_interrupt - called when the sensor activates the interrupt line.
+ *
+ * This is a "top half" interrupt handler, it just asks motion sense ask
+ * to schedule the "bottom half", ->irq_handler().
+ */
+void bmi3xx_interrupt(enum gpio_signal signal)
+{
+ last_interrupt_timestamp = __hw_clock_source_read();
+
+ task_set_event(TASK_ID_MOTIONSENSE, CONFIG_ACCELGYRO_BMI3XX_INT_EVENT);
+}
+
+static int enable_fifo(const struct motion_sensor_t *s, int enable)
+{
+ struct bmi_drv_data_t *data = BMI_GET_DATA(s);
+ /* Set FIFO config to enable accel gyro data */
+ uint8_t reg_data[4];
+
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_FIFO_CONF, reg_data, 4));
+
+ if (enable) {
+ if (s->type == MOTIONSENSE_TYPE_ACCEL)
+ reg_data[3] |= BMI3_FIFO_ACC_EN;
+ else
+ reg_data[3] |= BMI3_FIFO_GYR_EN;
+
+ data->flags |= 1 << (s->type + BMI_FIFO_FLAG_OFFSET);
+ } else {
+ if (s->type == MOTIONSENSE_TYPE_ACCEL)
+ reg_data[3] &= ~BMI3_FIFO_ACC_EN;
+ else
+ reg_data[3] &= ~BMI3_FIFO_GYR_EN;
+
+ data->flags &= ~(1 << (s->type + BMI_FIFO_FLAG_OFFSET));
+ }
+
+ return bmi3_write_n(s, BMI3_REG_FIFO_CONF, &reg_data[2], 2);
+}
+
+static int config_interrupt(const struct motion_sensor_t *s)
+{
+ int ret;
+ uint8_t reg_data[6] = { 0 };
+
+ if (s->type != MOTIONSENSE_TYPE_ACCEL)
+ return EC_SUCCESS;
+
+ mutex_lock(s->mutex);
+
+ /* Clear the FIFO using Flush command */
+ reg_data[0] = BMI3_ENABLE;
+ reg_data[1] = 0;
+ ret = bmi3_write_n(s, BMI3_REG_FIFO_CTRL, reg_data, 2);
+ if (ret)
+ goto err_unlock;
+
+ /* Map FIFO water-mark and FIFO full to INT1 pin */
+ ret = bmi3_read_n(s, BMI3_REG_INT_MAP1, reg_data, 6);
+ if (ret)
+ goto err_unlock;
+
+ reg_data[5] = BMI3_SET_BITS(reg_data[5], BMI3_FWM_INT, BMI3_INT1);
+ reg_data[5] = BMI3_SET_BITS(reg_data[5], BMI3_FFULL_INT, BMI3_INT1);
+ if (IS_ENABLED(CONFIG_BMI_ORIENTATION_SENSOR)) {
+ /* Map orientation to INT1 pin */
+ reg_data[2] =
+ BMI3_SET_BITS(reg_data[2], BMI3_ORIENT_INT, BMI3_INT1);
+ }
+
+ ret = bmi3_write_n(s, BMI3_REG_INT_MAP1, &reg_data[2], 4);
+ if (ret)
+ goto err_unlock;
+
+ /* Set FIFO water-mark to read data whenever available */
+ reg_data[0] = BMI3_FIFO_ENTRY;
+ reg_data[1] = 0;
+
+ ret = bmi3_write_n(s, BMI3_REG_FIFO_WATERMARK, reg_data, 2);
+ if (ret)
+ goto err_unlock;
+
+ /* Get the previous configuration data */
+ ret = bmi3_read_n(s, BMI3_REG_IO_INT_CTRL, reg_data, 4);
+ if (ret)
+ goto err_unlock;
+
+ reg_data[2] = BMI3_SET_BIT_POS0(reg_data[2], BMI3_INT1_LVL,
+ BMI3_INT_ACTIVE_LOW);
+
+ reg_data[2] =
+ BMI3_SET_BITS(reg_data[2], BMI3_INT1_OD, BMI3_INT_PUSH_PULL);
+
+ reg_data[2] = BMI3_SET_BITS(reg_data[2], BMI3_INT1_OUTPUT_EN,
+ BMI3_INT_OUTPUT_ENABLE);
+
+ /*
+ * Set the interrupt pin configurations
+ */
+ ret = bmi3_write_n(s, BMI3_REG_IO_INT_CTRL, &reg_data[2], 2);
+ if (ret)
+ goto err_unlock;
+
+ if (IS_ENABLED(CONFIG_BMI_ORIENTATION_SENSOR)) {
+ /* Enable the orientation feature in BMI3 */
+ ret = bmi3_read_n(s, BMI3_FEATURE_IO_0, reg_data, 4);
+ if (ret)
+ goto err_unlock;
+
+ reg_data[2] |= BMI3_ANY_MOTION_X_EN_MASK;
+ ret = bmi3_write_n(s, BMI3_FEATURE_IO_0, &reg_data[2], 2);
+ if (ret)
+ goto err_unlock;
+
+ /* Write to feature engine */
+ reg_data[0] = 1;
+ reg_data[1] = 0;
+ ret = bmi3_write_n(s, BMI3_FEATURE_IO_STATUS, reg_data, 2);
+ }
+
+err_unlock:
+ mutex_unlock(s->mutex);
+ return ret;
+}
+
+static void bmi3_parse_fifo_data(struct motion_sensor_t *s,
+ struct bmi3_fifo_frame *fifo_frame,
+ uint32_t last_ts)
+{
+ struct bmi_drv_data_t *data = BMI_GET_DATA(s);
+ uint16_t reg_data;
+ intv3_t v;
+ int i;
+
+ /* Start index for FIFO parsing after I2C sync word removal */
+ size_t fifo_index = 1;
+
+ /* Variable to store I2C sync data which will get in FIFO data */
+ uint16_t i2c_sync_data, fifo_size;
+
+ if (!(data->flags & (BMI_FIFO_ALL_MASK << BMI_FIFO_FLAG_OFFSET))) {
+ /*
+ * The FIFO was disabled while we were processing it
+ * Flush potential left over:
+ * When sensor is resumed, we won't read old data.
+ */
+
+ /* Clear the FIFO using Flush command */
+ reg_data = BMI3_ENABLE;
+ bmi3_write_n(s, BMI3_REG_FIFO_CTRL, (uint8_t *)&reg_data, 2);
+ return;
+ }
+
+ /* Parse the length of data read excluding I2C sync word */
+ fifo_size = fifo_frame->available_fifo_len - 1;
+
+ while (fifo_size > 0) {
+ for (i = 0; i < NUM_OF_PRIMARY_SENSOR; i++) {
+ struct motion_sensor_t *sens_output = s + i;
+
+ if (data->flags & BIT(i + BMI_FIFO_FLAG_OFFSET)) {
+ /*
+ * In-case of FIFO read fail it has only
+ * 0x8000.
+ */
+ if (fifo_frame->data[fifo_index] == 0x8000)
+ break;
+
+ /*
+ * In case the frame has been cut, FIFO was
+ * greater than our buffer.
+ */
+ if (fifo_size < BMI3_FIFO_ENTRY)
+ break;
+
+ /* Frame is complete, but may have no data. */
+ fifo_size -= BMI3_FIFO_ENTRY;
+ i2c_sync_data = fifo_frame->data[fifo_index++];
+ if (i2c_sync_data ==
+ BMI3_FIFO_ACCEL_I2C_SYNC_FRAME + i) {
+ fifo_index += 2;
+ continue;
+ }
+
+ v[X] = i2c_sync_data;
+ v[Y] = fifo_frame->data[fifo_index++];
+ v[Z] = fifo_frame->data[fifo_index++];
+
+ rotate(v, *sens_output->rot_standard_ref, v);
+
+ if (IS_ENABLED(CONFIG_ACCEL_FIFO)) {
+ struct ec_response_motion_sensor_data
+ vect;
+
+ vect.data[X] = v[X];
+ vect.data[Y] = v[Y];
+ vect.data[Z] = v[Z];
+ vect.flags = 0;
+ vect.sensor_num =
+ sens_output - motion_sensors;
+ motion_sense_fifo_stage_data(
+ &vect, sens_output, 3, last_ts);
+ } else {
+ motion_sense_push_raw_xyz(sens_output);
+ }
+ }
+ }
+ }
+}
+
+/*
+ * irq_handler - bottom half of the interrupt stack.
+ * Ran from the motion_sense task, finds the events that raised the interrupt.
+ *
+ * For now, we just print out. We should set a bitmask motion sense code will
+ * act upon.
+ */
+static int irq_handler(struct motion_sensor_t *s, uint32_t *event)
+{
+ bool has_read_fifo = false;
+ uint16_t int_status[2];
+ uint16_t reg_data[2];
+ struct bmi3_fifo_frame fifo_frame;
+
+ if ((s->type != MOTIONSENSE_TYPE_ACCEL) ||
+ (!(*event & CONFIG_ACCELGYRO_BMI3XX_INT_EVENT)))
+ return EC_ERROR_NOT_HANDLED;
+
+ /* Get the interrupt status */
+ do {
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_INT_STATUS_INT1,
+ (uint8_t *)int_status, 4));
+
+ if (IS_ENABLED(CONFIG_BMI_ORIENTATION_SENSOR) &&
+ (BMI3_INT_STATUS_ORIENTATION & int_status[1]))
+ irq_set_orientation(s);
+
+ if ((int_status[1] &
+ (BMI3_INT_STATUS_FWM | BMI3_INT_STATUS_FFULL)) == 0)
+ break;
+
+ /* Get the FIFO fill level in words */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_FIFO_FILL_LVL,
+ (uint8_t *)reg_data, 4));
+
+ reg_data[1] =
+ BMI3_GET_BIT_POS0(reg_data[1], BMI3_FIFO_FILL_LVL);
+
+ /* Add space for the initial 16bit read. */
+ fifo_frame.available_fifo_len = reg_data[1] + 1;
+
+ /*
+ * If fill level is greater than buffer size then wrap it to
+ * buffer size.
+ */
+ if (fifo_frame.available_fifo_len > ARRAY_SIZE(fifo_frame.data))
+ CPRINTS("unexpected large FIFO: %d",
+ fifo_frame.available_fifo_len);
+
+ fifo_frame.available_fifo_len =
+ MIN(fifo_frame.available_fifo_len,
+ ARRAY_SIZE(fifo_frame.data));
+ /* Read FIFO data */
+ RETURN_ERROR(bmi3_read_n(
+ s, BMI3_REG_FIFO_DATA, (uint8_t *)fifo_frame.data,
+ fifo_frame.available_fifo_len * sizeof(uint16_t)));
+
+ bmi3_parse_fifo_data(s, &fifo_frame, last_interrupt_timestamp);
+ has_read_fifo = true;
+ } while (true);
+
+ if (IS_ENABLED(CONFIG_ACCEL_FIFO) && has_read_fifo)
+ motion_sense_fifo_commit_data();
+
+ return EC_SUCCESS;
+}
+#endif /* ACCELGYRO_BMI3XX_INT_ENABLE */
+
+static int read_temp(const struct motion_sensor_t *s, int *temp_ptr)
+{
+ return EC_ERROR_UNIMPLEMENTED;
+}
+
+static int poll_offset(const struct motion_sensor_t *s, uint8_t *reg_data)
+{
+ /* Delay time for offset update */
+ for (int i = 0; i < OFFSET_UPDATE_DELAY; i += OFFSET_UPDATE_PER_TRY) {
+ msleep(OFFSET_UPDATE_PER_TRY);
+
+ /* Read the configuration from the feature engine register */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_FEATURE_IO_1, reg_data, 4));
+
+ if ((reg_data[3] & BMI3_UGAIN_OFFS_UPD_COMPLETE) &&
+ ((reg_data[2] & BMI3_FEATURE_IO_1_ERROR_MASK) ==
+ BMI3_FEATURE_IO_1_NO_ERROR)) {
+ return EC_SUCCESS;
+ }
+ }
+ return EC_ERROR_NOT_CALIBRATED;
+}
+
+static int reset_offset(const struct motion_sensor_t *s, uint8_t offset_en)
+{
+ uint8_t offset_sel[2] = { BMI3_REG_UGAIN_OFF_SEL, 0 };
+ uint8_t reg_data[4] = { 0 };
+
+ /* Reset the existing offset values by setting the bits in DMA*/
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, offset_sel, 2));
+
+ reg_data[0] = offset_en;
+ reg_data[1] = 0;
+
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 2));
+
+ /* Update the offset change to the sensor engine */
+ reg_data[0] =
+ (uint8_t)(BMI3_CMD_USR_GAIN_OFFS_UPDATE & BMI3_SET_LOW_BYTE);
+ reg_data[1] = (uint8_t)((BMI3_CMD_USR_GAIN_OFFS_UPDATE &
+ BMI3_SET_HIGH_BYTE) >>
+ 8);
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_CMD, reg_data, 2));
+
+ return poll_offset(s, reg_data);
+}
+
+int get_gyro_offset(const struct motion_sensor_t *s, intv3_t v)
+{
+ int i;
+ uint8_t reg_data[14] = { 0 };
+
+ /* Get the accel offset values */
+ RETURN_ERROR(bmi3_read_n(s, GYR_DP_OFF_X, reg_data, 14));
+
+ v[0] = ((uint16_t)(reg_data[3] << 8) | reg_data[2]) & 0x03FF;
+ v[1] = ((uint16_t)(reg_data[7] << 8) | reg_data[6]) & 0x03FF;
+ v[2] = ((uint16_t)(reg_data[11] << 8) | reg_data[10]) & 0x03FF;
+
+ for (i = X; i <= Z; ++i) {
+ if (v[i] > 0x01FF)
+ v[i] = -1024 + v[i];
+
+ v[i] = round_divide((int64_t)v[i] * BMI_OFFSET_GYRO_MULTI_MDS,
+ BMI_OFFSET_GYRO_DIV_MDS);
+ }
+
+ return EC_SUCCESS;
+}
+
+static int write_gyro_offset(const struct motion_sensor_t *s, int *val)
+{
+ uint8_t reg_data[6] = { 0 };
+ uint8_t base_addr[2] = { BMI3_GYRO_OFFSET_ADDR, 0 };
+ uint8_t offset_sel[2] = { BMI3_REG_UGAIN_OFF_SEL, 0 };
+
+ /* Enable user gain/offset update*/
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, offset_sel, 2));
+ reg_data[0] = 0;
+ reg_data[1] = 0;
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 2));
+ /*
+ * Set the user gyro offset base address to feature engine
+ * transmission address to start DMA transaction
+ */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, base_addr, 2));
+
+ reg_data[0] = (uint8_t)(val[0] & BMI3_SET_LOW_BYTE);
+ reg_data[1] = (uint8_t)((val[0] & 0x0300) >> 8);
+ reg_data[2] = (uint8_t)(val[1] & BMI3_SET_LOW_BYTE);
+ reg_data[3] = (uint8_t)((val[1] & 0x0300) >> 8);
+ reg_data[4] = (uint8_t)(val[2] & BMI3_SET_LOW_BYTE);
+ reg_data[5] = (uint8_t)((val[2] & 0x0300) >> 8);
+
+ /* Set the configuration to the feature engine register */
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 6));
+
+ /* Update the offset to the sensor engine */
+ reg_data[0] =
+ (uint8_t)(BMI3_CMD_USR_GAIN_OFFS_UPDATE & BMI3_SET_LOW_BYTE);
+ reg_data[1] = (uint8_t)((BMI3_CMD_USR_GAIN_OFFS_UPDATE &
+ BMI3_SET_HIGH_BYTE) >>
+ 8);
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_CMD, reg_data, 2));
+
+ return poll_offset(s, reg_data);
+}
+
+int set_gyro_offset(const struct motion_sensor_t *s, intv3_t v)
+{
+ uint8_t reg_data[4] = { 0 };
+ uint8_t saved_conf[6] = { 0 };
+ int i, val[3];
+
+ for (i = X; i <= Z; ++i) {
+ val[i] = round_divide((int64_t)v[i] * BMI_OFFSET_GYRO_DIV_MDS,
+ BMI_OFFSET_GYRO_MULTI_MDS);
+ if (val[i] > 511)
+ val[i] = 511;
+ if (val[i] < -512)
+ val[i] = -512;
+ if (val[i] < 0)
+ val[i] = 1024 + val[i];
+ }
+
+ /* Set the power mode as suspend */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_ACC_CONF, saved_conf, 6));
+
+ /* Disable accelerometer and gyroscope */
+ reg_data[0] = saved_conf[2];
+ reg_data[1] = 0x00;
+ reg_data[2] = saved_conf[4];
+ reg_data[3] = 0x00;
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_ACC_CONF, reg_data, 4));
+
+ /* Reset the existing offset values */
+ RETURN_ERROR(reset_offset(s, 2));
+
+ /* Set the gyro offset in the sensor registers */
+ RETURN_ERROR(write_gyro_offset(s, val));
+
+ /* Restore ACC_CONF by storing saved_conf data */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_ACC_CONF, &saved_conf[2], 4));
+
+ return EC_SUCCESS;
+}
+
+int get_accel_offset(const struct motion_sensor_t *s, intv3_t v)
+{
+ int i;
+ uint8_t reg_data[14] = { 0 };
+
+ /* Get the accel offset values from user registers */
+ RETURN_ERROR(bmi3_read_n(s, ACC_DP_OFF_X, reg_data, 14));
+
+ v[0] = ((uint16_t)(reg_data[3] << 8) | reg_data[2]) & 0x1FFF;
+ v[1] = ((uint16_t)(reg_data[7] << 8) | reg_data[6]) & 0x1FFF;
+ v[2] = ((uint16_t)(reg_data[11] << 8) | reg_data[10]) & 0x1FFF;
+
+ for (i = X; i <= Z; ++i) {
+ if (v[i] > 0x0FFF)
+ v[i] = -8192 + v[i];
+
+ v[i] = round_divide((int64_t)v[i] * BMI3_OFFSET_ACC_MULTI_MG,
+ BMI_OFFSET_ACC_DIV_MG);
+ }
+
+ return EC_SUCCESS;
+}
+
+static int write_accel_offsets(const struct motion_sensor_t *s, int *val)
+{
+ uint8_t base_addr[2] = { BMI3_ACC_OFFSET_ADDR, 0 };
+ uint8_t offset_sel[2] = { BMI3_REG_UGAIN_OFF_SEL, 0 };
+ uint8_t reg_data[6] = { 0 };
+
+ /* Enable user gain/offset update*/
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, offset_sel, 2));
+ reg_data[0] = 0;
+ reg_data[1] = 0;
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 2));
+ /*
+ * Set the user accel offset base address to feature engine
+ * transmission address to start DMA transaction
+ */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, base_addr, 2));
+
+ reg_data[0] = (uint8_t)(val[0] & BMI3_SET_LOW_BYTE);
+ reg_data[1] = (uint8_t)((val[0] & 0x1F00) >> 8);
+ reg_data[2] = (uint8_t)(val[1] & BMI3_SET_LOW_BYTE);
+ reg_data[3] = (uint8_t)((val[1] & 0x1F00) >> 8);
+ reg_data[4] = (uint8_t)(val[2] & BMI3_SET_LOW_BYTE);
+ reg_data[5] = (uint8_t)((val[2] & 0x1F00) >> 8);
+
+ /* Set the configuration to the feature engine register */
+ RETURN_ERROR(
+ bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 6));
+
+ /* Update the offset to the sensor engine */
+ reg_data[0] =
+ (uint8_t)(BMI3_CMD_USR_GAIN_OFFS_UPDATE & BMI3_SET_LOW_BYTE);
+
+ reg_data[1] = (uint8_t)((BMI3_CMD_USR_GAIN_OFFS_UPDATE &
+ BMI3_SET_HIGH_BYTE) >>
+ 8);
+
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_CMD, reg_data, 2));
+
+ return poll_offset(s, reg_data);
+}
+
+int set_accel_offset(const struct motion_sensor_t *s, intv3_t v,
+ uint8_t reset_en)
+{
+ uint8_t reg_data[4] = { 0 };
+ uint8_t saved_conf[6] = { 0 };
+ int i, val[3];
+
+ for (i = X; i <= Z; ++i) {
+ val[i] = round_divide((int64_t)v[i] * BMI_OFFSET_ACC_DIV_MG,
+ BMI3_OFFSET_ACC_MULTI_MG);
+ if (val[i] > 4095)
+ val[i] = 4095;
+ if (val[i] < -4096)
+ val[i] = -4096;
+ if (val[i] < 0)
+ val[i] += 8192;
+ }
+
+ /* Set the power mode as suspend */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_ACC_CONF, saved_conf, 6));
+
+ /* Disable accelerometer and gyroscope */
+ reg_data[0] = saved_conf[2];
+ reg_data[1] = 0x00;
+ reg_data[2] = saved_conf[4];
+ reg_data[3] = 0x00;
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_ACC_CONF, reg_data, 4));
+
+ /* Reset the existing offset values */
+ if (reset_en) {
+ /* Reset is only done for writing offset and not for FOC */
+ RETURN_ERROR(reset_offset(s, 1));
+ }
+
+ /* Set the accel offset in the sensor registers */
+ RETURN_ERROR(write_accel_offsets(s, val));
+
+ /* Restore ACC_CONF by storing saved_conf data */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_ACC_CONF, &saved_conf[2], 4));
+
+ return EC_SUCCESS;
+}
+
+static int wait_and_read_data(const struct motion_sensor_t *s,
+ intv3_t accel_data)
+{
+ uint8_t reg_data[8] = { 0 };
+
+ /* Retry 5 times */
+ uint8_t try_cnt = FOC_TRY_COUNT;
+
+ /* Check if data is ready */
+ while (try_cnt && (!(reg_data[2] & BMI3_STAT_DATA_RDY_ACCEL_MSK))) {
+ /* 20ms delay for 50Hz ODR */
+ msleep(FOC_DELAY);
+
+ /* Read the status register */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_STATUS, reg_data, 4));
+ try_cnt--;
+ }
+
+ if (!(reg_data[2] & BMI3_STAT_DATA_RDY_ACCEL_MSK))
+ return EC_ERROR_TIMEOUT;
+
+ /* Read the sensor data */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_ACC_DATA_X, reg_data, 8));
+
+ accel_data[0] = ((int16_t)((reg_data[3] << 8) | reg_data[2]));
+ accel_data[1] = ((int16_t)((reg_data[5] << 8) | reg_data[4]));
+ accel_data[2] = ((int16_t)((reg_data[7] << 8) | reg_data[6]));
+
+ rotate(accel_data, *s->rot_standard_ref, accel_data);
+
+ return EC_SUCCESS;
+}
+
+/*!
+ * @brief This internal API performs Fast Offset Compensation for accelerometer.
+ */
+static int8_t perform_accel_foc(struct motion_sensor_t *s, int *target,
+ int sens_range)
+{
+ intv3_t accel_data, offset;
+ int32_t delta_value[3] = { 0, 0, 0 };
+
+ /* Variable to define count */
+ uint8_t i, loop, sample_count = 0;
+
+ for (loop = 0; loop < BMI3_FOC_SAMPLE_LIMIT; loop++) {
+ RETURN_ERROR(wait_and_read_data(s, accel_data));
+
+ sample_count++;
+
+ /* Store the data in a temporary structure */
+ delta_value[0] += accel_data[0] - target[X];
+ delta_value[1] += accel_data[1] - target[Y];
+ delta_value[2] += accel_data[2] - target[Z];
+ }
+
+ /* The data is in LSB so -> [(LSB)*1000*range/2^15] (mdps | mg) */
+ for (i = X; i <= Z; ++i) {
+ offset[i] = (((int64_t)(delta_value[i] * 1000 * sens_range /
+ sample_count) >>
+ 15) *
+ -1);
+ }
+
+ rotate_inv(offset, *s->rot_standard_ref, offset);
+
+ /* Set accel offset without resetting the existing offsets
+ * since we calculated the bias with the existing offsets
+ */
+ RETURN_ERROR(set_accel_offset(s, offset, BMI3_DISABLE));
+
+ return EC_SUCCESS;
+}
+
+static int set_gyro_foc_config(struct motion_sensor_t *s)
+{
+ uint8_t reg_data[4] = { 0 };
+ uint8_t base_addr[2] = { BMI3_BASE_ADDR_SC, 0 };
+
+ /*
+ * Set the FOC base address to feature engine
+ * transmission address to start DMA transaction
+ */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, base_addr, 2));
+
+ /* Read the configuration from the feature engine register */
+ RETURN_ERROR(
+ bmi3_read_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA, reg_data, 4));
+ /* Enable self calibration */
+ reg_data[2] |= 0x07;
+
+ RETURN_ERROR(bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX, base_addr, 2));
+
+ /* Set the configuration to the feature engine register */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_FEATURE_ENGINE_DMA_TX_DATA,
+ &reg_data[2], 2));
+
+ /* Trigger bmi3 gyro self calibration */
+ reg_data[0] = (uint8_t)(BMI3_CMD_SELF_CALIB & BMI3_SET_LOW_BYTE);
+ reg_data[1] =
+ (uint8_t)((BMI3_CMD_SELF_CALIB & BMI3_SET_HIGH_BYTE) >> 8);
+
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_CMD, reg_data, 2));
+
+ return EC_SUCCESS;
+}
+
+static int get_calib_result(struct motion_sensor_t *s)
+{
+ uint8_t i, reg_data[4];
+
+ for (i = 0; i < 25; i++) {
+ /* A delay of 120ms is required to read this status register */
+ msleep(OFFSET_UPDATE_DELAY);
+
+ /* Read the configuration from the feature engine register */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_FEATURE_IO_1, reg_data, 4));
+
+ switch (s->type) {
+ case MOTIONSENSE_TYPE_ACCEL:
+ if ((reg_data[3] & BMI3_UGAIN_OFFS_UPD_COMPLETE) &&
+ ((reg_data[2] & BMI3_FEATURE_IO_1_ERROR_MASK) ==
+ BMI3_FEATURE_IO_1_NO_ERROR)) {
+ return EC_SUCCESS;
+ }
+ break;
+ case MOTIONSENSE_TYPE_GYRO:
+ if (reg_data[2] & BMI3_SC_ST_STATUS_MASK) {
+ /* Check calibration result */
+ if (reg_data[2] & BMI3_SC_RESULT_MASK)
+ return EC_SUCCESS;
+ }
+ break;
+ default:
+ return EC_ERROR_UNIMPLEMENTED;
+ }
+ }
+
+ return EC_ERROR_NOT_CALIBRATED;
+}
+
+static int perform_calib(struct motion_sensor_t *s, int enable)
+{
+ int ret;
+ intv3_t target = { 0, 0, 0 };
+ uint8_t saved_conf[6] = { 0 };
+
+ /* Sensor is configured to be in 16G range */
+ int sens_range = 16;
+
+ /* Variable to set the accelerometer configuration value 50Hz for FOC */
+ uint8_t acc_conf_data[2] = { BMI3_FOC_ACC_CONF_VAL_LSB,
+ BMI3_FOC_ACC_CONF_VAL_MSB };
+
+ if (!enable)
+ return EC_SUCCESS;
+
+ /* Get default configurations for the type of feature selected. */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_ACC_CONF, saved_conf, 6));
+
+ ret = bmi3_write_n(s, BMI3_REG_ACC_CONF, acc_conf_data, 2);
+ if (ret)
+ goto end_calib;
+
+ msleep(FOC_DELAY);
+
+ switch (s->type) {
+ case MOTIONSENSE_TYPE_ACCEL:
+ target[Z] = BMI3_ACC_DATA_PLUS_1G(sens_range);
+
+ /* Perform accel calibration */
+ ret = perform_accel_foc(s, target, sens_range);
+ if (ret)
+ goto end_calib;
+
+ /* Get caliration results */
+ ret = get_calib_result(s);
+ if (ret)
+ goto end_calib;
+
+ break;
+ case MOTIONSENSE_TYPE_GYRO:
+ ret = set_gyro_foc_config(s);
+ if (ret)
+ goto end_calib;
+
+ ret = get_calib_result(s);
+ if (ret)
+ goto end_calib;
+
+ break;
+ default:
+ /* Not supported on Magnetometer */
+ ret = EC_RES_INVALID_PARAM;
+ goto end_calib;
+ }
+
+end_calib:
+ /* Restore ACC_CONF before exiting */
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_ACC_CONF, &saved_conf[2], 4));
+
+ return ret;
+}
+
+static int get_offset(const struct motion_sensor_t *s, int16_t *offset,
+ int16_t *temp)
+{
+ int i;
+ intv3_t v;
+
+ switch (s->type) {
+ case MOTIONSENSE_TYPE_ACCEL:
+ /*
+ * The offset of the accelerometer is a 8 bit
+ * two-complement number in units of 3.9 mg independent of the
+ * range selected for the accelerometer.
+ */
+ RETURN_ERROR(get_accel_offset(s, v));
+ break;
+ case MOTIONSENSE_TYPE_GYRO:
+ /* Gyro offset is in milli-dps */
+ RETURN_ERROR(get_gyro_offset(s, v));
+ break;
+ default:
+ for (i = X; i <= Z; i++)
+ v[i] = 0;
+ }
+
+ rotate(v, *s->rot_standard_ref, v);
+ offset[X] = v[X];
+ offset[Y] = v[Y];
+ offset[Z] = v[Z];
+ /* Saving temperature at calibration not supported yet */
+ *temp = (int16_t)EC_MOTION_SENSE_INVALID_CALIB_TEMP;
+
+ return EC_SUCCESS;
+}
+
+static int set_offset(const struct motion_sensor_t *s, const int16_t *offset,
+ int16_t temp)
+{
+ intv3_t v = { offset[X], offset[Y], offset[Z] };
+ (void)temp;
+
+ rotate_inv(v, *s->rot_standard_ref, v);
+
+ switch (s->type) {
+ case MOTIONSENSE_TYPE_ACCEL:
+ /* Offset should be in units of mg */
+ RETURN_ERROR(set_accel_offset(s, v, BMI3_ENABLE));
+ break;
+ case MOTIONSENSE_TYPE_GYRO:
+ /* Offset should be in units of mdps */
+ RETURN_ERROR(set_gyro_offset(s, v));
+ break;
+ default:
+ return EC_RES_INVALID_PARAM;
+ }
+
+ return EC_SUCCESS;
+}
+
+#ifdef CONFIG_BODY_DETECTION
+int get_rms_noise(const struct motion_sensor_t *s)
+{
+ return EC_ERROR_UNIMPLEMENTED;
+}
+#endif
+
+static int set_scale(const struct motion_sensor_t *s, const uint16_t *scale,
+ int16_t temp)
+{
+ struct accelgyro_saved_data_t *saved_data = BMI_GET_SAVED_DATA(s);
+
+ saved_data->scale[X] = scale[X];
+ saved_data->scale[Y] = scale[Y];
+ saved_data->scale[Z] = scale[Z];
+
+ return EC_SUCCESS;
+}
+
+static int get_scale(const struct motion_sensor_t *s, uint16_t *scale,
+ int16_t *temp)
+{
+ struct accelgyro_saved_data_t *saved_data = BMI_GET_SAVED_DATA(s);
+
+ scale[X] = saved_data->scale[X];
+ scale[Y] = saved_data->scale[Y];
+ scale[Z] = saved_data->scale[Z];
+
+ *temp = (int16_t)EC_MOTION_SENSE_INVALID_CALIB_TEMP;
+
+ return EC_SUCCESS;
+}
+
+static int get_data_rate(const struct motion_sensor_t *s)
+{
+ struct accelgyro_saved_data_t *saved_data = BMI_GET_SAVED_DATA(s);
+
+ return saved_data->odr;
+}
+
+static int set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
+{
+ int ret;
+ int normalized_rate = 0;
+ uint8_t reg_data[4];
+ uint8_t reg_val = 0;
+
+ struct accelgyro_saved_data_t *saved_data = BMI_GET_SAVED_DATA(s);
+
+ if (rate > 0)
+ RETURN_ERROR(bmi_get_normalized_rate(
+ s, rate, rnd, &normalized_rate, &reg_val));
+
+ /*
+ * Lock accel resource to prevent another task from attempting
+ * to write accel parameters until we are done.
+ */
+ mutex_lock(s->mutex);
+
+ /*
+ * Get default configurations for the type of feature selected.
+ */
+ ret = bmi3_read_n(s, BMI3_REG_ACC_CONF + s->type, reg_data, 4);
+ if (ret) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+
+ if (s->type == MOTIONSENSE_TYPE_ACCEL) {
+ if (rate == 0) {
+ /* FIFO stop collecting events */
+ if (IS_ENABLED(ACCELGYRO_BMI3XX_INT_ENABLE))
+ ret = enable_fifo(s, 0);
+
+ /*
+ * Disable accel to set rate equal to zero.
+ * Accel does not have suspend mode.
+ */
+ reg_data[3] = BMI3_SET_BITS(reg_data[3],
+ BMI3_POWER_MODE,
+ BMI3_ACC_MODE_DISABLE);
+
+ saved_data->odr = 0;
+ } else if (saved_data->odr == 0) {
+ /*
+ * Power mode changed from suspend to
+ * normal
+ */
+ reg_data[3] = BMI3_SET_BITS(reg_data[3],
+ BMI3_POWER_MODE,
+ BMI3_ACC_MODE_NORMAL);
+ }
+ } else if (s->type == MOTIONSENSE_TYPE_GYRO) {
+ if (rate == 0) {
+ /* FIFO stop collecting events */
+ if (IS_ENABLED(ACCELGYRO_BMI3XX_INT_ENABLE))
+ ret = enable_fifo(s, 0);
+
+ /*
+ * Set gyro to suspend mode to disable gyro
+ * however keep internal driver enabled
+ */
+ reg_data[3] = BMI3_SET_BITS(reg_data[3],
+ BMI3_POWER_MODE,
+ BMI3_GYR_MODE_SUSPEND);
+
+ saved_data->odr = 0;
+ } else if (saved_data->odr == 0) {
+ /* Power mode changed from suspend to
+ * normal
+ */
+ reg_data[3] = BMI3_SET_BITS(reg_data[3],
+ BMI3_POWER_MODE,
+ BMI3_GYR_MODE_NORMAL);
+ }
+ }
+
+ /* Set accelerometer ODR */
+ reg_data[2] = BMI3_SET_BIT_POS0(reg_data[2], BMI3_SENS_ODR, reg_val);
+
+ /* Set the accel/gyro configurations. */
+ ret = bmi3_write_n(s, BMI3_REG_ACC_CONF + s->type, &reg_data[2], 2);
+ if (ret) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+
+ saved_data->odr = normalized_rate;
+
+ /*
+ * If rate is non zero, FIFO start collecting events.
+ * They will be discarded if AP does not want them.
+ */
+ if (IS_ENABLED(ACCELGYRO_BMI3XX_INT_ENABLE) && (rate > 0))
+ ret = enable_fifo(s, 1);
+
+ mutex_unlock(s->mutex);
+ return ret;
+}
+
+static int get_resolution(const struct motion_sensor_t *s)
+{
+ return BMI3_16_BIT_RESOLUTION;
+}
+
+static int set_range(struct motion_sensor_t *s, int range, int rnd)
+{
+ int ret;
+ uint8_t index, sens_size = 0;
+ uint8_t reg_data[4] = { 0 };
+ int(*sensor_range)[2];
+
+ int acc_sensor_range[4][2] = {
+ { 2, BMI3_ACC_RANGE_2G },
+ { 4, BMI3_ACC_RANGE_4G },
+ { 8, BMI3_ACC_RANGE_8G },
+ { 16, BMI3_ACC_RANGE_16G },
+ };
+
+ int gyr_sensor_range[5][2] = {
+ { 125, BMI3_GYR_RANGE_125DPS },
+ { 250, BMI3_GYR_RANGE_250DPS },
+ { 500, BMI3_GYR_RANGE_500DPS },
+ { 1000, BMI3_GYR_RANGE_1000DPS },
+ { 2000, BMI3_GYR_RANGE_2000DPS },
+ };
+
+ if (s->type == MOTIONSENSE_TYPE_ACCEL) {
+ sens_size = ARRAY_SIZE(acc_sensor_range);
+ sensor_range = acc_sensor_range;
+ } else {
+ sens_size = ARRAY_SIZE(gyr_sensor_range);
+ sensor_range = gyr_sensor_range;
+ }
+
+ for (index = 0; index < sens_size - 1; index++) {
+ if (range <= sensor_range[index][0])
+ break;
+
+ if (range < sensor_range[index + 1][0] && rnd) {
+ index++;
+ break;
+ }
+ }
+
+ mutex_lock(s->mutex);
+
+ /*
+ * Read the range register from sensor for accelerometer/gyroscope
+ * s->type should have MOTIONSENSE_TYPE_ACCEL = 0 ;
+ * MOTIONSENSE_TYPE_GYRO = 1
+ */
+ ret = bmi3_read_n(s, BMI3_REG_ACC_CONF + s->type, reg_data, 4);
+
+ if (ret == EC_SUCCESS) {
+ /* Set accelerometer/Gyroscope range */
+ /* Gravity range of the sensor (+/- 2G, 4G, 8G, 16G). */
+ reg_data[2] = BMI3_SET_BITS(reg_data[2], BMI3_SENS_RANGE,
+ sensor_range[index][1]);
+
+ /* Set the accel/gyro configurations. */
+ ret = bmi3_write_n(s, BMI3_REG_ACC_CONF + s->type, &reg_data[2],
+ 2);
+
+ /* Now that we have set the range, update the driver's value. */
+ if (ret == EC_SUCCESS)
+ s->current_range = sensor_range[index][0];
+ }
+
+ mutex_unlock(s->mutex);
+
+ return ret;
+}
+
+static int read(const struct motion_sensor_t *s, intv3_t v)
+{
+ int ret;
+ uint8_t reg_data[8] = { 0 };
+ uint16_t status_val = 0;
+
+ mutex_lock(s->mutex);
+
+ /* Read the status register */
+ ret = bmi3_read_n(s, BMI3_REG_STATUS, reg_data, 4);
+
+ if (ret == EC_SUCCESS) {
+ status_val = (reg_data[2] | ((uint16_t)reg_data[3] << 8));
+ /*
+ * If sensor data is not ready, return the previous read data.
+ * Note: return success so that motion sensor task can read
+ * again to get the latest updated sensor data quickly.
+ */
+ if (!(status_val & BMI3_DRDY_MASK(s->type))) {
+ if (v != s->raw_xyz)
+ memcpy(v, s->raw_xyz, sizeof(s->raw_xyz));
+
+ mutex_unlock(s->mutex);
+
+ return EC_SUCCESS;
+ }
+
+ if (s->type == MOTIONSENSE_TYPE_ACCEL) {
+ /* Read the sensor data */
+ ret = bmi3_read_n(s, BMI3_REG_ACC_DATA_X, reg_data, 8);
+ } else if (s->type == MOTIONSENSE_TYPE_GYRO) {
+ /* Read the sensor data */
+ ret = bmi3_read_n(s, BMI3_REG_GYR_DATA_X, reg_data, 8);
+ }
+
+ if (ret == EC_SUCCESS) {
+ v[0] = ((int16_t)((reg_data[3] << 8) | reg_data[2]));
+ v[1] = ((int16_t)((reg_data[5] << 8) | reg_data[4]));
+ v[2] = ((int16_t)((reg_data[7] << 8) | reg_data[6]));
+
+ rotate(v, *s->rot_standard_ref, v);
+ }
+ }
+
+ mutex_unlock(s->mutex);
+
+ return ret;
+}
+
+static int init(struct motion_sensor_t *s)
+{
+ /* Status of communication result */
+ uint8_t i;
+ uint8_t reg_data[4] = { 0 };
+
+ /* Store the sensor configurations */
+ struct accelgyro_saved_data_t *saved_data = BMI_GET_SAVED_DATA(s);
+ struct bmi_drv_data_t *data = BMI_GET_DATA(s);
+
+ /* This driver requires a mutex */
+ ASSERT(s->mutex);
+
+ /*
+ * BMI3xx driver only supports MOTIONSENSE_TYPE_ACCEL and
+ * MOTIONSENSE_TYPE_GYR0
+ */
+ if (s->type != MOTIONSENSE_TYPE_ACCEL &&
+ s->type != MOTIONSENSE_TYPE_GYRO)
+ return EC_ERROR_UNIMPLEMENTED;
+
+ /* Read chip id */
+ RETURN_ERROR(bmi3_read_n(s, BMI3_REG_CHIP_ID, reg_data, 4));
+
+ if (reg_data[2] != BMI323_CHIP_ID)
+ return EC_ERROR_HW_INTERNAL;
+
+ if (s->type == MOTIONSENSE_TYPE_ACCEL) {
+ /* Reset bmi3 device */
+ reg_data[0] =
+ (uint8_t)(BMI3_CMD_SOFT_RESET & BMI3_SET_LOW_BYTE);
+ reg_data[1] =
+ (uint8_t)((BMI3_CMD_SOFT_RESET & BMI3_SET_HIGH_BYTE) >>
+ 8);
+
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_CMD, reg_data, 2));
+
+ /* Delay of 2ms after soft reset*/
+ msleep(2);
+
+ /* Enable feature engine bit */
+ reg_data[0] = BMI3_ENABLE;
+ reg_data[1] = 0;
+
+ RETURN_ERROR(bmi3_write_n(s, BMI3_REG_FEATURE_ENGINE_GLOB_CTRL,
+ reg_data, 2));
+
+ if (IS_ENABLED(ACCELGYRO_BMI3XX_INT_ENABLE))
+ RETURN_ERROR(config_interrupt(s));
+ }
+
+ for (i = X; i <= Z; i++)
+ saved_data->scale[i] = MOTION_SENSE_DEFAULT_SCALE;
+
+ /* The sensor is in Suspend mode at init, so set data rate to 0*/
+ saved_data->odr = 0;
+
+ /* Flags used in FIFO parsing */
+ data->flags &= ~(BMI_FLAG_SEC_I2C_ENABLED |
+ (BMI_FIFO_ALL_MASK << BMI_FIFO_FLAG_OFFSET));
+
+ return sensor_init_done(s);
+}
+
+/* Accelerometer/Gyroscope base driver structure */
+const struct accelgyro_drv bmi3xx_drv = {
+ .init = init,
+ .read = read,
+ .set_range = set_range,
+ .get_resolution = get_resolution,
+ .set_data_rate = set_data_rate,
+ .get_data_rate = get_data_rate,
+ .get_scale = get_scale,
+ .set_scale = set_scale,
+ .set_offset = set_offset,
+ .get_offset = get_offset,
+ .perform_calib = perform_calib,
+ .read_temp = read_temp,
+#ifdef ACCELGYRO_BMI3XX_INT_ENABLE
+ .irq_handler = irq_handler,
+#endif
+#ifdef CONFIG_BODY_DETECTION
+ .get_rms_noise = get_rms_noise,
+#endif
+};
diff --git a/driver/accelgyro_bmi3xx.h b/driver/accelgyro_bmi3xx.h
new file mode 100644
index 0000000000..3f27eecfe1
--- /dev/null
+++ b/driver/accelgyro_bmi3xx.h
@@ -0,0 +1,282 @@
+/* Copyright 2022 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.
+ */
+
+/* BMI3XX gsensor module for Chrome EC */
+
+#ifndef __CROS_EC_ACCELGYRO_BMI3XX_H
+#define __CROS_EC_ACCELGYRO_BMI3XX_H
+
+/* Sensor Specific macros */
+#define BMI3_ADDR_I2C_PRIM 0x68
+#define BMI3_ADDR_I2C_SEC 0x69
+#define BMI3_16_BIT_RESOLUTION 16
+
+/* Chip-specific registers */
+#define BMI3_REG_CHIP_ID 0x00
+
+#define BMI3_REG_STATUS 0x02
+#define BMI3_STAT_DATA_RDY_ACCEL_POS 7
+#define BMI3_STAT_DATA_RDY_ACCEL_MSK 0x80
+
+#define BMI3_REG_ACC_DATA_X 0x03
+#define BMI3_ACC_RANGE_2G 0x00
+#define BMI3_ACC_RANGE_4G 0x01
+#define BMI3_ACC_RANGE_8G 0x02
+#define BMI3_ACC_RANGE_16G 0x03
+#define BMI3_ACC_MODE_DISABLE 0x00
+#define BMI3_ACC_MODE_LOW_PWR 0x03
+#define BMI3_ACC_MODE_NORMAL 0X04
+#define BMI3_ACC_MODE_HIGH_PERF 0x07
+
+#define BMI3_REG_GYR_DATA_X 0x06
+#define BMI3_GYR_RANGE_125DPS 0x00
+#define BMI3_GYR_RANGE_250DPS 0x01
+#define BMI3_GYR_RANGE_500DPS 0x02
+#define BMI3_GYR_RANGE_1000DPS 0x03
+#define BMI3_GYR_RANGE_2000DPS 0x04
+#define BMI3_GYR_MODE_DISABLE 0x00
+#define BMI3_GYR_MODE_SUSPEND 0X01
+#define BMI3_GYR_MODE_ULTRA_LOW_PWR 0X02
+#define BMI3_GYR_MODE_LOW_PWR 0x03
+#define BMI3_GYR_MODE_NORMAL 0X04
+#define BMI3_GYR_MODE_HIGH_PERF 0x07
+
+#define BMI3_REG_INT_STATUS_INT1 0x0D
+#define BMI3_REG_FIFO_FILL_LVL 0x15
+#define BMI3_REG_FIFO_DATA 0x16
+#define BMI3_REG_ACC_CONF 0x20
+#define BMI3_REG_GYR_CONF 0x21
+#define BMI3_REG_INT_MAP1 0x3A
+#define BMI3_REG_FIFO_WATERMARK 0x35
+#define BMI3_REG_UGAIN_OFF_SEL 0x3F
+#define BMI3_REG_FIFO_CONF 0x36
+#define BMI3_FIFO_STOP_ON_FULL 0x01
+#define BMI3_FIFO_TIME_EN 0x01
+#define BMI3_FIFO_ACC_EN 0x02
+#define BMI3_FIFO_GYR_EN 0x04
+#define BMI3_FIFO_TEMP_EN 0x08
+#define BMI3_FIFO_ALL_EN 0x0F
+
+#define BMI3_REG_FIFO_CTRL 0x37
+#define BMI3_REG_IO_INT_CTRL 0x38
+#define BMI3_INT1_LVL_MASK 0x01
+#define BMI3_INT1_OD_MASK 0x02
+#define BMI3_INT1_OD_POS 1
+#define BMI3_INT1_OUTPUT_EN_MASK 0x04
+#define BMI3_INT1_OUTPUT_EN_POS 2
+#define BMI3_INT_PUSH_PULL 0
+#define BMI3_INT_OPEN_DRAIN 1
+#define BMI3_INT_ACTIVE_LOW 0
+#define BMI3_INT_ACTIVE_HIGH 1
+
+#define BMI3_REG_IO_INT_CONF 0x39
+#define BMI3_INT_LATCH_EN 1
+#define BMI3_INT_LATCH_DISABLE 0
+
+#define BMI3_REG_FEATURE_ENGINE_GLOB_CTRL 0x40
+
+#define BMI3_FEATURE_EVENT_EXT 0x47
+#define BMI3_PORTRAIT_LANDSCAPE_MASK 0x03
+#define BMI3_PORTRAIT 0
+#define BMI3_LANDSCAPE 1
+#define BMI3_PORTRAIT_INVERT 2
+#define BMI3_LANDSCAPE_INVERT 3
+
+#define ACC_DP_OFF_X 0x60
+#define GYR_DP_OFF_X 0x66
+
+#define BMI3_REG_CMD 0x7E
+#define BMI3_CMD_SOFT_RESET 0xDEAF
+
+/* BMI3 Interrupt Output Enable */
+#define BMI3_INT_OUTPUT_DISABLE 0
+#define BMI3_INT_OUTPUT_ENABLE 1
+
+/* FIFO sensor data length (in word), Accel or Gyro */
+#define BMI3_FIFO_ENTRY 0x3
+/* Macro to define accelerometer configuration value for FOC */
+#define BMI3_FOC_ACC_CONF_VAL_LSB 0xB7
+#define BMI3_FOC_ACC_CONF_VAL_MSB 0x40
+/* Macro to define the accel FOC range */
+#define BMI3_ACC_FOC_2G_REF 16384
+#define BMI3_ACC_FOC_4G_REF 8192
+#define BMI3_ACC_FOC_8G_REF 4096
+#define BMI3_ACC_FOC_16G_REF 2048
+#define BMI3_FOC_SAMPLE_LIMIT 128
+
+#define FOC_TRY_COUNT 5
+/* 20ms delay for 50Hz ODR */
+#define FOC_DELAY 20
+#define OFFSET_UPDATE_DELAY 120
+#define BMI3_INT_STATUS_FWM 0x4000
+#define BMI3_INT_STATUS_FFULL 0x8000
+#define BMI3_INT_STATUS_ORIENTATION 0x0008
+
+
+#define BMI3_FIFO_GYRO_I2C_SYNC_FRAME 0x7f02
+#define BMI3_FIFO_ACCEL_I2C_SYNC_FRAME 0x7f01
+
+/* Gyro self calibration address */
+#define BMI3_BASE_ADDR_SC 0x26
+#define BMI3_CMD_SELF_CALIB 0x0101
+
+/* Feature engine General purpose register 1. */
+#define BMI3_FEATURE_IO_0 0x10
+#define BMI3_ANY_MOTION_X_EN_MASK 0x08
+
+#define BMI3_FEATURE_IO_1 0x11
+#define BMI3_FEATURE_IO_1_ERROR_MASK 0x0F
+#define BMI3_FEATURE_IO_1_NO_ERROR 0x05
+#define BMI3_SC_ST_STATUS_MASK 0x10
+#define BMI3_SC_RESULT_MASK 0x20
+#define BMI3_UGAIN_OFFS_UPD_COMPLETE 0x01
+
+#define BMI3_FEATURE_IO_STATUS 0x14
+
+/*
+ * The max positive value of accel data is 0x7FFF, equal to range(g)
+ * So, in order to get +1g, divide the 0x7FFF by range
+ */
+#define BMI3_ACC_DATA_PLUS_1G(range) (0x7FFF / (range))
+#define BMI3_ACC_DATA_MINUS_1G(range) (-BMI3_ACC_DATA_PLUS_1G(range))
+
+/* Offset DMA registers */
+#define BMI3_ACC_OFFSET_ADDR 0x40
+#define BMI3_GYRO_OFFSET_ADDR 0x46
+
+/*
+ * Start address of the DMA transaction. Has to be written to initiate a
+ * transaction.
+ */
+#define BMI3_FEATURE_ENGINE_DMA_TX 0x41
+
+/* DMA read/write data. On read transaction expect first word to be zero. */
+#define BMI3_FEATURE_ENGINE_DMA_TX_DATA 0x42
+
+/* Command for offset update */
+#define BMI3_CMD_USR_GAIN_OFFS_UPDATE 0x301
+
+/* 1LSB - 31 Micro-G */
+#define BMI3_OFFSET_ACC_MULTI_MG (31 * 1000)
+
+/* 1LSB = 61 milli-dps*/
+#define BMI3_OFFSET_GYR_MDPS (61 * 1000)
+
+#define BMI3_FIFO_BUFFER 32
+
+/* General Macro Definitions */
+/* LSB and MSB mask definitions */
+#define BMI3_SET_LOW_BYTE 0x00FF
+#define BMI3_SET_HIGH_BYTE 0xFF00
+
+/* For enable and disable */
+#define BMI3_ENABLE 0x1
+#define BMI3_DISABLE 0x0
+
+/* Defines mode of operation for Accelerometer */
+#define BMI3_POWER_MODE_MASK 0x70
+#define BMI3_POWER_MODE_POS 4
+
+#define BMI3_SENS_ODR_MASK 0x0F
+
+/* Full scale, Resolution */
+#define BMI3_SENS_RANGE_MASK 0x70
+#define BMI3_SENS_RANGE_POS 4
+
+#define BMI3_CHIP_ID_MASK 0xFF
+
+/* Map FIFO water-mark interrupt to either INT1 or INT2 or IBI */
+#define BMI3_FWM_INT_MASK 0x30
+#define BMI3_FWM_INT_POS 4
+
+/* Map FIFO full interrupt to either INT1 or INT2 or IBI */
+#define BMI3_FFULL_INT_MASK 0xC0
+#define BMI3_FFULL_INT_POS 6
+
+#define BMI3_ORIENT_INT_MASK 0xC0
+#define BMI3_ORIENT_INT_POS 6
+
+
+
+/* Mask definitions for interrupt pin configuration */
+#define BMI3_INT_LATCH_MASK 0x0001
+
+/**
+ * Current fill level of FIFO buffer
+ * An empty FIFO corresponds to 0x000. The word counter may be reset by reading
+ * out all frames from the FIFO buffer or when the FIFO is reset through
+ * fifo_flush. The word counter is updated each time a complete frame was read
+ * or written.
+ */
+#define BMI3_FIFO_FILL_LVL_MASK 0x07FF
+
+/* Enum to define interrupt lines */
+enum bmi3_hw_int_pin {
+ BMI3_INT_NONE,
+ BMI3_INT1,
+ BMI3_INT2,
+ BMI3_I3C_INT,
+ BMI3_INT_PIN_MAX
+};
+
+/* Structure to define FIFO frame configuration */
+struct bmi3_fifo_frame {
+ uint16_t data[BMI3_FIFO_BUFFER + 1];
+
+ /* Available fifo length */
+ uint16_t available_fifo_len;
+};
+
+enum sensor_index_t {
+ FIRST_CONT_SENSOR = 0,
+ SENSOR_ACCEL = FIRST_CONT_SENSOR,
+ SENSOR_GYRO,
+ NUM_OF_PRIMARY_SENSOR,
+};
+
+#define BMI3_DRDY_OFF(_sensor) (7 - (_sensor))
+#define BMI3_DRDY_MASK(_sensor) (1 << BMI3_DRDY_OFF(_sensor))
+
+/* Utility macros */
+#define BMI3_SET_BITS(reg_data, bitname, data) \
+ ((reg_data & ~(bitname##_MASK)) | \
+ ((data << bitname##_POS) & bitname##_MASK))
+
+#define BMI3_GET_BITS(reg_data, bitname) \
+ ((reg_data & (bitname##_MASK)) >> \
+ (bitname##_POS))
+
+#define BMI3_SET_BIT_POS0(reg_data, bitname, data) \
+ ((reg_data & ~(bitname##_MASK)) | \
+ (data & bitname##_MASK))
+
+#define BMI3_GET_BIT_POS0(reg_data, bitname) \
+ (reg_data & (bitname##_MASK))
+
+extern const struct accelgyro_drv bmi3xx_drv;
+
+void bmi3xx_interrupt(enum gpio_signal signal);
+
+#if defined(CONFIG_ZEPHYR)
+#if DT_NODE_EXISTS(DT_ALIAS(bmi3xx_int))
+/*
+ * Get the motion sensor ID of the BMI3xx sensor that
+ * generates the interrupt.
+ * The interrupt is converted to the event and transferred to motion
+ * sense task that actually handles the interrupt.
+ *
+ * Here, we use alias to get the motion sensor ID
+ *
+ * e.g) base_accel is the label of a child node in /motionsense-sensors
+ * aliases {
+ * bmi3xx-int = &base_accel;
+ * };
+ */
+#define CONFIG_ACCELGYRO_BMI3XX_INT_EVENT \
+ TASK_EVENT_MOTION_SENSOR_INTERRUPT(SENSOR_ID(DT_ALIAS(bmi3xx_int)))
+#endif
+#endif /* CONFIG_ZEPHYR */
+
+#endif /* __CROS_EC_ACCELGYRO_BMI3XX_H */
diff --git a/driver/accelgyro_bmi_common.c b/driver/accelgyro_bmi_common.c
index e7c1776a51..8da6b76e15 100644
--- a/driver/accelgyro_bmi_common.c
+++ b/driver/accelgyro_bmi_common.c
@@ -23,8 +23,9 @@
#define CPRINTF(format, args...) cprintf(CC_ACCEL, format, ## args)
#define CPRINTS(format, args...) cprints(CC_ACCEL, format, ## args)
-#if !defined(CONFIG_ACCELGYRO_BMI160) && !defined(CONFIG_ACCELGYRO_BMI260)
-#error "Must use either BMI160 or BMI260"
+#if !defined(CONFIG_ACCELGYRO_BMI160) && !defined(CONFIG_ACCELGYRO_BMI260) \
+&& !defined(CONFIG_ACCELGYRO_BMI3XX)
+#error "Must use following sensors BMI160 BMI260 BMI3XX"
#endif
#if defined(CONFIG_ACCELGYRO_BMI260) && !defined(CONFIG_ACCELGYRO_BMI160)
diff --git a/driver/build.mk b/driver/build.mk
index 2e394c2ac0..e1b6433f96 100644
--- a/driver/build.mk
+++ b/driver/build.mk
@@ -16,6 +16,7 @@ driver-$(CONFIG_ACCEL_KX022)+=accel_kionix.o
driver-$(CONFIG_ACCELGYRO_LSM6DS0)+=accelgyro_lsm6ds0.o
driver-$(CONFIG_ACCELGYRO_BMI160)+=accelgyro_bmi160.o accelgyro_bmi_common.o
driver-$(CONFIG_ACCELGYRO_BMI260)+=accelgyro_bmi260.o accelgyro_bmi_common.o
+driver-$(CONFIG_ACCELGYRO_BMI3XX)+=accelgyro_bmi3xx.o accelgyro_bmi_common.o
driver-$(CONFIG_ACCEL_BMA4XX)+=accel_bma4xx.o
driver-$(CONFIG_MAG_BMI_BMM150)+=mag_bmm150.o
driver-$(CONFIG_ACCELGYRO_LSM6DSM)+=accelgyro_lsm6dsm.o stm_mems_common.o
diff --git a/include/config.h b/include/config.h
index 7241e63190..1ec20663c5 100644
--- a/include/config.h
+++ b/include/config.h
@@ -120,6 +120,7 @@
#undef CONFIG_ACCELGYRO_BMI160
#undef CONFIG_ACCELGYRO_BMI260
+#undef CONFIG_ACCELGYRO_BMI3XX
#undef CONFIG_ACCELGYRO_ICM426XX
#undef CONFIG_ACCELGYRO_LSM6DS0
/* Use CONFIG_ACCELGYRO_LSM6DSM for LSM6DSL, LSM6DSM, and/or LSM6DS3 */
@@ -348,6 +349,7 @@
*/
#undef CONFIG_ACCELGYRO_BMI160_INT_EVENT
#undef CONFIG_ACCELGYRO_BMI260_INT_EVENT
+#undef CONFIG_ACCELGYRO_BMI3XX_INT_EVENT
#undef CONFIG_ACCELGYRO_ICM426XX_INT_EVENT
#undef CONFIG_ACCEL_LSM6DSM_INT_EVENT
#undef CONFIG_ACCEL_LSM6DSO_INT_EVENT
diff --git a/include/ec_commands.h b/include/ec_commands.h
index 675dfcb4ec..e4c7cf73ca 100644
--- a/include/ec_commands.h
+++ b/include/ec_commands.h
@@ -2602,6 +2602,7 @@ enum motionsensor_chip {
MOTIONSENSE_CHIP_ICM426XX = 25,
MOTIONSENSE_CHIP_ICM42607 = 26,
MOTIONSENSE_CHIP_BMA422 = 27,
+ MOTIONSENSE_CHIP_BMI323 = 28,
MOTIONSENSE_CHIP_MAX,
};
diff --git a/zephyr/shim/include/config_chip.h b/zephyr/shim/include/config_chip.h
index b637960060..7b120b3bc9 100644
--- a/zephyr/shim/include/config_chip.h
+++ b/zephyr/shim/include/config_chip.h
@@ -82,6 +82,681 @@
#endif /* CONFIG_PLATFORM_EC_TIMER */
+/* USB-C things */
+#ifdef CONFIG_PLATFORM_EC_USBC
+
+/* Zephyr only supports v2 so we always define this */
+#define CONFIG_USB_PD_TCPMV2
+
+/*
+ * Define these here for now. They are not actually CONFIG options in the EC
+ * code base. Ideally they would be defined in the devicetree (perhaps for a
+ * 'board' driver if not in the USB chip driver itself).
+ *
+ * SN5S30 PPC supports up to 24V VBUS source and sink, however passive USB-C
+ * cables only support up to 60W.
+ */
+#define PD_OPERATING_POWER_MW 15000
+#define PD_MAX_POWER_MW 60000
+#define PD_MAX_CURRENT_MA 3000
+#define PD_MAX_VOLTAGE_MV 20000
+
+/* TODO: b/144165680 - measure and check these values on Volteer */
+#define PD_POWER_SUPPLY_TURN_ON_DELAY 30000 /* us */
+#define PD_POWER_SUPPLY_TURN_OFF_DELAY 30000 /* us */
+#endif
+
+#undef CONFIG_CMD_PPC_DUMP
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_PPC_DUMP
+#define CONFIG_CMD_PPC_DUMP
+#endif
+
+#undef CONFIG_CMD_TCPC_DUMP
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_TCPC_DUMP
+#define CONFIG_CMD_TCPC_DUMP
+#endif
+
+#undef CONFIG_USB_POWER_DELIVERY
+#ifdef CONFIG_PLATFORM_EC_USB_POWER_DELIVERY
+#define CONFIG_USB_POWER_DELIVERY
+#endif
+
+#undef CONFIG_CHARGER
+#undef CONFIG_CHARGE_MANAGER
+#ifdef CONFIG_PLATFORM_EC_CHARGE_MANAGER
+#define CONFIG_CHARGE_MANAGER
+#define CONFIG_CHARGER
+
+/* TODO: Put these charger defines in the devicetree? */
+#define CONFIG_CHARGER_SENSE_RESISTOR 10
+#define CONFIG_CHARGER_SENSE_RESISTOR_AC 10
+
+#endif
+
+#undef CONFIG_CHARGER_INPUT_CURRENT
+#ifdef CONFIG_PLATFORM_EC_CHARGER_INPUT_CURRENT
+#define CONFIG_CHARGER_INPUT_CURRENT CONFIG_PLATFORM_EC_CHARGER_INPUT_CURRENT
+#endif
+
+#undef CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON
+#ifdef CONFIG_PLATFORM_EC_CHARGER_MIN_BAT_PCT_FOR_POWER_ON
+#define CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON \
+ CONFIG_PLATFORM_EC_CHARGER_MIN_BAT_PCT_FOR_POWER_ON
+#endif
+
+#undef CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON_WITH_AC
+#ifdef CONFIG_PLATFORM_EC_CHARGER_MIN_BAT_PCT_FOR_POWER_ON_WITH_AC
+#define CONFIG_CHARGER_MIN_BAT_PCT_FOR_POWER_ON_WITH_AC \
+ CONFIG_PLATFORM_EC_CHARGER_MIN_BAT_PCT_FOR_POWER_ON_WITH_AC
+#endif
+
+#undef CONFIG_CHARGER_MIN_POWER_MW_FOR_POWER_ON_WITH_BATT
+#ifdef CONFIG_PLATFORM_EC_CHARGER_MIN_POWER_MW_FOR_POWER_ON_WITH_BATT
+#define CONFIG_CHARGER_MIN_POWER_MW_FOR_POWER_ON_WITH_BATT \
+ CONFIG_PLATFORM_EC_CHARGER_MIN_POWER_MW_FOR_POWER_ON_WITH_BATT
+#endif
+
+#undef CONFIG_CHARGER_MIN_POWER_MW_FOR_POWER_ON
+#ifdef CONFIG_PLATFORM_EC_CHARGER_MIN_POWER_MW_FOR_POWER_ON
+#define CONFIG_CHARGER_MIN_POWER_MW_FOR_POWER_ON \
+ CONFIG_PLATFORM_EC_CHARGER_MIN_POWER_MW_FOR_POWER_ON
+#endif
+
+#undef CONFIG_CHARGE_RAMP_SW
+#ifdef CONFIG_PLATFORM_EC_CHARGE_RAMP_SW
+#define CONFIG_CHARGE_RAMP_SW
+#endif
+
+#undef CONFIG_CHARGE_RAMP_HW
+#ifdef CONFIG_PLATFORM_EC_CHARGE_RAMP_HW
+#define CONFIG_CHARGE_RAMP_HW
+#endif
+
+#undef CONFIG_CMD_CHGRAMP
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_CHGRAMP
+#define CONFIG_CMD_CHGRAMP
+#endif
+
+#undef CONFIG_USB_PID
+#ifdef CONFIG_PLATFORM_EC_USB_PID
+#define CONFIG_USB_PID CONFIG_PLATFORM_EC_USB_PID
+#endif
+
+#undef CONFIG_USB_BCD_DEV
+#ifdef CONFIG_PLATFORM_EC_USB_BCD_DEV
+#define CONFIG_USB_BCD_DEV CONFIG_PLATFORM_EC_USB_BCD_DEV
+#endif
+
+#undef CONFIG_USB_VID
+#ifdef CONFIG_PLATFORM_EC_USB_VID
+#define CONFIG_USB_VID CONFIG_PLATFORM_EC_USB_VID
+#endif
+
+/* VBUS-voltage measurement */
+#undef CONFIG_USB_PD_VBUS_MEASURE_NOT_PRESENT
+#undef CONFIG_USB_PD_VBUS_MEASURE_CHARGER
+#undef CONFIG_USB_PD_VBUS_MEASURE_TCPC
+#undef CONFIG_USB_PD_VBUS_MEASURE_ADC_EACH_PORT
+#ifdef CONFIG_PLATFORM_EC_USB_PD_VBUS_MEASURE_NOT_PRESENT
+#define CONFIG_USB_PD_VBUS_MEASURE_NOT_PRESENT
+#elif defined(CONFIG_PLATFORM_EC_USB_PD_VBUS_MEASURE_CHARGER)
+#define CONFIG_USB_PD_VBUS_MEASURE_CHARGER
+#elif defined(CONFIG_PLATFORM_EC_USB_PD_VBUS_MEASURE_TCPC)
+#define CONFIG_USB_PD_VBUS_MEASURE_TCPC
+#elif defined(CONFIG_PLATFORM_EC_USB_PD_VBUS_MEASURE_ADC_EACH_PORT)
+#define CONFIG_USB_PD_VBUS_MEASURE_ADC_EACH_PORT
+#endif /* VBUS-voltage measurement */
+
+#undef CONFIG_USB_CHARGER
+#ifdef CONFIG_PLATFORM_EC_USB_CHARGER
+#define CONFIG_USB_CHARGER
+#endif
+
+#define USB_PORT_COUNT CONFIG_PLATFORM_EC_USB_A_PORT_COUNT
+
+#undef CONFIG_USB_PORT_POWER_DUMB
+#ifdef CONFIG_PLATFORM_EC_USB_PORT_POWER_DUMB
+#define CONFIG_USB_PORT_POWER_DUMB
+#endif
+
+#undef CONFIG_USB_PORT_POWER_DUMB_CUSTOM_HOOK
+#ifdef CONFIG_PLATFORM_EC_USB_PORT_POWER_DUMB_CUSTOM_HOOK
+#define CONFIG_USB_PORT_POWER_DUMB_CUSTOM_HOOK
+#endif
+
+#undef CONFIG_BC12_DETECT_PI3USB9201
+#ifdef CONFIG_PLATFORM_EC_BC12_DETECT_PI3USB9201
+#define CONFIG_BC12_DETECT_PI3USB9201
+#endif
+
+#undef CONFIG_BC12_DETECT_MT6360
+#ifdef CONFIG_PLATFORM_EC_BC12_DETECT_MT6360
+#define CONFIG_BC12_DETECT_MT6360
+#endif
+
+#undef CONFIG_MT6360_BC12_GPIO
+#ifdef CONFIG_PLATFORM_EC_MT6360_BC12_GPIO
+#define CONFIG_MT6360_BC12_GPIO
+#endif
+
+#undef CONFIG_USB_PD_DUAL_ROLE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_DUAL_ROLE
+#define CONFIG_USB_PD_DUAL_ROLE
+#endif
+
+#undef CONFIG_USB_PD_DUAL_ROLE_AUTO_TOGGLE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_DUAL_ROLE_AUTO_TOGGLE
+#define CONFIG_USB_PD_DUAL_ROLE_AUTO_TOGGLE
+#endif
+
+#undef CONFIG_USB_PD_DISCHARGE_PPC
+#ifdef CONFIG_PLATFORM_EC_USB_PD_DISCHARGE_PPC
+#define CONFIG_USB_PD_DISCHARGE_PPC
+#endif
+
+#undef CONFIG_USB_PD_LOGGING
+#ifdef CONFIG_PLATFORM_EC_USB_PD_LOGGING
+#define CONFIG_USB_PD_LOGGING
+#endif
+
+#undef CONFIG_USBC_OCP
+#ifdef CONFIG_PLATFORM_EC_USBC_OCP
+#define CONFIG_USBC_OCP
+#endif
+
+#undef CONFIG_USB_PD_CONSOLE_CMD
+#ifdef CONFIG_PLATFORM_EC_USB_PD_CONSOLE_CMD
+#define CONFIG_USB_PD_CONSOLE_CMD
+#endif
+
+#undef CONFIG_USB_PD_HOST_CMD
+#ifdef CONFIG_PLATFORM_EC_USB_PD_HOST_CMD
+#define CONFIG_USB_PD_HOST_CMD
+#endif
+
+#undef CONFIG_USB_PD_REV30
+#ifdef CONFIG_PLATFORM_EC_USB_PD_REV30
+#define CONFIG_USB_PD_REV30
+
+/*
+ * Support USB PD 3.0 Extended Messages. Note that Chromebooks disabling this
+ * config item are non-compliant with PD 3.0, because they have batteries but do
+ * not support Get_Battery_Cap or Get_Battery_Status.
+ */
+#define CONFIG_USB_PD_EXTENDED_MESSAGES
+#endif
+
+#undef CONFIG_USB_PD_VBUS_DETECT_TCPC
+#undef CONFIG_USB_PD_VBUS_DETECT_CHARGER
+#undef CONFIG_USB_PD_VBUS_DETECT_GPIO
+#undef CONFIG_USB_PD_VBUS_DETECT_PPC
+#undef CONFIG_USB_PD_VBUS_DETECT_NONE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_VBUS_DETECT_TCPC
+#define CONFIG_USB_PD_VBUS_DETECT_TCPC
+#endif
+#ifdef CONFIG_PLATFORM_EC_USB_PD_VBUS_DETECT_CHARGER
+#define CONFIG_USB_PD_VBUS_DETECT_CHARGER
+#endif
+#ifdef CONFIG_PLATFORM_EC_USB_PD_VBUS_DETECT_PPC
+#define CONFIG_USB_PD_VBUS_DETECT_PPC
+#endif
+#ifdef CONFIG_PLATFORM_EC_USB_PD_VBUS_DETECT_NONE
+#define CONFIG_USB_PD_VBUS_DETECT_NONE
+#endif
+
+#undef CONFIG_USB_PD_5V_EN_CUSTOM
+#ifdef CONFIG_PLATFORM_EC_USB_PD_5V_EN_CUSTOM
+#define CONFIG_USB_PD_5V_EN_CUSTOM
+#endif
+
+#undef CONFIG_USB_TYPEC_SM
+#ifdef CONFIG_PLATFORM_EC_USB_TYPEC_SM
+#define CONFIG_USB_TYPEC_SM
+#endif
+
+#undef CONFIG_USB_PRL_SM
+#ifdef CONFIG_PLATFORM_EC_USB_PRL_SM
+#define CONFIG_USB_PRL_SM
+#endif
+
+#undef CONFIG_USB_PE_SM
+#ifdef CONFIG_PLATFORM_EC_USB_PE_SM
+#define CONFIG_USB_PE_SM
+#endif
+
+#undef CONFIG_USB_PD_DECODE_SOP
+#ifdef CONFIG_PLATFORM_EC_USB_PD_DECODE_SOP
+#define CONFIG_USB_PD_DECODE_SOP
+#endif
+
+#undef CONFIG_USB_VPD
+#ifdef CONFIG_PLATFORM_EC_USB_VPD
+#define CONFIG_USB_VPD
+#endif
+
+#undef CONFIG_USB_CTVPD
+#ifdef CONFIG_PLATFORM_EC_USB_CTVPD
+#define CONFIG_USB_CTVPD
+#endif
+
+#undef CONFIG_USB_DRP_ACC_TRYSRC
+#ifdef CONFIG_PLATFORM_EC_USB_DRP_ACC_TRYSRC
+#define CONFIG_USB_DRP_ACC_TRYSRC
+#endif
+
+#undef CONFIG_USB_PD_TCPM_PS8751
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_PS8751
+#define CONFIG_USB_PD_TCPM_PS8751
+#endif
+
+#undef CONFIG_USB_PD_TCPM_PS8805
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_PS8805
+#define CONFIG_USB_PD_TCPM_PS8805
+#endif
+
+#undef CONFIG_USB_PD_TCPM_PS8815
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_PS8815
+#define CONFIG_USB_PD_TCPM_PS8815
+#define CONFIG_USB_PD_TCPM_PS8815_FORCE_DID
+#endif
+
+#undef CONFIG_USB_PD_TCPM_MULTI_PS8XXX
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_MULTI_PS8XXX
+#define CONFIG_USB_PD_TCPM_MULTI_PS8XXX
+#endif
+
+#undef CONFIG_USB_PD_TCPM_RT1715
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_RT1715
+#define CONFIG_USB_PD_TCPM_RT1715
+#endif
+
+#undef CONFIG_USB_PD_TCPM_TUSB422
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_TUSB422
+#define CONFIG_USB_PD_TCPM_TUSB422
+#endif
+
+#undef CONFIG_USB_PD_TCPM_TCPCI
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_TCPCI
+#define CONFIG_USB_PD_TCPM_TCPCI
+#endif
+
+#undef CONFIG_USB_PD_TCPM_ITE_ON_CHIP
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_ITE_ON_CHIP
+#define CONFIG_USB_PD_TCPM_ITE_ON_CHIP
+
+/* TODO(b:189855648): hard-code a few things here; move to zephyr? */
+#define IT83XX_USBPD_PHY_PORT_COUNT 2
+#endif
+
+#undef CONFIG_USB_PD_TCPM_DRIVER_IT8XXX2
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_DRIVER_IT8XXX2
+#define CONFIG_USB_PD_TCPM_DRIVER_IT8XXX2
+#endif
+
+#undef CONFIG_USB_PD_TCPM_DRIVER_IT83XX
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_DRIVER_IT83XX
+#define CONFIG_USB_PD_TCPM_DRIVER_IT83XX
+#endif
+
+#undef CONFIG_USB_PD_PORT_MAX_COUNT
+#ifdef CONFIG_PLATFORM_EC_USB_PD_PORT_MAX_COUNT
+#define CONFIG_USB_PD_PORT_MAX_COUNT CONFIG_PLATFORM_EC_USB_PD_PORT_MAX_COUNT
+#endif
+
+#undef CONFIG_USB_PD_ITE_ACTIVE_PORT_COUNT
+#ifdef CONFIG_PLATFORM_EC_USB_PD_ITE_ACTIVE_PORT_COUNT
+#define CONFIG_USB_PD_ITE_ACTIVE_PORT_COUNT \
+ CONFIG_PLATFORM_EC_USB_PD_ITE_ACTIVE_PORT_COUNT
+#endif
+
+#undef CONFIG_USBC_PPC
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC
+#define CONFIG_USBC_PPC
+#endif
+
+#undef CONFIG_USBC_PPC_SN5S330
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_SN5S330
+#define CONFIG_USBC_PPC_SN5S330
+#endif
+
+#undef CONFIG_USBC_PPC_SYV682X
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_SYV682X
+#define CONFIG_USBC_PPC_SYV682X
+#endif
+
+#undef CONFIG_USBC_PPC_SYV682C
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_SYV682C
+#define CONFIG_USBC_PPC_SYV682C
+#endif
+
+#undef CONFIG_SYV682X_NO_CC
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_SYV682X_NO_CC
+#define CONFIG_SYV682X_NO_CC
+#endif
+
+#undef CONFIG_USB_PD_TCPC_RUNTIME_CONFIG
+#undef CONFIG_USB_MUX_RUNTIME_CONFIG
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPC_RUNTIME_CONFIG
+#define CONFIG_USB_PD_TCPC_RUNTIME_CONFIG
+
+#ifdef CONFIG_PLATFORM_EC_USB_MUX_RUNTIME_CONFIG
+#define CONFIG_USB_MUX_RUNTIME_CONFIG
+#endif /* CONFIG_PLATFORM_EC_USB_MUX_RUNTIME_CONFIG */
+
+#endif /* CONFIG_PLATFORM_EC_USB_PD_TCPC_RUNTIME_CONFIG */
+
+#undef CONFIG_USB_PD_ALT_MODE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_ALT_MODE
+#define CONFIG_USB_PD_ALT_MODE
+#endif
+
+#undef CONFIG_USB_PD_ALT_MODE_DFP
+#ifdef CONFIG_PLATFORM_EC_USB_PD_ALT_MODE_DFP
+#define CONFIG_USB_PD_ALT_MODE_DFP
+#endif
+
+#undef CONFIG_USB_PD_ALT_MODE_UFP
+#ifdef CONFIG_PLATFORM_EC_USB_PD_ALT_MODE_UFP
+#define CONFIG_USB_PD_ALT_MODE_UFP
+#endif
+
+#undef CONFIG_DP_REDRIVER_TDP142
+#ifdef CONFIG_PLATFORM_EC_DP_REDRIVER_TDP142
+#define CONFIG_DP_REDRIVER_TDP142
+#endif
+
+#undef CONFIG_USBC_RETIMER_FW_UPDATE
+#ifdef CONFIG_PLATFORM_EC_USBC_RETIMER_FW_UPDATE
+#define CONFIG_USBC_RETIMER_FW_UPDATE
+#endif
+
+#undef CONFIG_USBC_RETIMER_INTEL_BB
+#ifdef CONFIG_PLATFORM_EC_USBC_RETIMER_INTEL_BB
+
+#define USBC_PORT_C1_BB_RETIMER_I2C_ADDR \
+ DT_REG_ADDR(DT_NODELABEL(usb_c1_bb_retimer))
+#define CONFIG_USBC_RETIMER_INTEL_BB
+#endif
+
+#undef CONFIG_USBC_RETIMER_INTEL_BB_RUNTIME_CONFIG
+#ifdef CONFIG_PLATFORM_EC_USBC_RETIMER_INTEL_BB_RUNTIME_CONFIG
+#define CONFIG_USBC_RETIMER_INTEL_BB_RUNTIME_CONFIG
+#endif
+
+#undef CONFIG_USBC_RETIMER_ANX7451
+#ifdef PLATFORM_EC_USBC_RETIMER_ANX7451
+#define CONFIG_USBC_RETIMER_ANX7451
+#endif
+
+#undef CONFIG_USBC_RETIMER_PS8811
+#ifdef PLATFORM_EC_USBC_RETIMER_PS8811
+#define CONFIG_USBC_RETIMER_PS8811
+#endif
+
+#undef CONFIG_USBC_SS_MUX
+#ifdef CONFIG_PLATFORM_EC_USBC_SS_MUX
+#define CONFIG_USBC_SS_MUX
+#endif
+
+#undef CONFIG_USBC_SS_MUX_DFP_ONLY
+#ifdef CONFIG_PLATFORM_EC_USBC_SS_MUX_DFP_ONLY
+#define CONFIG_USBC_SS_MUX_DFP_ONLY
+#endif
+
+#undef CONFIG_USB_MUX_IT5205
+#ifdef CONFIG_PLATFORM_EC_USB_MUX_IT5205
+#define CONFIG_USB_MUX_IT5205
+#endif
+
+#undef CONFIG_USB_MUX_PS8743
+#ifdef CONFIG_PLATFORM_EC_USB_MUX_PS8743
+#define CONFIG_USB_MUX_PS8743
+#endif
+
+#undef CONFIG_USB_MUX_VIRTUAL
+#ifdef CONFIG_PLATFORM_EC_USB_MUX_VIRTUAL
+#define CONFIG_USB_MUX_VIRTUAL
+#endif
+
+#undef CONFIG_USB_PD_TCPM_MUX
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPM_MUX
+#define CONFIG_USB_PD_TCPM_MUX
+#endif
+
+#undef CONFIG_USBC_PPC_DEDICATED_INT
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_DEDICATED_INT
+#define CONFIG_USBC_PPC_DEDICATED_INT
+#endif
+
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_PD
+#define CONFIG_CONSOLE_CMD_PD
+#endif
+
+#ifdef CONFIG_HAS_TASK_PD_INT_C0
+/* This must be defined if any task is active */
+#define CONFIG_HAS_TASK_PD_INT
+#endif
+
+#undef CONFIG_MKBP_EVENT
+#undef CONFIG_MKBP_USE_GPIO
+#undef CONFIG_MKBP_USE_HOST_EVENT
+#undef CONFIG_MKBP_USE_GPIO_AND_HOST_EVENT
+#undef CONFIG_MKBP_USE_CUSTOM
+#ifdef CONFIG_PLATFORM_EC_MKBP_EVENT
+#define CONFIG_MKBP_EVENT
+#ifdef CONFIG_PLATFORM_EC_MKBP_USE_GPIO
+#define CONFIG_MKBP_USE_GPIO
+#elif PLATFORM_EC_MKBP_USE_HOST_EVENT
+#define CONFIG_MKBP_USE_HOST_EVENT
+#elif PLATFORM_EC_MKBP_USE_GPIO_AND_HOST_EVENT
+#define CONFIG_MKBP_USE_GPIO_AND_HOST_EVENT
+#elif PLATFORM_EC_MKBP_USE_CUSTOM
+#define CONFIG_MKBP_USE_CUSTOM
+#endif
+#endif /* CONFIG_PLATFORM_EC_MKBP_EVENT */
+
+#undef CONFIG_USB_PD_TCPC_LOW_POWER
+#undef CONFIG_USB_PD_TCPC_LPM_EXIT_DEBOUNCE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TCPC_LOW_POWER
+#define CONFIG_USB_PD_TCPC_LOW_POWER
+#define CONFIG_USB_PD_TCPC_LPM_EXIT_DEBOUNCE \
+ CONFIG_PLATFORM_EC_USB_PD_TCPC_LPM_EXIT_DEBOUNCE_US
+#endif /* CONFIG_PLATFORM_EC_USB_PD_TCPC_LOW_POWER */
+
+#undef CONFIG_USB_PD_DEBUG_LEVEL
+#ifdef CONFIG_PLATFORM_EC_USB_PD_DEBUG_FIXED_LEVEL
+#define CONFIG_USB_PD_DEBUG_LEVEL CONFIG_PLATFORM_EC_USB_PD_DEBUG_LEVEL
+#endif
+
+#undef CONFIG_USBC_VCONN
+#ifdef CONFIG_PLATFORM_EC_USBC_VCONN
+#define CONFIG_USBC_VCONN
+
+/* This must be defined as well */
+#define CONFIG_USBC_VCONN_SWAP
+#endif /* CONFIG_PLATFORM_EC_USBC_VCONN */
+
+#undef CONFIG_USB_PD_TRY_SRC
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TRY_SRC
+#define CONFIG_USB_PD_TRY_SRC
+#endif
+
+#undef CONFIG_USBC_PPC_POLARITY
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_POLARITY
+#define CONFIG_USBC_PPC_POLARITY
+#endif
+
+#undef CONFIG_USBC_PPC_SBU
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_SBU
+#define CONFIG_USBC_PPC_SBU
+#endif
+
+#undef CONFIG_USBC_PPC_VCONN
+#ifdef CONFIG_PLATFORM_EC_USBC_PPC_VCONN
+#define CONFIG_USBC_PPC_VCONN
+#endif
+
+#undef CONFIG_USB_PD_USB32_DRD
+#ifdef CONFIG_PLATFORM_EC_USB_PD_USB32_DRD
+#define CONFIG_USB_PD_USB32_DRD
+#endif
+
+#undef CONFIG_HOSTCMD_PD_CONTROL
+#ifdef CONFIG_PLATFORM_EC_HOSTCMD_PD_CONTROL
+#define CONFIG_HOSTCMD_PD_CONTROL
+#endif
+
+#undef CONFIG_CMD_HCDEBUG
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_HCDEBUG
+#define CONFIG_CMD_HCDEBUG
+#endif
+
+#undef CONFIG_CMD_USB_PD_PE
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_USB_PD_PE
+#define CONFIG_CMD_USB_PD_PE
+#endif
+
+#undef CONFIG_CMD_USB_PD_CABLE
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_USB_PD_CABLE
+#define CONFIG_CMD_USB_PD_CABLE
+#endif
+
+#undef CONFIG_USB_PD_TBT_COMPAT_MODE
+#ifdef CONFIG_PLATFORM_EC_USB_PD_TBT_COMPAT_MODE
+#define CONFIG_USB_PD_TBT_COMPAT_MODE
+#endif
+
+#undef CONFIG_USB_PD_USB4
+#ifdef CONFIG_PLATFORM_EC_USB_PD_USB4
+#define CONFIG_USB_PD_USB4
+#endif
+
+#undef CONFIG_USB_PD_FRS
+#ifdef CONFIG_PLATFORM_EC_USB_PD_FRS
+#define CONFIG_USB_PD_FRS
+#endif
+
+#undef CONFIG_USB_PD_FRS_TCPC
+#ifdef CONFIG_PLATFORM_EC_USB_PD_FRS_TCPC
+#define CONFIG_USB_PD_FRS_TCPC
+#endif
+
+#undef CONFIG_USB_PD_FRS_PPC
+#ifdef CONFIG_PLATFORM_EC_USB_PD_FRS_PPC
+#define CONFIG_USB_PD_FRS_PPC
+#endif
+
+#undef CONFIG_VSTORE
+#undef VSTORE_SLOT_COUNT
+#ifdef CONFIG_PLATFORM_EC_VSTORE
+#define CONFIG_VSTORE
+#define CONFIG_VSTORE_SLOT_COUNT CONFIG_PLATFORM_EC_VSTORE_SLOT_COUNT
+#endif
+
+/* motion sense */
+#undef CONFIG_MOTIONSENSE
+#ifdef CONFIG_PLATFORM_EC_MOTIONSENSE
+#define CONFIG_MOTIONSENSE
+
+#undef CONFIG_ACCEL_FIFO
+#undef CONFIG_ACCEL_FIFO_SIZE
+#undef CONFIG_ACCEL_FIFO_THRES
+#ifdef CONFIG_PLATFORM_EC_ACCEL_FIFO
+#define CONFIG_ACCEL_FIFO
+#define CONFIG_ACCEL_FIFO_SIZE CONFIG_PLATFORM_EC_ACCEL_FIFO_SIZE
+#define CONFIG_ACCEL_FIFO_THRES CONFIG_PLATFORM_EC_ACCEL_FIFO_THRES
+#endif /* CONFIG_PLATFORM_EC_ACCEL_FIFO */
+
+#undef CONFIG_CMD_ACCELS
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_ACCELS
+#define CONFIG_CMD_ACCELS
+#endif
+
+#undef CONFIG_CMD_ACCEL_INFO
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_ACCEL_INFO
+#define CONFIG_CMD_ACCEL_INFO
+#endif
+
+#undef CONFIG_ACCEL_SPOOF_MODE
+#ifdef CONFIG_PLATFORM_EC_ACCEL_SPOOF_MODE
+#define CONFIG_ACCEL_SPOOF_MODE
+#endif
+
+#undef CONFIG_CMD_ACCEL_SPOOF
+#ifdef CONFIG_PLATFORM_EC_CONSOLE_CMD_ACCEL_SPOOF
+#define CONFIG_CMD_ACCEL_SPOOF
+#endif
+
+#undef CONFIG_SENSOR_TIGHT_TIMESTAMPS
+#ifdef CONFIG_PLATFORM_EC_SENSOR_TIGHT_TIMESTAMPS
+#define CONFIG_SENSOR_TIGHT_TIMESTAMPS
+#endif
+
+#undef CONFIG_ACCEL_INTERRUPTS
+#ifdef CONFIG_PLATFORM_EC_ACCEL_INTERRUPTS
+#define CONFIG_ACCEL_INTERRUPTS
+#endif
+
+#undef CONFIG_ALS
+#undef CONFIG_ALS_COUNT
+#ifdef CONFIG_PLATFORM_EC_ALS
+#define CONFIG_ALS
+#define ALS_COUNT CONFIG_PLATFORM_EC_ALS_COUNT
+#else
+#define ALS_COUNT 0
+#endif
+
+#undef CONFIG_DYNAMIC_MOTION_SENSOR_COUNT
+#ifdef CONFIG_PLATFORM_EC_DYNAMIC_MOTION_SENSOR_COUNT
+#define CONFIG_DYNAMIC_MOTION_SENSOR_COUNT
+#endif
+
+#undef CONFIG_LID_ANGLE
+#ifdef CONFIG_PLATFORM_EC_LID_ANGLE
+#define CONFIG_LID_ANGLE
+#endif
+
+#undef CONFIG_LID_ANGLE_UPDATE
+#ifdef CONFIG_PLATFORM_EC_LID_ANGLE_UPDATE
+#define CONFIG_LID_ANGLE_UPDATE
+#endif
+
+#undef CONFIG_TABLET_MODE
+#ifdef CONFIG_PLATFORM_EC_TABLET_MODE
+#define CONFIG_TABLET_MODE
+#endif
+
+#undef CONFIG_TABLET_MODE_SWITCH
+#ifdef CONFIG_PLATFORM_EC_TABLET_MODE_SWITCH
+#define CONFIG_TABLET_MODE_SWITCH
+#endif
+
+#undef CONFIG_GMR_TABLET_MODE
+#ifdef CONFIG_PLATFORM_EC_GMR_TABLET_MODE
+#define CONFIG_GMR_TABLET_MODE
+#endif
+
+/* sensors */
+#undef CONFIG_ACCELGYRO_BMI160
+#ifdef CONFIG_PLATFORM_EC_ACCELGYRO_BMI160
+#define CONFIG_ACCELGYRO_BMI160
+#endif
+
+#undef CONFIG_ACCELGYRO_BMI260
+#ifdef CONFIG_PLATFORM_EC_ACCELGYRO_BMI260
+#define CONFIG_ACCELGYRO_BMI260
+#endif
+
+#undef CONFIG_ACCELGYRO_BMI3XX
+#ifdef CONFIG_PLATFORM_EC_ACCELGYRO_BMI3XX
+#define CONFIG_ACCELGYRO_BMI3XX
+#endif
+
+#undef CONFIG_ACCEL_BMA255
+#ifdef CONFIG_PLATFORM_EC_ACCEL_BMA255
+#define CONFIG_ACCEL_BMA255
+#endif
+
#undef CONFIG_ACCEL_BMA4XX
#ifdef CONFIG_PLATFORM_EC_ACCEL_BMA4XX
#define CONFIG_ACCEL_BMA4XX