summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorWonjoon Lee <woojoo.lee@samsung.com>2016-05-27 00:31:40 +0900
committerchrome-bot <chrome-bot@chromium.org>2016-05-31 14:14:44 -0700
commit5564c9fae726b0f5042fb3474763b4da33cc145b (patch)
tree6ef96e435ab536f0535d3e36a1d4e2c3f13a1809
parent8f2c7d7f7670d696479e64daada86a9386bd1a31 (diff)
downloadchrome-ec-5564c9fae726b0f5042fb3474763b4da33cc145b.tar.gz
driver: Add support bma255 sensor
BMA255 is one of BMA2x2 accel sensor series. Adding defines,driver from https://github.com/BoschSensortec/BMA2x2_driver BUG=chrome-os-partner:52877 BRANCH=none TEST="accelread 2" is working on kevin, also check accelrate, accelrange can set proper value on IC Change-Id: I99932ff75aae91a744fe18dddc010b802085a2da Signed-off-by: Wonjoon Lee <woojoo.lee@samsung.com> Reviewed-on: https://chromium-review.googlesource.com/347722 Reviewed-by: Shawn N <shawnn@chromium.org>
-rw-r--r--common/build.mk1
-rw-r--r--driver/accel_bma2x2.c340
-rw-r--r--driver/accel_bma2x2.h161
-rw-r--r--driver/build.mk1
-rw-r--r--include/config.h1
-rw-r--r--include/ec_commands.h1
6 files changed, 505 insertions, 0 deletions
diff --git a/common/build.mk b/common/build.mk
index bfb4e6aef7..54696f4ef9 100644
--- a/common/build.mk
+++ b/common/build.mk
@@ -9,6 +9,7 @@
common-y=util.o
common-y+=version.o printf.o queue.o queue_policies.o
+common-$(CONFIG_ACCELGYRO_BMA255)+=math_util.o
common-$(CONFIG_ACCELGYRO_BMI160)+=math_util.o
common-$(CONFIG_ACCELGYRO_LSM6DS0)+=math_util.o
common-$(CONFIG_ACCEL_KXCJ9)+=math_util.o
diff --git a/driver/accel_bma2x2.c b/driver/accel_bma2x2.c
new file mode 100644
index 0000000000..89c3f9fa66
--- /dev/null
+++ b/driver/accel_bma2x2.c
@@ -0,0 +1,340 @@
+/* Copyright 2015 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.
+ */
+
+/*
+ * Bosch Accelerometer driver for Chrome EC
+ *
+ * Supported: BMA255
+ */
+
+#include "accelgyro.h"
+#include "common.h"
+#include "console.h"
+#include "driver/accel_bma2x2.h"
+#include "i2c.h"
+#include "math_util.h"
+#include "spi.h"
+#include "task.h"
+#include "util.h"
+
+#define CPUTS(outstr) cputs(CC_ACCEL, outstr)
+#define CPRINTF(format, args...) cprintf(CC_ACCEL, format, ## args)
+
+/* Number of times to attempt to enable sensor before giving up. */
+#define SENSOR_ENABLE_ATTEMPTS 5
+
+/*
+ * Struct for pairing an engineering value with the register value for a
+ * parameter.
+ */
+struct accel_param_pair {
+ int val; /* Value in engineering units. */
+ int reg; /* Corresponding register value. */
+};
+
+/* List of range values in +/-G's and their associated register values. */
+static const struct accel_param_pair ranges[] = {
+ {2, BMA2x2_RANGE_2G},
+ {4, BMA2x2_RANGE_4G},
+ {8, BMA2x2_RANGE_8G},
+ {16, BMA2x2_RANGE_16G},
+};
+
+/* List of ODR values in mHz and their associated register values. */
+static const struct accel_param_pair datarates[] = {
+ {781, BMA2x2_BW_7_81HZ},
+ {1563, BMA2x2_BW_15_63HZ},
+ {3125, BMA2x2_BW_31_25HZ},
+ {6250, BMA2x2_BW_62_50HZ},
+ {12500, BMA2x2_BW_125HZ},
+ {25000, BMA2x2_BW_250HZ},
+ {50000, BMA2x2_BW_500HZ},
+ {100000, BMA2x2_BW_1000HZ},
+};
+
+/**
+ * Find index into a accel_param_pair that matches the given engineering value
+ * passed in. The round_up flag is used to specify whether to round up or down.
+ * Note, this function always returns a valid index. If the request is
+ * outside the range of values, it returns the closest valid index.
+ */
+static int find_param_index(const int eng_val, const int round_up,
+ const struct accel_param_pair *pairs,
+ const int size)
+{
+ int i = 0;
+
+ /* match first index */
+ if (eng_val <= pairs[i].val)
+ return i;
+
+ /* Linear search for index to match. */
+ while (++i < size) {
+ if (eng_val < pairs[i].val)
+ return round_up ? i : i - 1;
+ else if (eng_val == pairs[i].val)
+ return i;
+ }
+
+ return i - 1;
+}
+
+/**
+ * Read register from accelerometer.
+ */
+static int raw_read8(const int port, const int addr, const int reg,
+ int *data_ptr)
+{
+ return i2c_read8(port, addr, reg, data_ptr);
+}
+
+/**
+ * Write register from accelerometer.
+ */
+static int raw_write8(const int port, const int addr, const int reg, int data)
+{
+ return i2c_write8(port, addr, reg, data);
+}
+
+static int raw_read_multi(const int port, int addr, uint8_t reg,
+ uint8_t *rxdata, int rxlen)
+{
+ int rv;
+
+ i2c_lock(port, 1);
+ rv = i2c_xfer(port, addr, &reg, 1, rxdata, rxlen,
+ I2C_XFER_SINGLE);
+ i2c_lock(port, 0);
+
+ return rv;
+}
+
+static int set_range(const struct motion_sensor_t *s, int range, int rnd)
+{
+ int ret, index, reg, range_val, reg_val, range_reg_val;
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ /* Find index for interface pair matching the specified range. */
+ index = find_param_index(range, rnd, ranges, ARRAY_SIZE(ranges));
+
+ reg = BMA2x2_RANGE_SELECT_REG;
+ range_val = ranges[index].reg;
+
+ mutex_lock(s->mutex);
+
+ /* Determine the new value of control reg and attempt to write it. */
+ ret = raw_read8(s->port, s->addr, reg, &range_reg_val);
+ if (ret != EC_SUCCESS) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+ reg_val = (range_reg_val & ~BMA2x2_RANGE_SELECT_MSK) | range_val;
+ ret = raw_write8(s->port, s->addr, reg, reg_val);
+
+ /* If successfully written, then save the range. */
+ if (ret == EC_SUCCESS)
+ data->sensor_range = index;
+
+ mutex_unlock(s->mutex);
+
+ return ret;
+}
+
+static int get_range(const struct motion_sensor_t *s)
+{
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ return ranges[data->sensor_range].val;
+}
+
+static int set_resolution(const struct motion_sensor_t *s, int res, int rnd)
+{
+ /* Only one resolution, BMA2x2_RESOLUTION, so nothing to do. */
+ return EC_SUCCESS;
+}
+
+static int get_resolution(const struct motion_sensor_t *s)
+{
+ return BMA2x2_RESOLUTION;
+}
+
+static int set_data_rate(const struct motion_sensor_t *s, int rate, int rnd)
+{
+ int ret, index, odr_val, odr_reg_val, reg_val, reg;
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ /* Find index for interface pair matching the specified rate. */
+ index = find_param_index(rate, rnd, datarates, ARRAY_SIZE(datarates));
+
+ odr_val = datarates[index].reg;
+ reg = BMA2x2_BW_REG;
+
+ mutex_lock(s->mutex);
+
+ /* Determine the new value of control reg and attempt to write it. */
+ ret = raw_read8(s->port, s->addr, reg, &odr_reg_val);
+ if (ret != EC_SUCCESS) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+ reg_val = (odr_reg_val & ~BMA2x2_BW_MSK) | odr_val;
+ /* Set output data rate. */
+ ret = raw_write8(s->port, s->addr, reg, reg_val);
+
+ /* If successfully written, then save the new data rate. */
+ if (ret == EC_SUCCESS)
+ data->sensor_datarate = index;
+
+ mutex_unlock(s->mutex);
+ return ret;
+}
+
+static int get_data_rate(const struct motion_sensor_t *s)
+{
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ return datarates[data->sensor_datarate].val;
+}
+
+static int set_offset(const struct motion_sensor_t *s, const int16_t *offset,
+ int16_t temp)
+{
+ /* temperature is ignored */
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ data->offset[X] = offset[X];
+ data->offset[Y] = offset[Y];
+ data->offset[Z] = offset[Z];
+
+ return EC_SUCCESS;
+}
+
+static int get_offset(const struct motion_sensor_t *s, int16_t *offset,
+ int16_t *temp)
+{
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ offset[X] = data->offset[X];
+ offset[Y] = data->offset[Y];
+ offset[Z] = data->offset[Z];
+ *temp = EC_MOTION_SENSE_INVALID_CALIB_TEMP;
+
+ return EC_SUCCESS;
+}
+
+static int read(const struct motion_sensor_t *s, vector_3_t v)
+{
+ uint8_t acc[6];
+ int ret, i, range;
+ struct bma2x2_accel_data *data = s->drv_data;
+
+ /* Read 6 bytes starting at X_AXIS_LSB. */
+ mutex_lock(s->mutex);
+ ret = raw_read_multi(s->port, s->addr, BMA2x2_X_AXIS_LSB_ADDR, acc, 6);
+ mutex_unlock(s->mutex);
+
+ if (ret != EC_SUCCESS)
+ return ret;
+
+ /*
+ * Convert acceleration to a signed 16-bit number. Note, based on
+ * the order of the registers:
+ *
+ * acc[0] = X_AXIS_LSB -> bit 7~4 for value, bit 0 for new data bit
+ * acc[1] = X_AXIS_MSB
+ * acc[2] = Y_AXIS_LSB -> bit 7~4 for value, bit 0 for new data bit
+ * acc[3] = Y_AXIS_MSB
+ * acc[4] = Z_AXIS_LSB -> bit 7~4 for value, bit 0 for new data bit
+ * acc[5] = Z_AXIS_MSB
+ *
+ * Add calibration offset before returning the data.
+ */
+ for (i = X; i <= Z; i++)
+ v[i] = (((int8_t)acc[i * 2 + 1]) << 8) | (acc[i * 2] & 0xf0);
+ rotate(v, *s->rot_standard_ref, v);
+
+ /* apply offset in the device coordinates */
+ range = get_range(s);
+ for (i = X; i <= Z; i++)
+ v[i] += (data->offset[i] << 5) / range;
+
+ return EC_SUCCESS;
+}
+
+static int init(const struct motion_sensor_t *s)
+{
+ int ret = 0, tries = 0, val, reg, reset_field;
+
+ ret = raw_read8(s->port, s->addr, BMA2x2_CHIP_ID_ADDR, &val);
+ if (ret)
+ return EC_ERROR_UNKNOWN;
+
+ if (val != BMA255_CHIP_ID_MAJOR)
+ return EC_ERROR_ACCESS_DENIED;
+
+ /* Reset the chip to be in a good state */
+ reg = BMA2x2_RST_ADDR;
+ reset_field = BMA2x2_CMD_SOFT_RESET;
+
+ mutex_lock(s->mutex);
+
+ ret = raw_read8(s->port, s->addr, reg, &val);
+ if (ret != EC_SUCCESS) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+ val |= reset_field;
+ ret = raw_write8(s->port, s->addr, reg, val);
+ if (ret != EC_SUCCESS) {
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+
+ /* The SRST will be cleared when reset is complete. */
+ do {
+ ret = raw_read8(s->port, s->addr, reg, &val);
+
+ /* Reset complete. */
+ if ((ret == EC_SUCCESS) && !(val & reset_field))
+ break;
+
+ /* Check for tires. */
+ if (tries++ > SENSOR_ENABLE_ATTEMPTS) {
+ ret = EC_ERROR_TIMEOUT;
+ mutex_unlock(s->mutex);
+ return ret;
+ }
+ msleep(1);
+ } while (1);
+ mutex_unlock(s->mutex);
+
+ /* Initialize with the desired parameters. */
+ ret = set_range(s, s->default_range, 1);
+ if (ret != EC_SUCCESS)
+ return ret;
+
+ ret = set_resolution(s, 12, 1);
+ if (ret != EC_SUCCESS)
+ return ret;
+
+ CPRINTF("[%T %s: Done Init type:0x%X range:%d]\n",
+ s->name, s->type, get_range(s));
+
+ return ret;
+}
+
+const struct accelgyro_drv bma2x2_accel_drv = {
+ .init = init,
+ .read = read,
+ .set_range = set_range,
+ .get_range = get_range,
+ .set_resolution = set_resolution,
+ .get_resolution = get_resolution,
+ .set_data_rate = set_data_rate,
+ .get_data_rate = get_data_rate,
+ .set_offset = set_offset,
+ .get_offset = get_offset,
+ .perform_calib = NULL,
+};
diff --git a/driver/accel_bma2x2.h b/driver/accel_bma2x2.h
new file mode 100644
index 0000000000..f5facc90e9
--- /dev/null
+++ b/driver/accel_bma2x2.h
@@ -0,0 +1,161 @@
+/* Copyright 2016 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.
+ */
+
+/* BMA2x2 gsensor module for Chrome EC */
+
+#ifndef __CROS_EC_ACCEL_BMA2x2_H
+#define __CROS_EC_ACCEL_BMA2x2_H
+
+enum bma2x2_accel {
+ BMA255,
+ SUPPORTED_BOSCH_ACCELS,
+};
+
+struct bma2x2_accel_data {
+ /* Variant of Bosch Accelerometer. */
+ uint8_t variant;
+ /* Note, the following are indicies into their respective tables. */
+ /* Current range of accelerometer. */
+ int sensor_range;
+ /* Current output data rate of accelerometer. */
+ int sensor_datarate;
+ /* Current resolution of accelerometer. */
+ int sensor_resolution;
+ /* Device address. */
+ int accel_addr;
+ int16_t offset[3];
+};
+
+extern const struct accelgyro_drv bma2x2_accel_drv;
+
+/* I2C ADDRESS DEFINITIONS */
+/* The following definition of I2C address is used for the following sensors
+* BMA255
+* BMA355
+* BMA280
+* BMA282
+* BMA223
+* BMA254
+* BMA284
+* BMA250E
+* BMA222E
+*/
+#define BMA2x2_I2C_ADDR1 0x30
+#define BMA2x2_I2C_ADDR2 0x19
+
+/* The following definition of I2C address is used for the following sensors
+* BMC150
+* BMC056
+* BMC156
+*/
+#define BMA2x2_I2C_ADDR3 0x10
+#define BMA2x2_I2C_ADDR4 0x11
+
+/*** Chip-specific registers ***/
+/* REGISTER ADDRESS DEFINITIONS */
+#define BMA2x2_EEP_OFFSET 0x16
+#define BMA2x2_IMAGE_BASE 0x38
+#define BMA2x2_IMAGE_LEN 22
+#define BMA2x2_CHIP_ID_ADDR 0x00
+#define BMA255_CHIP_ID_MAJOR 0xfa
+
+/* DATA ADDRESS DEFINITIONS */
+#define BMA2x2_X_AXIS_LSB_ADDR 0x02
+#define BMA2x2_X_AXIS_MSB_ADDR 0x03
+#define BMA2x2_Y_AXIS_LSB_ADDR 0x04
+#define BMA2x2_Y_AXIS_MSB_ADDR 0x05
+#define BMA2x2_Z_AXIS_LSB_ADDR 0x06
+#define BMA2x2_Z_AXIS_MSB_ADDR 0x07
+#define BMA2x2_TEMP_ADDR 0x08
+
+/* STATUS ADDRESS DEFINITIONS */
+#define BMA2x2_STAT1_ADDR 0x09
+#define BMA2x2_STAT2_ADDR 0x0A
+#define BMA2x2_STAT_TAP_SLOPE_ADDR 0x0B
+#define BMA2x2_STAT_ORIENT_HIGH_ADDR 0x0C
+#define BMA2x2_STAT_FIFO_ADDR 0x0E
+#define BMA2x2_RANGE_SELECT_ADDR 0x0F
+#define BMA2x2_BW_SELECT_ADDR 0x10
+#define BMA2x2_MODE_CTRL_ADDR 0x11
+#define BMA2x2_LOW_NOISE_CTRL_ADDR 0x12
+#define BMA2x2_DATA_CTRL_ADDR 0x13
+#define BMA2x2_RST_ADDR 0x14
+#define BMA2x2_CMD_SOFT_RESET 0xb6
+
+/* INTERRUPT ADDRESS DEFINITIONS */
+#define BMA2x2_INTR_ENABLE1_ADDR 0x16
+#define BMA2x2_INTR_ENABLE2_ADDR 0x17
+#define BMA2x2_INTR_SLOW_NO_MOTION_ADDR 0x18
+#define BMA2x2_INTR1_PAD_SELECT_ADDR 0x19
+#define BMA2x2_INTR_DATA_SELECT_ADDR 0x1A
+#define BMA2x2_INTR2_PAD_SELECT_ADDR 0x1B
+#define BMA2x2_INTR_SOURCE_ADDR 0x1E
+#define BMA2x2_INTR_SET_ADDR 0x20
+#define BMA2x2_INTR_CTRL_ADDR 0x21
+
+/* FEATURE ADDRESS DEFINITIONS */
+#define BMA2x2_LOW_DURN_ADDR 0x22
+#define BMA2x2_LOW_THRES_ADDR 0x23
+#define BMA2x2_LOW_HIGH_HYST_ADDR 0x24
+#define BMA2x2_HIGH_DURN_ADDR 0x25
+#define BMA2x2_HIGH_THRES_ADDR 0x26
+#define BMA2x2_SLOPE_DURN_ADDR 0x27
+#define BMA2x2_SLOPE_THRES_ADDR 0x28
+#define BMA2x2_SLOW_NO_MOTION_THRES_ADDR 0x29
+#define BMA2x2_TAP_PARAM_ADDR 0x2A
+#define BMA2x2_TAP_THRES_ADDR 0x2B
+#define BMA2x2_ORIENT_PARAM_ADDR 0x2C
+#define BMA2x2_THETA_BLOCK_ADDR 0x2D
+#define BMA2x2_THETA_FLAT_ADDR 0x2E
+#define BMA2x2_FLAT_HOLD_TIME_ADDR 0x2F
+#define BMA2x2_SELFTEST_ADDR 0x32
+#define BMA2x2_EEPROM_CTRL_ADDR 0x33
+#define BMA2x2_SERIAL_CTRL_ADDR 0x34
+
+/* OFFSET ADDRESS DEFINITIONS */
+#define BMA2x2_OFFSET_CTRL_ADDR 0x36
+#define BMA2x2_OFFSET_PARAMS_ADDR 0x37
+#define BMA2x2_OFFSET_X_AXIS_ADDR 0x38
+#define BMA2x2_OFFSET_Y_AXIS_ADDR 0x39
+#define BMA2x2_OFFSET_Z_AXIS_ADDR 0x3A
+
+/* GP ADDRESS DEFINITIONS */
+#define BMA2x2_GP0_ADDR 0x3B
+#define BMA2x2_GP1_ADDR 0x3C
+
+/* FIFO ADDRESS DEFINITIONS */
+#define BMA2x2_FIFO_MODE_ADDR 0x3E
+#define BMA2x2_FIFO_DATA_OUTPUT_ADDR 0x3F
+#define BMA2x2_FIFO_WML_TRIG 0x30
+
+/* RANGE */
+#define BMA2x2_RANGE_SELECT_POS 0
+#define BMA2x2_RANGE_SELECT_LEN 4
+#define BMA2x2_RANGE_SELECT_MSK 0x0F
+#define BMA2x2_RANGE_SELECT_REG BMA2x2_RANGE_SELECT_ADDR
+
+#define BMA2x2_RANGE_2G 3
+#define BMA2x2_RANGE_4G 5
+#define BMA2x2_RANGE_8G 8
+#define BMA2x2_RANGE_16G 12
+
+/* Sensor resolution in number of bits. This sensor has fixed resolution. */
+#define BMA2x2_RESOLUTION 12
+
+/* BANDWIDTH */
+#define BMA2x2_BW_POS 0
+#define BMA2x2_BW_LEN 5
+#define BMA2x2_BW_MSK 0x1F
+#define BMA2x2_BW_REG BMA2x2_BW_SELECT_ADDR
+
+#define BMA2x2_BW_7_81HZ 0x08 /* LowPass 7.81HZ */
+#define BMA2x2_BW_15_63HZ 0x09 /* LowPass 15.63HZ */
+#define BMA2x2_BW_31_25HZ 0x0A /* LowPass 31.25HZ */
+#define BMA2x2_BW_62_50HZ 0x0B /* LowPass 62.50HZ */
+#define BMA2x2_BW_125HZ 0x0C /* LowPass 125HZ */
+#define BMA2x2_BW_250HZ 0x0D /* LowPass 250HZ */
+#define BMA2x2_BW_500HZ 0x0E /* LowPass 500HZ */
+#define BMA2x2_BW_1000HZ 0x0F /* LowPass 1000HZ */
+#endif /* __CROS_EC_ACCEL_BMA2x2_H */
diff --git a/driver/build.mk b/driver/build.mk
index fc571af018..6145bfbd22 100644
--- a/driver/build.mk
+++ b/driver/build.mk
@@ -7,6 +7,7 @@
#
# Accelerometers
+driver-$(CONFIG_ACCEL_BMA255)+=accel_bma2x2.o
driver-$(CONFIG_ACCEL_KXCJ9)+=accel_kionix.o
driver-$(CONFIG_ACCEL_KX022)+=accel_kionix.o
driver-$(CONFIG_ACCELGYRO_LSM6DS0)+=accelgyro_lsm6ds0.o
diff --git a/include/config.h b/include/config.h
index 2c4fa6ccc4..0addbc1a1e 100644
--- a/include/config.h
+++ b/include/config.h
@@ -51,6 +51,7 @@
#undef CONFIG_ACCEL_FORCE_MODE_MASK
/* Specify type of accelerometers attached. */
+#undef CONFIG_ACCEL_BMA255
#undef CONFIG_ACCEL_KXCJ9
#undef CONFIG_ACCEL_KX022
#undef CONFIG_ACCELGYRO_LSM6DS0
diff --git a/include/ec_commands.h b/include/ec_commands.h
index 871dbf9662..d58c560d62 100644
--- a/include/ec_commands.h
+++ b/include/ec_commands.h
@@ -1788,6 +1788,7 @@ enum motionsensor_chip {
MOTIONSENSE_CHIP_SI1143 = 5,
MOTIONSENSE_CHIP_KX022 = 6,
MOTIONSENSE_CHIP_L3GD20H = 7,
+ MOTIONSENSE_CHIP_BMA255 = 8,
};
struct ec_response_motion_sensor_data {