summaryrefslogtreecommitdiff
path: root/driver
diff options
context:
space:
mode:
authorGwendal Grignou <gwendal@chromium.org>2020-10-21 12:57:22 -0700
committerCommit Bot <commit-bot@chromium.org>2020-11-06 01:43:35 +0000
commit7413dd10826ecb42cc2ee6b0a7919be2b290dd57 (patch)
treeb920b71a879e94079dfe4ef350b706f2aa64faf6 /driver
parent25588eb6a324d4e9f72b1a25fdcef4fc55bd653f (diff)
downloadchrome-ec-7413dd10826ecb42cc2ee6b0a7919be2b290dd57.tar.gz
driver: use IS_ENABLED on more accelerometer drivers
BUG=chromium:1140877 BRANCH=none TEST=buildall Change-Id: I3c45918b628d4f0999842922680a948cdd4933a2 Signed-off-by: Gwendal Grignou <gwendal@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/2491267 Reviewed-by: Ching-Kang Yen <chingkang@chromium.org>
Diffstat (limited to 'driver')
-rw-r--r--driver/accel_kionix.c21
-rw-r--r--driver/accel_lis2ds.c5
-rw-r--r--driver/accel_lis2dw12.c221
-rw-r--r--driver/accelgyro_icm426xx.c5
-rw-r--r--driver/accelgyro_lsm6dsm.c139
-rw-r--r--driver/accelgyro_lsm6dsm.h9
-rw-r--r--driver/accelgyro_lsm6dso.c7
7 files changed, 205 insertions, 202 deletions
diff --git a/driver/accel_kionix.c b/driver/accel_kionix.c
index a57291e6b0..141e645d99 100644
--- a/driver/accel_kionix.c
+++ b/driver/accel_kionix.c
@@ -42,6 +42,9 @@
#define T(s_) V(s_)
#endif /* !defined(CONFIG_ACCEL_KXCJ9) || !defined(CONFIG_ACCEL_KX022) */
+STATIC_IF(CONFIG_KX022_ORIENTATION_SENSOR) int check_orientation_locked(
+ const struct motion_sensor_t *s);
+
/* List of range values in +/-G's and their associated register values. */
static const struct accel_param_pair ranges[][3] = {
#ifdef CONFIG_ACCEL_KX022
@@ -264,11 +267,11 @@ static int enable_sensor(const struct motion_sensor_t *s, int reg_val)
if (ret != EC_SUCCESS)
continue;
-#ifdef CONFIG_KX022_ORIENTATION_SENSOR
/* Enable tilt orientation mode if lid sensor */
- if ((s->location == MOTIONSENSE_LOC_LID) && (V(s) == 0))
+ if (IS_ENABLED(CONFIG_KX022_ORIENTATION_SENSOR) &&
+ (s->location == MOTIONSENSE_LOC_LID) &&
+ (V(s) == 0))
reg_val |= KX022_CNTL1_TPE;
-#endif
/* Enable accelerometer based on reg_val value. */
ret = raw_write8(s->port, s->i2c_spi_addr_flags,
@@ -415,8 +418,7 @@ static int get_offset(const struct motion_sensor_t *s, int16_t *offset,
return EC_SUCCESS;
}
-#ifdef CONFIG_KX022_ORIENTATION_SENSOR
-static enum motionsensor_orientation kx022_convert_orientation(
+static __maybe_unused enum motionsensor_orientation kx022_convert_orientation(
const struct motion_sensor_t *s,
int orientation)
{
@@ -442,6 +444,7 @@ static enum motionsensor_orientation kx022_convert_orientation(
return res;
}
+#ifdef CONFIG_KX022_ORIENTATION_SENSOR
static int check_orientation_locked(const struct motion_sensor_t *s)
{
struct kionix_accel_data *data = s->drv_data;
@@ -494,11 +497,11 @@ static int read(const struct motion_sensor_t *s, intv3_t v)
reg = KIONIX_XOUT_L(V(s));
mutex_lock(s->mutex);
ret = raw_read_multi(s->port, s->i2c_spi_addr_flags, reg, acc, 6);
-#ifdef CONFIG_KX022_ORIENTATION_SENSOR
- if ((s->location == MOTIONSENSE_LOC_LID) && (V(s) == 0) &&
- (ret == EC_SUCCESS))
+ if (IS_ENABLED(CONFIG_KX022_ORIENTATION_SENSOR) &&
+ (s->location == MOTIONSENSE_LOC_LID) &&
+ (V(s) == 0) &&
+ (ret == EC_SUCCESS))
ret = check_orientation_locked(s);
-#endif
mutex_unlock(s->mutex);
if (ret != EC_SUCCESS)
diff --git a/driver/accel_lis2ds.c b/driver/accel_lis2ds.c
index c064cba03c..5c593bdcd0 100644
--- a/driver/accel_lis2ds.c
+++ b/driver/accel_lis2ds.c
@@ -360,11 +360,10 @@ static int init(const struct motion_sensor_t *s)
if (ret != EC_SUCCESS)
goto err_unlock;
-#ifdef CONFIG_ACCEL_INTERRUPTS
- ret = lis2ds_config_interrupt(s);
+ if (IS_ENABLED(CONFIG_ACCEL_INTERRUPTS))
+ ret = lis2ds_config_interrupt(s);
if (ret != EC_SUCCESS)
goto err_unlock;
-#endif /* CONFIG_ACCEL_INTERRUPTS */
mutex_unlock(s->mutex);
diff --git a/driver/accel_lis2dw12.c b/driver/accel_lis2dw12.c
index 1f791a8364..e67489956a 100644
--- a/driver/accel_lis2dw12.c
+++ b/driver/accel_lis2dw12.c
@@ -21,21 +21,22 @@
#define CPRINTF(format, args...) cprintf(CC_ACCEL, format, ## args)
#define CPRINTS(format, args...) cprints(CC_ACCEL, format, ## args)
-/* Only when configured as base accel sensor, fifo and interrupt
- * are supported.
+#if defined(CONFIG_ACCEL_INTERRUPTS) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
+/*
+ * Enable interrupts and FIFO only when the accelerometer is the main sensor.
*/
-#ifdef CONFIG_ACCEL_LIS2DW_AS_BASE
+#define LIS2DW12_ENABLE_FIFO
+#endif
-#ifdef CONFIG_ACCEL_FIFO
-static volatile uint32_t last_interrupt_timestamp;
+STATIC_IF(LIS2DW12_ENABLE_FIFO) volatile uint32_t last_interrupt_timestamp;
/**
* lis2dw12_enable_fifo - Enable/Disable FIFO in LIS2DW12
* @s: Motion sensor pointer
* @mode: fifo_modes
*/
-static int lis2dw12_enable_fifo(const struct motion_sensor_t *s,
- enum lis2dw12_fmode mode)
+static __maybe_unused int lis2dw12_enable_fifo(const struct motion_sensor_t *s,
+ enum lis2dw12_fmode mode)
{
return st_write_data_with_mask(s, LIS2DW12_FIFO_CTRL_ADDR,
LIS2DW12_FIFO_MODE_MASK, mode);
@@ -45,8 +46,8 @@ static int lis2dw12_enable_fifo(const struct motion_sensor_t *s,
* Load data from internal sensor FIFO.
* @s: Motion sensor pointer
*/
-static int lis2dw12_load_fifo(struct motion_sensor_t *s, int nsamples,
- uint32_t *last_fifo_read_ts)
+static __maybe_unused int lis2dw12_load_fifo(struct motion_sensor_t *s,
+ int nsamples, uint32_t *last_fifo_read_ts)
{
int ret, left, length, i;
struct ec_response_motion_sensor_data vect;
@@ -97,7 +98,8 @@ static int lis2dw12_load_fifo(struct motion_sensor_t *s, int nsamples,
/**
* lis2dw12_get_fifo_samples - check for stored FIFO samples.
*/
-static int lis2dw12_get_fifo_samples(struct motion_sensor_t *s, int *nsamples)
+static __maybe_unused int lis2dw12_get_fifo_samples(struct motion_sensor_t *s,
+ int *nsamples)
{
int ret, tmp;
@@ -111,7 +113,7 @@ static int lis2dw12_get_fifo_samples(struct motion_sensor_t *s, int *nsamples)
return EC_SUCCESS;
}
-static int fifo_data_avail(struct motion_sensor_t *s)
+static __maybe_unused int fifo_data_avail(struct motion_sensor_t *s)
{
int ret, nsamples;
@@ -125,7 +127,6 @@ static int fifo_data_avail(struct motion_sensor_t *s)
return 0;
return nsamples;
}
-#endif /* CONFIG_ACCEL_FIFO */
/**
* lis2dw12_config_interrupt- Configure interrupt for supported features.
@@ -133,70 +134,72 @@ static int fifo_data_avail(struct motion_sensor_t *s)
*
* Must works with interface mutex locked
*/
-static int lis2dw12_config_interrupt(const struct motion_sensor_t *s)
+static __maybe_unused int lis2dw12_config_interrupt(
+ const struct motion_sensor_t *s)
{
int ret = EC_SUCCESS;
-#ifdef CONFIG_ACCEL_FIFO_THRES
- /* Configure FIFO watermark level. */
- ret = st_write_data_with_mask(s, LIS2DW12_FIFO_CTRL_ADDR,
- LIS2DW12_FIFO_THRESHOLD_MASK, 1);
- if (ret != EC_SUCCESS)
- return ret;
+ if (IS_ENABLED(CONFIG_ACCEL_FIFO)) {
+ /* Configure FIFO watermark level. */
+ ret = st_write_data_with_mask(s, LIS2DW12_FIFO_CTRL_ADDR,
+ LIS2DW12_FIFO_THRESHOLD_MASK, 1);
+ if (ret != EC_SUCCESS)
+ return ret;
- /* Enable interrupt on FIFO watermask and route to int1. */
- ret = st_write_data_with_mask(s, LIS2DW12_INT1_FTH_ADDR,
- LIS2DW12_INT1_FTH_MASK, LIS2DW12_EN_BIT);
- if (ret != EC_SUCCESS)
- return ret;
-#endif /* CONFIG_ACCEL_FIFO */
+ /* Enable interrupt on FIFO watermark and route to int1. */
+ ret = st_write_data_with_mask(s, LIS2DW12_INT1_FTH_ADDR,
+ LIS2DW12_INT1_FTH_MASK, LIS2DW12_EN_BIT);
+ if (ret != EC_SUCCESS)
+ return ret;
+ }
-#ifdef CONFIG_GESTURE_SENSOR_DOUBLE_TAP
- /*
- * Configure D-TAP event detection on 3 axis.
- * For more details please refer to AN5038.
- */
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- LIS2DW12_TAP_THS_X_ADDR, 0x09);
- if (ret != EC_SUCCESS)
- return ret;
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- LIS2DW12_TAP_THS_Y_ADDR, 0x09);
- if (ret != EC_SUCCESS)
- return ret;
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- LIS2DW12_TAP_THS_Z_ADDR, 0xE9);
- if (ret != EC_SUCCESS)
- return ret;
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- LIS2DW12_INT_DUR_ADDR, 0x7F);
- if (ret != EC_SUCCESS)
- return ret;
+ if (IS_ENABLED(CONFIG_GESTURE_SENSOR_DOUBLE_TAP)) {
+ /*
+ * Configure D-TAP event detection on 3 axis.
+ * For more details please refer to AN5038.
+ */
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ LIS2DW12_TAP_THS_X_ADDR, 0x09);
+ if (ret != EC_SUCCESS)
+ return ret;
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ LIS2DW12_TAP_THS_Y_ADDR, 0x09);
+ if (ret != EC_SUCCESS)
+ return ret;
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ LIS2DW12_TAP_THS_Z_ADDR, 0xE9);
+ if (ret != EC_SUCCESS)
+ return ret;
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ LIS2DW12_INT_DUR_ADDR, 0x7F);
+ if (ret != EC_SUCCESS)
+ return ret;
- /* Enable D-TAP event detection. */
- ret = st_write_data_with_mask(s, LIS2DW12_WAKE_UP_THS_ADDR,
- LIS2DW12_SINGLE_DOUBLE_TAP,
- LIS2DW12_EN_BIT);
- if (ret != EC_SUCCESS)
- return ret;
+ /* Enable D-TAP event detection. */
+ ret = st_write_data_with_mask(s, LIS2DW12_WAKE_UP_THS_ADDR,
+ LIS2DW12_SINGLE_DOUBLE_TAP,
+ LIS2DW12_EN_BIT);
+ if (ret != EC_SUCCESS)
+ return ret;
- /*
- * Enable D-TAP detection on int_1 pad. In any case D-TAP event
- * can be detected only if ODR is over 200 Hz.
- */
- ret = st_write_data_with_mask(s, LIS2DW12_INT1_TAP_ADDR,
- LIS2DW12_INT1_DTAP_MASK,
- LIS2DW12_EN_BIT);
-#endif /* CONFIG_GESTURE_SENSOR_DOUBLE_TAP */
+ /*
+ * Enable D-TAP detection on int_1 pad. In any case D-TAP event
+ * can be detected only if ODR is over 200 Hz.
+ */
+ ret = st_write_data_with_mask(s, LIS2DW12_INT1_TAP_ADDR,
+ LIS2DW12_INT1_DTAP_MASK,
+ LIS2DW12_EN_BIT);
+ }
return ret;
}
+#ifdef LIS2DW12_ENABLE_FIFO
static void lis2dw12_handle_interrupt_for_fifo(uint32_t ts)
{
-#ifdef CONFIG_ACCEL_FIFO
- if (time_after(ts, last_interrupt_timestamp))
+ if (IS_ENABLED(CONFIG_ACCEL_FIFO) &&
+ time_after(ts, last_interrupt_timestamp))
last_interrupt_timestamp = ts;
-#endif
+
task_set_event(TASK_ID_MOTIONSENSE,
CONFIG_ACCEL_LIS2DW12_INT_EVENT, 0);
}
@@ -213,7 +216,8 @@ void lis2dw12_interrupt(enum gpio_signal signal)
/**
* lis2dw12_irq_handler - bottom half of the interrupt stack.
*/
-static int lis2dw12_irq_handler(struct motion_sensor_t *s, uint32_t *event)
+static int lis2dw12_irq_handler(struct motion_sensor_t *s,
+ uint32_t *event)
{
int ret = EC_SUCCESS;
@@ -222,20 +226,18 @@ static int lis2dw12_irq_handler(struct motion_sensor_t *s, uint32_t *event)
return EC_ERROR_NOT_HANDLED;
}
-#ifdef CONFIG_GESTURE_SENSOR_DOUBLE_TAP
- {
+ if (IS_ENABLED(CONFIG_GESTURE_SENSOR_DOUBLE_TAP)) {
int status = 0;
/* Read Status register to check TAP events. */
st_raw_read8(s->port, s->i2c_spi_addr_flags,
LIS2DW12_STATUS_TAP, &status);
if (status & LIS2DW12_DOUBLE_TAP)
- *event |= CONFIG_GESTURE_TAP_EVENT;
+ *event |= TASK_EVENT_MOTION_ACTIVITY_INTERRUPT(
+ MOTIONSENSE_ACTIVITY_DOUBLE_TAP);
}
-#endif /* CONFIG_GESTURE_SENSOR_DOUBLE_TAP */
-#ifdef CONFIG_ACCEL_FIFO
- {
+ if (IS_ENABLED(CONFIG_ACCEL_FIFO)) {
int nsamples;
uint32_t last_fifo_read_ts;
uint32_t triggering_interrupt_timestamp =
@@ -262,12 +264,10 @@ static int lis2dw12_irq_handler(struct motion_sensor_t *s, uint32_t *event)
triggering_interrupt_timestamp == last_interrupt_timestamp)
lis2dw12_handle_interrupt_for_fifo(last_fifo_read_ts);
}
-#endif /* CONFIG_ACCEL_FIFO */
return ret;
}
-
-#endif /* CONFIG_ACCEL_LIS2DW_AS_BASE */
+#endif
/**
* set_power_mode - set sensor power mode
@@ -324,27 +324,29 @@ static int set_range(const struct motion_sensor_t *s, int range, int rnd)
reg_val = LIS2DW12_FS_REG(newrange);
mutex_lock(s->mutex);
-#if defined(CONFIG_ACCEL_FIFO) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
/*
* FIFO stop collecting events. Restart FIFO in Bypass mode.
* If Range is changed all samples in FIFO must be discharged because
* with a different sensitivity.
*/
- err = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_BYPASS_MODE);
- if (err != EC_SUCCESS)
- goto unlock_rate;
-#endif /* CONFIG_ACCEL_FIFO && CONFIG_ACCEL_LIS2DW_AS_BASE */
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO)) {
+ err = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_BYPASS_MODE);
+ if (err != EC_SUCCESS)
+ goto unlock_rate;
+ }
err = st_write_data_with_mask(s, LIS2DW12_FS_ADDR, LIS2DW12_FS_MASK,
reg_val);
if (err == EC_SUCCESS)
data->base.range = newrange;
-#if defined(CONFIG_ACCEL_FIFO) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
+ else
+ goto unlock_rate;
+
/* FIFO restart collecting events in Cont. mode. */
- err = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_CONT_MODE);
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO))
+ err = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_CONT_MODE);
unlock_rate:
-#endif /* CONFIG_ACCEL_FIFO && CONFIG_ACCEL_LIS2DW_AS_BASE */
mutex_unlock(s->mutex);
return err;
@@ -387,12 +389,12 @@ static int set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
mutex_lock(s->mutex);
-#if defined(CONFIG_ACCEL_FIFO) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
/* FIFO stop collecting events. Restart FIFO in Bypass mode. */
- ret = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_BYPASS_MODE);
- if (ret != EC_SUCCESS)
- goto unlock_rate;
-#endif /* CONFIG_ACCEL_FIFO && CONFIG_ACCEL_LIS2DW_AS_BASE */
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO)) {
+ ret = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_BYPASS_MODE);
+ if (ret != EC_SUCCESS)
+ goto unlock_rate;
+ }
if (rate == 0) {
ret = st_write_data_with_mask(s, LIS2DW12_ACC_ODR_ADDR,
@@ -424,23 +426,22 @@ static int set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
* and it will always stay at high performance mode from initialization.
* But lis2dw12 needs switch low power mode according to odr value.
*/
-#ifndef CONFIG_ACCEL_LIS2DWL
- if (reg_val > LIS2DW12_ODR_200HZ_VAL)
- ret = set_power_mode(s, LIS2DW12_HIGH_PERF, 0);
- else
- ret = set_power_mode(s, LIS2DW12_LOW_POWER,
- LIS2DW12_LOW_POWER_MODE_2);
-#endif
+ if (!IS_ENABLED(CONFIG_ACCEL_LIS2DWL)) {
+ if (reg_val > LIS2DW12_ODR_200HZ_VAL)
+ ret = set_power_mode(s, LIS2DW12_HIGH_PERF, 0);
+ else
+ ret = set_power_mode(s, LIS2DW12_LOW_POWER,
+ LIS2DW12_LOW_POWER_MODE_2);
+ }
ret = st_write_data_with_mask(s, LIS2DW12_ACC_ODR_ADDR,
LIS2DW12_ACC_ODR_MASK, reg_val);
if (ret == EC_SUCCESS)
data->base.odr = normalized_rate;
-#if defined(CONFIG_ACCEL_FIFO) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
/* FIFO restart collecting events in continuous mode. */
- ret = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_CONT_MODE);
-#endif /* CONFIG_ACCEL_FIFO && CONFIG_ACCEL_LIS2DW_AS_BASE */
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO))
+ ret = lis2dw12_enable_fifo(s, LIS2DW12_FIFO_CONT_MODE);
unlock_rate:
mutex_unlock(s->mutex);
@@ -547,34 +548,34 @@ static int init(const struct motion_sensor_t *s)
if (ret != EC_SUCCESS)
goto err_unlock;
-#if defined(CONFIG_ACCEL_INTERRUPTS) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
/* Interrupt trigger level of power-on-reset is HIGH */
- if (!(MOTIONSENSE_FLAG_INT_ACTIVE_HIGH & s->flags)) {
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO) &&
+ !(MOTIONSENSE_FLAG_INT_ACTIVE_HIGH & s->flags)) {
ret = st_write_data_with_mask(s, LIS2DW12_H_ACTIVE_ADDR,
LIS2DW12_H_ACTIVE_MASK,
LIS2DW12_EN_BIT);
if (ret != EC_SUCCESS)
goto err_unlock;
}
-#endif
-#ifdef CONFIG_ACCEL_LIS2DWL
- /* lis2dwl supports 14 bit resolution only at high perfomance mode */
- ret = set_power_mode(s, LIS2DW12_HIGH_PERF, 0);
-#else
- /* Set default Mode and Low Power Mode. */
- ret = set_power_mode(s, LIS2DW12_LOW_POWER, LIS2DW12_LOW_POWER_MODE_2);
-#endif
+ if (IS_ENABLED(CONFIG_ACCEL_LIS2DWL))
+ /*
+ * lis2dwl supports 14 bit resolution only
+ * at high performance mode
+ */
+ ret = set_power_mode(s, LIS2DW12_HIGH_PERF, 0);
+ else
+ /* Set default Mode and Low Power Mode. */
+ ret = set_power_mode(s, LIS2DW12_LOW_POWER,
+ LIS2DW12_LOW_POWER_MODE_2);
if (ret != EC_SUCCESS)
goto err_unlock;
-#ifdef CONFIG_ACCEL_LIS2DW_AS_BASE
- if (IS_ENABLED(CONFIG_ACCEL_INTERRUPTS)) {
+ if (IS_ENABLED(LIS2DW12_ENABLE_FIFO)) {
ret = lis2dw12_config_interrupt(s);
if (ret != EC_SUCCESS)
goto err_unlock;
}
-#endif
mutex_unlock(s->mutex);
/* Set default resolution. */
@@ -597,7 +598,7 @@ const struct accelgyro_drv lis2dw12_drv = {
.get_data_rate = st_get_data_rate,
.set_offset = st_set_offset,
.get_offset = st_get_offset,
-#if defined(CONFIG_ACCEL_INTERRUPTS) && defined(CONFIG_ACCEL_LIS2DW_AS_BASE)
+#ifdef LIS2DW12_ENABLE_FIFO
.irq_handler = lis2dw12_irq_handler,
#endif /* CONFIG_ACCEL_INTERRUPTS && CONFIG_ACCEL_LIS2DW_AS_BASE */
};
diff --git a/driver/accelgyro_icm426xx.c b/driver/accelgyro_icm426xx.c
index 27d590b96e..b83c166084 100644
--- a/driver/accelgyro_icm426xx.c
+++ b/driver/accelgyro_icm426xx.c
@@ -909,11 +909,10 @@ static int icm426xx_init(const struct motion_sensor_t *s)
if (ret)
goto out_unlock;
-#ifdef CONFIG_ACCEL_INTERRUPTS
- ret = icm426xx_config_interrupt(s);
+ if (IS_ENABLED(CONFIG_ACCEL_INTERRUPTS))
+ ret = icm426xx_config_interrupt(s);
if (ret)
goto out_unlock;
-#endif
}
for (i = X; i <= Z; i++)
diff --git a/driver/accelgyro_lsm6dsm.c b/driver/accelgyro_lsm6dsm.c
index 64a1d22517..3383d36741 100644
--- a/driver/accelgyro_lsm6dsm.c
+++ b/driver/accelgyro_lsm6dsm.c
@@ -67,9 +67,7 @@ static inline enum dev_fifo get_fifo_type(const struct motion_sensor_t *s)
static enum dev_fifo map[] = {
FIFO_DEV_ACCEL,
FIFO_DEV_GYRO,
-#ifdef CONFIG_LSM6DSM_SEC_I2C
FIFO_DEV_MAG
-#endif /* CONFIG_LSM6DSM_SEC_I2C */
};
return map[s->type];
}
@@ -225,40 +223,44 @@ static int fifo_enable(const struct motion_sensor_t *accel)
LSM6DSM_FIFO_CTRL3_ADDR,
(decimators[FIFO_DEV_GYRO] << LSM6DSM_FIFO_DEC_G_OFF) |
(decimators[FIFO_DEV_ACCEL] << LSM6DSM_FIFO_DEC_XL_OFF));
-#ifdef CONFIG_LSM6DSM_SEC_I2C
- st_raw_write8(accel->port, accel->i2c_spi_addr_flags,
- LSM6DSM_FIFO_CTRL4_ADDR,
- decimators[FIFO_DEV_MAG]);
+ if (IS_ENABLED(CONFIG_LSM6DSM_SEC_I2C)) {
+ st_raw_write8(accel->port, accel->i2c_spi_addr_flags,
+ LSM6DSM_FIFO_CTRL4_ADDR,
+ decimators[FIFO_DEV_MAG]);
- /*
- * FIFO ODR is limited by odr of gyro or accel.
- * If we are sampling magnetometer faster than gyro or accel,
- * bump up ODR of accel. Thanks to decimation we will still measure at
- * the specified ODR.
- * Contrary to gyroscope, sampling faster will not affect measurements.
- * Set the ODR behind the back of set/get_data_rate.
- *
- * First samples after ODR changes must be thrown out [See
- * AN4987, section 3.9].
- * When increasing accel ODR, the FIFO is going to drop samples,
- * - except the first one after ODR change.
- * When decreasing accel ODR, we don't need to drop sample if
- * frequency is less than 52Hz.
- * At most, we need to drop one sample, but Android requirement specify
- * that chaning one sensor ODR should not affect other sensors.
- * Leave the bad sample alone, it will be a single glitch in the
- * accelerometer data stream.
- */
- if (max_odr > MAX(odrs[FIFO_DEV_ACCEL], odrs[FIFO_DEV_GYRO])) {
- st_write_data_with_mask(accel, LSM6DSM_ODR_REG(accel->type),
+ /*
+ * FIFO ODR is limited by odr of gyro or accel.
+ * If we are sampling magnetometer faster than gyro or accel,
+ * bump up ODR of accel. Thanks to decimation we will still
+ * measure at the specified ODR.
+ * Contrary to gyroscope, sampling faster will not affect
+ * measurements.
+ * Set the ODR behind the back of set/get_data_rate.
+ *
+ * First samples after ODR changes must be thrown out [See
+ * AN4987, section 3.9].
+ * When increasing accel ODR, the FIFO is going to drop samples,
+ * - except the first one after ODR change.
+ * When decreasing accel ODR, we don't need to drop sample if
+ * frequency is less than 52Hz.
+ * At most, we need to drop one sample, but Android requirement
+ * specify that changing one sensor ODR should not affect other
+ * sensors.
+ * Leave the bad sample alone, it will be a single glitch in the
+ * accelerometer data stream.
+ */
+ if (max_odr > MAX(odrs[FIFO_DEV_ACCEL], odrs[FIFO_DEV_GYRO])) {
+ st_write_data_with_mask(accel,
+ LSM6DSM_ODR_REG(accel->type),
LSM6DSM_ODR_MASK,
LSM6DSM_ODR_TO_REG(max_odr));
- } else {
- st_write_data_with_mask(accel, LSM6DSM_ODR_REG(accel->type),
+ } else {
+ st_write_data_with_mask(accel,
+ LSM6DSM_ODR_REG(accel->type),
LSM6DSM_ODR_MASK,
LSM6DSM_ODR_TO_REG(odrs[FIFO_DEV_ACCEL]));
+ }
}
-#endif /* CONFIG_MAG_LSM6DSM_LIS2MDL */
/*
* After ODR and decimation values are set, continuous mode can be
* enabled
@@ -347,13 +349,11 @@ static void push_fifo_data(struct motion_sensor_t *accel, uint8_t *fifo,
axis = s->raw_xyz;
/* Apply precision, sensitivity and rotation. */
-#ifdef CONFIG_MAG_LSM6DSM_LIS2MDL
- if (s->type == MOTIONSENSE_TYPE_MAG) {
+ if (IS_ENABLED(CONFIG_MAG_LSM6DSM_LIS2MDL) &&
+ (s->type == MOTIONSENSE_TYPE_MAG)) {
lis2mdl_normalize(s, axis, fifo);
rotate(axis, *s->rot_standard_ref, axis);
- } else
-#endif
- {
+ } else {
st_normalize(s, axis, fifo);
}
@@ -609,12 +609,12 @@ int lsm6dsm_set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
return EC_RES_INVALID_PARAM;
}
-#ifdef CONFIG_MAG_LSM6DSM_LIS2MDL
/*
* TODO(b:110143516) Improve data rate selection:
* Sensor is always running at 100Hz, even when not used.
*/
- if (s->type == MOTIONSENSE_TYPE_MAG) {
+ if (IS_ENABLED(CONFIG_MAG_LSM6DSM_LIS2MDL) &&
+ (s->type == MOTIONSENSE_TYPE_MAG)) {
struct mag_cal_t *cal = LIS2MDL_CAL(s);
init_mag_cal(cal);
@@ -631,9 +631,7 @@ int lsm6dsm_set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
cal->batch_size = 0;
CPRINTS("Batch size: %d", cal->batch_size);
mutex_lock(s->mutex);
- } else
-#endif
- {
+ } else {
mutex_lock(s->mutex);
ctrl_reg = LSM6DSM_ODR_REG(s->type);
ret = st_write_data_with_mask(s, ctrl_reg, LSM6DSM_ODR_MASK,
@@ -767,37 +765,37 @@ static int init(const struct motion_sensor_t *s)
if (ret != EC_SUCCESS)
goto err_unlock;
-#ifdef CONFIG_LSM6DSM_SEC_I2C
- /*
- * Reboot to reload memory content as pass-through mode can get
- * stuck.
- * Direct to the AN: See "AN4987 - LSM6DSM: always-on 3D
- * accelerometer and 3D gyroscope".
- */
-
- /* Power ON Accel. */
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- ctrl_reg, reg_val);
- if (ret != EC_SUCCESS)
- goto err_unlock;
+ if (IS_ENABLED(CONFIG_LSM6DSM_SEC_I2C)) {
+ /*
+ * Reboot to reload memory content as pass-through mode
+ * can get stuck.
+ * Direct to the AN: See "AN4987 - LSM6DSM: always-on 3D
+ * accelerometer and 3D gyroscope".
+ */
+
+ /* Power ON Accel. */
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ ctrl_reg, reg_val);
+ if (ret != EC_SUCCESS)
+ goto err_unlock;
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- LSM6DSM_CTRL3_ADDR, LSM6DSM_BOOT);
- if (ret != EC_SUCCESS)
- goto err_unlock;
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ LSM6DSM_CTRL3_ADDR, LSM6DSM_BOOT);
+ if (ret != EC_SUCCESS)
+ goto err_unlock;
- /*
- * Refer to AN4987, wait 15ms for accelerometer to doing full
- * reboot.
- */
- msleep(15);
+ /*
+ * Refer to AN4987, wait 15ms for accelerometer to doing
+ * full reboot.
+ */
+ msleep(15);
- /* Power OFF Accel. */
- ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
- ctrl_reg, 0);
- if (ret != EC_SUCCESS)
- goto err_unlock;
-#endif
+ /* Power OFF Accel. */
+ ret = st_raw_write8(s->port, s->i2c_spi_addr_flags,
+ ctrl_reg, 0);
+ if (ret != EC_SUCCESS)
+ goto err_unlock;
+ }
/*
* Output data not updated until have been read.
@@ -817,11 +815,10 @@ static int init(const struct motion_sensor_t *s)
goto err_unlock;
}
-#ifdef CONFIG_ACCEL_INTERRUPTS
- ret = config_interrupt(s);
+ if (IS_ENABLED(CONFIG_ACCEL_INTERRUPTS))
+ ret = config_interrupt(s);
if (ret != EC_SUCCESS)
goto err_unlock;
-#endif /* CONFIG_ACCEL_INTERRUPTS */
mutex_unlock(s->mutex);
}
diff --git a/driver/accelgyro_lsm6dsm.h b/driver/accelgyro_lsm6dsm.h
index 7be2219be0..add3104adf 100644
--- a/driver/accelgyro_lsm6dsm.h
+++ b/driver/accelgyro_lsm6dsm.h
@@ -184,12 +184,15 @@ enum dev_fifo {
FIFO_DEV_INVALID = -1,
FIFO_DEV_GYRO = 0,
FIFO_DEV_ACCEL,
-#ifdef CONFIG_LSM6DSM_SEC_I2C
FIFO_DEV_MAG,
-#endif
- FIFO_DEV_NUM,
};
+#ifdef CONFIG_LSM6DSM_SEC_I2C
+#define FIFO_DEV_NUM (FIFO_DEV_MAG + 1)
+#else
+#define FIFO_DEV_NUM (FIFO_DEV_ACCEL + 1)
+#endif
+
struct fstatus {
uint16_t len;
uint16_t pattern;
diff --git a/driver/accelgyro_lsm6dso.c b/driver/accelgyro_lsm6dso.c
index e8ea0794d7..7370ddff6b 100644
--- a/driver/accelgyro_lsm6dso.c
+++ b/driver/accelgyro_lsm6dso.c
@@ -22,6 +22,8 @@
#define CPRINTS(format, args...) cprints(CC_ACCEL, format, ## args)
STATIC_IF(CONFIG_ACCEL_FIFO) volatile uint32_t last_interrupt_timestamp;
+STATIC_IF(CONFIG_ACCEL_INTERRUPTS) int config_interrupt(
+ const struct motion_sensor_t *s);
/*
* When ODR change, the sensor filters need settling time;
@@ -468,11 +470,10 @@ static int init(const struct motion_sensor_t *s)
goto err_unlock;
}
-#ifdef CONFIG_ACCEL_INTERRUPTS
- ret = config_interrupt(s);
+ if (IS_ENABLED(CONFIG_ACCEL_INTERRUPTS))
+ ret = config_interrupt(s);
if (ret != EC_SUCCESS)
goto err_unlock;
-#endif /* CONFIG_ACCEL_INTERRUPTS */
mutex_unlock(s->mutex);
}