summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--board/amenia/board.c37
-rw-r--r--board/amenia/board.h3
-rw-r--r--board/reef/board.c36
-rw-r--r--board/reef/board.h7
-rw-r--r--driver/baro_bmp280.c383
-rw-r--r--driver/baro_bmp280.h205
-rw-r--r--driver/build.mk3
-rw-r--r--include/config.h3
-rw-r--r--include/ec_commands.h2
9 files changed, 678 insertions, 1 deletions
diff --git a/board/amenia/board.c b/board/amenia/board.c
index 4432421c18..7026903ab1 100644
--- a/board/amenia/board.c
+++ b/board/amenia/board.c
@@ -17,6 +17,7 @@
#include "driver/accel_kionix.h"
#include "driver/accel_kx022.h"
#include "driver/accelgyro_bmi160.h"
+#include "driver/baro_bmp280.h"
#include "driver/charger/bd99955.h"
#include "driver/tcpm/anx74xx.h"
#include "driver/tcpm/tcpci.h"
@@ -596,6 +597,42 @@ struct motion_sensor_t motion_sensors[] = {
},
},
},
+
+ [BASE_BARO] = {
+ .name = "Base Baro",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_BMP280,
+ .type = MOTIONSENSE_TYPE_BARO,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &bmp280_drv,
+ .drv_data = &bmp280_drv_data,
+ .port = I2C_PORT_BARO,
+ .addr = BMP280_I2C_ADDRESS1,
+ .rot_standard_ref = NULL, /* Identity Matrix. */
+ .config = {
+ /* AP: by default shutdown all sensors */
+ [SENSOR_CONFIG_AP] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* EC does not need in S0 */
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ },
+ },
+
};
const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
diff --git a/board/amenia/board.h b/board/amenia/board.h
index 6485b8d591..8ea3b42315 100644
--- a/board/amenia/board.h
+++ b/board/amenia/board.h
@@ -21,6 +21,7 @@
#define CONFIG_ALS
#define CONFIG_ALS_ISL29035
#define CONFIG_BACKLIGHT_LID
+#define CONFIG_BARO_BMP280
#define CONFIG_BATTERY_CUT_OFF
#define CONFIG_BATTERY_PRESENT_CUSTOM
#define CONFIG_BATTERY_SMART
@@ -149,6 +150,7 @@
#define I2C_PORT_ACCELGYRO NPCX_I2C_PORT1
#define I2C_PORT_ALS NPCX_I2C_PORT2
#define I2C_PORT_ACCEL NPCX_I2C_PORT2
+#define I2C_PORT_BARO NPCX_I2C_PORT2
#define I2C_PORT_BATTERY NPCX_I2C_PORT3
#define I2C_PORT_CHARGER NPCX_I2C_PORT3
#define I2C_PORT_THERMAL NPCX_I2C_PORT3
@@ -210,6 +212,7 @@ enum sensor_id {
LID_GYRO,
LID_MAG,
BASE_ACCEL,
+ BASE_BARO,
};
/* start as a sink in case we have no other power supply/battery */
diff --git a/board/reef/board.c b/board/reef/board.c
index 4cfc582184..ce77746533 100644
--- a/board/reef/board.c
+++ b/board/reef/board.c
@@ -18,6 +18,7 @@
#include "driver/accel_kionix.h"
#include "driver/accel_kx022.h"
#include "driver/accelgyro_bmi160.h"
+#include "driver/baro_bmp280.h"
#include "driver/charger/bd99955.h"
#include "driver/tcpm/anx74xx.h"
#include "driver/tcpm/ps8751.h"
@@ -820,6 +821,41 @@ struct motion_sensor_t motion_sensors[] = {
},
},
},
+
+ [BASE_BARO] = {
+ .name = "Base Baro",
+ .active_mask = SENSOR_ACTIVE_S0,
+ .chip = MOTIONSENSE_CHIP_BMP280,
+ .type = MOTIONSENSE_TYPE_BARO,
+ .location = MOTIONSENSE_LOC_BASE,
+ .drv = &bmp280_drv,
+ .drv_data = &bmp280_drv_data,
+ .port = I2C_PORT_BARO,
+ .addr = BMP280_I2C_ADDRESS1,
+ .rot_standard_ref = NULL, /* Identity Matrix. */
+ .config = {
+ /* AP: by default shutdown all sensors */
+ [SENSOR_CONFIG_AP] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* EC does not need in S0 */
+ [SENSOR_CONFIG_EC_S0] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S3] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ /* Sensor off in S3/S5 */
+ [SENSOR_CONFIG_EC_S5] = {
+ .odr = 0,
+ .ec_rate = 0,
+ },
+ },
+ },
};
const unsigned int motion_sensor_count = ARRAY_SIZE(motion_sensors);
diff --git a/board/reef/board.h b/board/reef/board.h
index 0be463d22c..a67c48abb3 100644
--- a/board/reef/board.h
+++ b/board/reef/board.h
@@ -17,6 +17,9 @@
*/
#define CONFIG_SYSTEM_UNLOCKED
+/* EC console commands */
+#define CONFIG_CMD_ACCELS
+
/* Battery */
#define CONFIG_BATTERY_CUT_OFF
#define CONFIG_BATTERY_PRESENT_CUSTOM
@@ -135,6 +138,7 @@
#define I2C_PORT_GYRO NPCX_I2C_PORT1
#define I2C_PORT_LID_ACCEL NPCX_I2C_PORT2
#define I2C_PORT_ALS NPCX_I2C_PORT2
+#define I2C_PORT_BARO NPCX_I2C_PORT2
#define I2C_PORT_BATTERY NPCX_I2C_PORT3
#define I2C_PORT_CHARGER NPCX_I2C_PORT3
@@ -154,7 +158,7 @@
#define CONFIG_ALS
#define CONFIG_ALS_OPT3001
#define OPT3001_I2C_ADDR OPT3001_I2C_ADDR1
-/* FIXME: Need to add BMP280 barometer */
+#define CONFIG_BARO_BMP280
/* #define CONFIG_LID_ANGLE */ /* FIXME(dhendrix): maybe? */
/* #define CONFIG_LID_ANGLE_SENSOR_BASE 0 */ /* FIXME(dhendrix): maybe? */
/* #define CONFIG_LID_ANGLE_SENSOR_LID 2 */ /* FIXME(dhendrix): maybe? */
@@ -214,6 +218,7 @@ enum sensor_id {
BASE_GYRO,
BASE_MAG,
LID_ACCEL,
+ BASE_BARO,
};
enum reef_board_version {
diff --git a/driver/baro_bmp280.c b/driver/baro_bmp280.c
new file mode 100644
index 0000000000..b568407265
--- /dev/null
+++ b/driver/baro_bmp280.c
@@ -0,0 +1,383 @@
+/* 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.
+ */
+/*
+****************************************************************************
+* Copyright (C) 2012 - 2015 Bosch Sensortec GmbH
+*
+* File : bmp280.h
+*
+* Date : 2015/03/27
+*
+* Revision : 2.0.4(Pressure and Temperature compensation code revision is 1.1)
+*
+* Usage: Sensor Driver for BMP280 sensor
+*
+****************************************************************************
+*
+* \section License
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* Redistributions in binary form must reproduce the above copyright
+* notice, this list of conditions and the following disclaimer in the
+* documentation and/or other materials provided with the distribution.
+*
+* Neither the name of the copyright holder nor the names of the
+* contributors may be used to endorse or promote products derived from
+* this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+* OR CONTRIBUTORS BE LIABLE FOR ANY
+* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS
+* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+*
+* The information provided is believed to be accurate and reliable.
+* The copyright holder assumes no responsibility
+* for the consequences of use
+* of such information nor for any infringement of patents or
+* other rights of third parties which may result from its use.
+* No license is granted by implication or otherwise under any patent or
+* patent rights of the copyright holder.
+**************************************************************************/
+#include "accelgyro.h"
+#include "common.h"
+#include "console.h"
+#include "driver/baro_bmp280.h"
+#include "i2c.h"
+#include "timer.h"
+
+#define CPRINTF(format, args...) cprintf(CC_ACCEL, format, ## args)
+#define CPRINTS(format, args...) cprints(CC_ACCEL, format, ## args)
+
+static const int standby_durn[] = {1, 63, 125, 250, 500, 1000, 2000, 4000};
+
+static inline int raw_read8(const int port, const int addr, const uint8_t reg,
+ int *data_ptr)
+{
+ return i2c_read8(port, addr, reg, data_ptr);
+}
+
+/*
+ * Read n bytes from barometer.
+ */
+static inline int raw_read_n(const int port, const int addr, const uint8_t reg,
+ uint8_t *data_ptr, const int len)
+{
+ int rv;
+
+ i2c_lock(port, 1);
+ rv = i2c_xfer(port, addr, &reg, 1,
+ data_ptr, len, I2C_XFER_SINGLE);
+ i2c_lock(port, 0);
+ return rv;
+}
+
+/*
+ * Write 8bit register from accelerometer.
+ */
+static inline int raw_write8(const int port, const int addr, const uint8_t reg,
+ int data)
+{
+ return i2c_write8(port, addr, reg, data);
+}
+
+
+/*
+ * This function is used to get calibration parameters used for
+ * calculation in the registers
+ *
+ * parameter | Register address | bit
+ *------------|------------------|----------------
+ * dig_T1 | 0x88 and 0x89 | from 0 : 7 to 8: 15
+ * dig_T2 | 0x8A and 0x8B | from 0 : 7 to 8: 15
+ * dig_T3 | 0x8C and 0x8D | from 0 : 7 to 8: 15
+ * dig_P1 | 0x8E and 0x8F | from 0 : 7 to 8: 15
+ * dig_P2 | 0x90 and 0x91 | from 0 : 7 to 8: 15
+ * dig_P3 | 0x92 and 0x93 | from 0 : 7 to 8: 15
+ * dig_P4 | 0x94 and 0x95 | from 0 : 7 to 8: 15
+ * dig_P5 | 0x96 and 0x97 | from 0 : 7 to 8: 15
+ * dig_P6 | 0x98 and 0x99 | from 0 : 7 to 8: 15
+ * dig_P7 | 0x9A and 0x9B | from 0 : 7 to 8: 15
+ * dig_P8 | 0x9C and 0x9D | from 0 : 7 to 8: 15
+ * dig_P9 | 0x9E and 0x9F | from 0 : 7 to 8: 15
+ *
+ * @return results of bus communication function
+ * @retval 0 -> Success
+ *
+ */
+
+static int bmp280_get_calib_param(const struct motion_sensor_t *s)
+{
+ int ret;
+
+ uint8_t a_data_u8[BMP280_CALIB_DATA_SIZE] = {0};
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+
+ ret = raw_read_n(s->port, s->addr,
+ BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG,
+ a_data_u8, BMP280_CALIB_DATA_SIZE);
+
+ if (ret)
+ return ret;
+
+ /* read calibration values*/
+ data->calib_param.dig_T1 = (a_data_u8[1] << 8) | a_data_u8[0];
+ data->calib_param.dig_T2 = (a_data_u8[3] << 8 | a_data_u8[2]);
+ data->calib_param.dig_T3 = (a_data_u8[5] << 8) | a_data_u8[4];
+
+ data->calib_param.dig_P1 = (a_data_u8[7] << 8) | a_data_u8[6];
+ data->calib_param.dig_P2 = (a_data_u8[9] << 8) | a_data_u8[8];
+ data->calib_param.dig_P3 = (a_data_u8[11] << 8) | a_data_u8[10];
+ data->calib_param.dig_P4 = (a_data_u8[13] << 8) | a_data_u8[12];
+ data->calib_param.dig_P5 = (a_data_u8[15] << 8) | a_data_u8[14];
+ data->calib_param.dig_P6 = (a_data_u8[17] << 8) | a_data_u8[16];
+ data->calib_param.dig_P7 = (a_data_u8[19] << 8) | a_data_u8[18];
+ data->calib_param.dig_P8 = (a_data_u8[21] << 8) | a_data_u8[20];
+ data->calib_param.dig_P9 = (a_data_u8[23] << 8) | a_data_u8[22];
+
+ return EC_SUCCESS;
+}
+
+static int bmp280_read_uncomp_pressure(const struct motion_sensor_t *s,
+ int *uncomp_pres)
+{
+ int ret;
+ uint8_t a_data_u8[BMP280_PRESSURE_DATA_SIZE] = {0};
+
+ ret = raw_read_n(s->port, s->addr,
+ BMP280_PRESSURE_MSB_REG,
+ a_data_u8, BMP280_PRESSURE_DATA_SIZE);
+
+ if (ret)
+ return ret;
+
+ *uncomp_pres = (int32_t)((a_data_u8[0] << 12) |
+ (a_data_u8[1] << 4) |
+ (a_data_u8[2] >> 4));
+
+ return EC_SUCCESS;
+}
+
+/*
+ * Reads actual pressure from uncompensated pressure
+ * and returns the value in Pascal(Pa)
+ * @note Output value of "96386" equals 96386 Pa =
+ * 963.86 hPa = 963.86 millibar
+ *
+ * Algorithm from BMP280 Datasheet Rev 1.15 Section 8.2
+ *
+ */
+static int bmp280_compensate_pressure(const struct motion_sensor_t *s,
+ int uncomp_pressure)
+{
+ int var1, var2;
+ uint32_t p;
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+
+ /* calculate x1 */
+ var1 = (((int32_t)data->calib_param.t_fine)
+ >> 1) - 64000;
+ /* calculate x2 */
+ var2 = (((var1 >> 2) * (var1 >> 2)) >> 11)
+ * ((int32_t)data->calib_param.dig_P6);
+ var2 = var2 + ((var1 * ((int32_t)data->calib_param.dig_P5)) << 1);
+ var2 = (var2 >> 2) + (((int32_t)data->calib_param.dig_P4) << 16);
+ /* calculate x1 */
+ var1 = (((data->calib_param.dig_P3 *
+ (((var1 >> 2) * (var1 >> 2)) >> 13)) >> 3) +
+ ((((int32_t)data->calib_param.dig_P2) * var1) >> 1)) >> 18;
+ var1 = ((((32768 + var1)) *
+ ((int32_t)data->calib_param.dig_P1)) >> 15);
+
+ /* Avoid exception caused by division by zero */
+ if (!var1)
+ return 0;
+
+ /* calculate pressure */
+ p = (((uint32_t)((1048576) - uncomp_pressure) -
+ (var2 >> 12))) * 3125;
+
+ /* check overflow */
+ if (p < 0x80000000)
+ p = (p << 1) / ((uint32_t)var1);
+ else
+ p = (p / (uint32_t)var1) << 1;
+
+ /* calculate x1 */
+ var1 = (((int32_t)data->calib_param.dig_P9) *
+ ((int32_t)(((p >> 3) * (p >> 3)) >> 13))) >> 12;
+ /* calculate x2 */
+ var2 = (((int32_t)(p >> 2)) *
+ ((int32_t)data->calib_param.dig_P8)) >> 13;
+ /* calculate true pressure */
+ return (uint32_t)((int32_t)p + ((var1 + var2 +
+ data->calib_param.dig_P7) >> 4));
+}
+
+/*
+ * Set the standby duration
+ * standby_durn: The standby duration time value.
+ * value | standby duration
+ * ----------|--------------------
+ * 0x00 | 1_MS
+ * 0x01 | 63_MS
+ * 0x02 | 125_MS
+ * 0x03 | 250_MS
+ * 0x04 | 500_MS
+ * 0x05 | 1000_MS
+ * 0x06 | 2000_MS
+ * 0x07 | 4000_MS
+ */
+static int bmp280_set_standby_durn(const struct motion_sensor_t *s,
+ uint8_t durn)
+{
+ int ret, val;
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+
+ ret = raw_read8(s->port, s->addr,
+ BMP280_CONFIG_REG, &val);
+
+ if (ret == EC_SUCCESS) {
+ val = (val & 0xE0) | ((durn << 5) & 0xE0);
+ /* write the standby duration*/
+ ret = raw_write8(s->port, s->addr,
+ BMP280_CONFIG_REG, val);
+ }
+
+ data->rate = standby_durn[durn] + BMP280_COMPUTE_TIME;
+ return ret;
+}
+
+static int bmp280_set_power_mode(const struct motion_sensor_t *s,
+ uint8_t power_mode)
+{
+ int val;
+
+ val = (BMP280_OVERSAMP_TEMP << 5) +
+ (BMP280_OVERSAMP_PRES << 2) + power_mode;
+
+ return raw_write8(s->port, s->addr, BMP280_CTRL_MEAS_REG, val);
+}
+
+/*
+ * bmp280_init() - Used to initialize barometer with default config
+ *
+ * @return results of bus communication function
+ * @retval 0 -> Success
+ */
+
+static int bmp280_init(const struct motion_sensor_t *s)
+{
+ int val, ret;
+
+ if (!s)
+ return EC_ERROR_INVAL;
+
+ /* Read chip id */
+ ret = raw_read8(s->port, s->addr,
+ BMP280_CHIP_ID_REG, &val);
+ if (ret)
+ return ret;
+
+ if (val != BMP280_CHIP_ID)
+ return EC_ERROR_INVAL;
+
+ /* set power mode */
+ ret = bmp280_set_power_mode(s, BMP280_SLEEP_MODE);
+ if (ret)
+ return ret;
+
+ /* Read bmp280 calibration parameter */
+ return bmp280_get_calib_param(s);
+}
+
+static int bmp280_read(const struct motion_sensor_t *s, vector_3_t v)
+{
+ int ret, pres;
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+
+ /* Sensor in sleep mode */
+ if (!data->rate)
+ return EC_ERROR_INVAL;
+
+ ret = bmp280_read_uncomp_pressure(s, &pres);
+
+ if (ret)
+ return ret;
+
+ v[0] = bmp280_compensate_pressure(s, pres);
+ v[1] = v[2] = 0;
+
+ return EC_SUCCESS;
+}
+
+/* Set desired standby duration in ms */
+static int bmp280_set_data_rate(const struct motion_sensor_t *s, int rate,
+ int roundup)
+{
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+ int durn, i, ret;
+
+ if (rate < 0)
+ return EC_ERROR_INVAL;
+
+ if (!rate) {
+ /* Set to sleep mode */
+ data->rate = 0;
+ return bmp280_set_power_mode(s, BMP280_SLEEP_MODE);
+ }
+
+ /* reset power mode, waking from sleep */
+ if (!data->rate) {
+ ret = bmp280_set_power_mode(s, BMP280_NORMAL_MODE);
+ if (ret)
+ return ret;
+ }
+
+ durn = BMP280_STANDBY_CNT-1;
+ for (i = 0; i < BMP280_STANDBY_CNT-1; i++) {
+ if (rate == (standby_durn[i] + BMP280_COMPUTE_TIME) ||
+ rate < (standby_durn[i] + BMP280_COMPUTE_TIME)) {
+ durn = i;
+ break;
+ } else if (rate > (standby_durn[i] + BMP280_COMPUTE_TIME) &&
+ rate < (standby_durn[i+1] + BMP280_COMPUTE_TIME)) {
+ durn = roundup ? i+1 : i;
+ break;
+ }
+ }
+ return bmp280_set_standby_durn(s, durn);
+}
+
+static int bmp280_get_data_rate(const struct motion_sensor_t *s)
+{
+ struct bmp280_drv_data_t *data = BMP280_GET_DATA(s);
+
+ return data->rate;
+}
+
+struct bmp280_drv_data_t bmp280_drv_data;
+
+const struct accelgyro_drv bmp280_drv = {
+ .init = bmp280_init,
+ .read = bmp280_read,
+ .set_data_rate = bmp280_set_data_rate,
+ .get_data_rate = bmp280_get_data_rate,
+};
diff --git a/driver/baro_bmp280.h b/driver/baro_bmp280.h
new file mode 100644
index 0000000000..586ed6677b
--- /dev/null
+++ b/driver/baro_bmp280.h
@@ -0,0 +1,205 @@
+/* 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.
+ */
+/** \mainpage
+*
+****************************************************************************
+* Copyright (C) 2012 - 2015 Bosch Sensortec GmbH
+*
+* File : bmp280.h
+*
+* Date : 2015/03/27
+*
+* Revision : 2.0.4(Pressure and Temperature compensation code revision is 1.1)
+*
+* Usage: Sensor Driver for BMP280 sensor
+*
+****************************************************************************
+*
+* \section License
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* Redistributions in binary form must reproduce the above copyright
+* notice, this list of conditions and the following disclaimer in the
+* documentation and/or other materials provided with the distribution.
+*
+* Neither the name of the copyright holder nor the names of the
+* contributors may be used to endorse or promote products derived from
+* this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+* OR CONTRIBUTORS BE LIABLE FOR ANY
+* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS
+* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+*
+* The information provided is believed to be accurate and reliable.
+* The copyright holder assumes no responsibility
+* for the consequences of use
+* of such information nor for any infringement of patents or
+* other rights of third parties which may result from its use.
+* No license is granted by implication or otherwise under any patent or
+* patent rights of the copyright holder.
+**************************************************************************/
+/* BMP280 pressure and temperature module for Chrome EC */
+
+#ifndef __CROS_EC_BARO_BMP280_H
+#define __CROS_EC_BARO_BMP280_H
+
+/*
+ * The addr field of barometer_sensor for I2C:
+ *
+ * +-------------------------------+---+
+ * | 7 bit i2c address | 0 |
+ * +-------------------------------+---+
+ */
+
+/*
+ * Bit 1 of 7-bit address: 0 - If SDO is connected to GND
+ * Bit 1 of 7-bit address: 1 - If SDO is connected to Vddio
+ */
+#define BMP280_I2C_ADDRESS1 ((0x76) << 1)
+#define BMP280_I2C_ADDRESS2 ((0x77) << 1)
+/*
+ * CHIP ID
+ */
+#define BMP280_CHIP_ID 0x58
+/************************************************/
+/* CALIBRATION PARAMETERS DEFINITION */
+/************************************************/
+
+#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG 0x88
+
+/************************************************/
+/* REGISTER ADDRESS DEFINITION */
+/************************************************/
+#define BMP280_CHIP_ID_REG 0xD0
+#define BMP280_RST_REG 0xE0 /*Softreset Register */
+#define BMP280_STAT_REG 0xF3 /*Status Register */
+#define BMP280_CTRL_MEAS_REG 0xF4 /*Ctrl Measure Register */
+#define BMP280_CONFIG_REG 0xF5 /*Configuration Register */
+#define BMP280_PRESSURE_MSB_REG 0xF7 /*Pressure MSB Register */
+#define BMP280_PRESSURE_LSB_REG 0xF8 /*Pressure LSB Register */
+#define BMP280_PRESSURE_XLSB_REG 0xF9 /*Pressure XLSB Register */
+/************************************************/
+/* POWER MODE DEFINITION */
+/************************************************/
+/* Sensor Specific constants */
+#define BMP280_SLEEP_MODE 0x00
+#define BMP280_FORCED_MODE 0x01
+#define BMP280_NORMAL_MODE 0x03
+#define BMP280_SOFT_RESET_CODE 0xB6
+/************************************************/
+/* STANDBY TIME DEFINITION */
+/************************************************/
+#define BMP280_STANDBY_TIME_1_MS 0x00
+#define BMP280_STANDBY_TIME_63_MS 0x01
+#define BMP280_STANDBY_TIME_125_MS 0x02
+#define BMP280_STANDBY_TIME_250_MS 0x03
+#define BMP280_STANDBY_TIME_500_MS 0x04
+#define BMP280_STANDBY_TIME_1000_MS 0x05
+#define BMP280_STANDBY_TIME_2000_MS 0x06
+#define BMP280_STANDBY_TIME_4000_MS 0x07
+/************************************************/
+/* OVERSAMPLING DEFINITION */
+/************************************************/
+#define BMP280_OVERSAMP_SKIPPED 0x00
+#define BMP280_OVERSAMP_1X 0x01
+#define BMP280_OVERSAMP_2X 0x02
+#define BMP280_OVERSAMP_4X 0x03
+#define BMP280_OVERSAMP_8X 0x04
+#define BMP280_OVERSAMP_16X 0x05
+/************************************************/
+/* DEFINITIONS FOR ARRAY SIZE OF DATA */
+/************************************************/
+#define BMP280_PRESSURE_DATA_SIZE 3
+#define BMP280_DATA_FRAME_SIZE 6
+#define BMP280_CALIB_DATA_SIZE 24
+/*******************************************************/
+/* SAMPLING PERIOD COMPUTATION CONSTANT */
+/*******************************************************/
+#define BMP280_STANDBY_CNT 8
+#define T_INIT_MAX (20) /* (20/16 = 1.25ms) */
+#define T_MEASURE_PER_OSRS_MAX (37) /* (37/16 = 2.31ms) */
+#define T_SETUP_PRESSURE_MAX (10) /* (10/16 = 0.62ms) */
+
+/*
+ * This is the measurement time required for pressure and temp
+ */
+#define BMP280_COMPUTE_TIME \
+ ((T_INIT_MAX + T_MEASURE_PER_OSRS_MAX * \
+ (((1 << BMP280_OVERSAMP_TEMP) >> 1) + \
+ ((1 << BMP280_OVERSAMP_PRES) >> 1)) + \
+ (BMP280_OVERSAMP_PRES ? T_SETUP_PRESSURE_MAX : 0) + 15) / 16)
+
+/*
+ * These values are selected as per Bosch recommendation for
+ * standard handheld devices, with temp sensor not being used
+ */
+#define BMP280_OVERSAMP_PRES BMP280_OVERSAMP_4X
+#define BMP280_OVERSAMP_TEMP BMP280_OVERSAMP_SKIPPED
+/*******************************************************/
+/* GET DRIVER DATA */
+/*******************************************************/
+#define BMP280_GET_DATA(_s) \
+ ((struct bmp280_drv_data_t *)(_s)->drv_data)
+/**************************************************************/
+/* STRUCTURE and ENUM DEFINITIONS */
+/**************************************************************/
+
+/*
+ * struct bmp280_calib_param_t - Holds all device specific
+ * calibration parameters
+ *
+ * @dig_T1 to dig_T3: calibration Temp data
+ * @dig_P1 to dig_P9: calibration Pressure data
+ * @t_fine: calibration t_fine data
+ *
+ */
+struct bmp280_calib_param_t {
+ uint16_t dig_T1;
+ int16_t dig_T2;
+ int16_t dig_T3;
+ uint16_t dig_P1;
+ int16_t dig_P2;
+ int16_t dig_P3;
+ int16_t dig_P4;
+ int16_t dig_P5;
+ int16_t dig_P6;
+ int16_t dig_P7;
+ int16_t dig_P8;
+ int16_t dig_P9;
+
+ int32_t t_fine;
+};
+
+/*
+ * struct bmp280_t - This structure holds BMP280 initialization parameters
+ * @calib_param: calibration data
+ * @rate: rate set
+ */
+struct bmp280_drv_data_t {
+
+ struct bmp280_calib_param_t calib_param;
+ int rate;
+};
+
+extern const struct accelgyro_drv bmp280_drv;
+extern struct bmp280_drv_data_t bmp280_drv_data;
+#endif
diff --git a/driver/build.mk b/driver/build.mk
index 1458874864..514de8cc50 100644
--- a/driver/build.mk
+++ b/driver/build.mk
@@ -22,6 +22,9 @@ driver-$(CONFIG_ALS_ISL29035)+=als_isl29035.o
driver-$(CONFIG_ALS_OPT3001)+=als_opt3001.o
driver-$(CONFIG_ALS_SI114X)+=als_si114x.o
+#Barometers
+driver-$(CONFIG_BARO_BMP280)+=baro_bmp280.o
+
# Batteries
driver-$(CONFIG_BATTERY_BQ20Z453)+=battery/bq20z453.o
driver-$(CONFIG_BATTERY_BQ27541)+=battery/bq27541.o
diff --git a/include/config.h b/include/config.h
index a315d1c15b..86964d1617 100644
--- a/include/config.h
+++ b/include/config.h
@@ -57,6 +57,9 @@
#undef CONFIG_ACCELGYRO_LSM6DS0
#undef CONFIG_ACCELGYRO_BMI160
+/* Specify barometer attached */
+#undef CONFIG_BARO_BMP280
+
/*
* Use the old standard reference frame for accelerometers. The old
* reference frame is:
diff --git a/include/ec_commands.h b/include/ec_commands.h
index 4f5b130833..c1abb72b6b 100644
--- a/include/ec_commands.h
+++ b/include/ec_commands.h
@@ -1795,6 +1795,7 @@ enum motionsensor_type {
MOTIONSENSE_TYPE_PROX = 3,
MOTIONSENSE_TYPE_LIGHT = 4,
MOTIONSENSE_TYPE_ACTIVITY = 5,
+ MOTIONSENSE_TYPE_BARO = 6,
MOTIONSENSE_TYPE_MAX,
};
@@ -1816,6 +1817,7 @@ enum motionsensor_chip {
MOTIONSENSE_CHIP_KX022 = 6,
MOTIONSENSE_CHIP_L3GD20H = 7,
MOTIONSENSE_CHIP_BMA255 = 8,
+ MOTIONSENSE_CHIP_BMP280 = 9,
};
struct ec_response_motion_sensor_data {